feat(les5): Add basic moveit2 robot arm

This commit is contained in:
2025-10-02 11:45:13 +02:00
parent 4531e8166a
commit 277b07c61e
33 changed files with 1079 additions and 1 deletions

View File

@@ -26,6 +26,9 @@ if type -q bass
if test -f ./install/setup.bash
bass source ./install/setup.bash
end
if test -f ~/Documents/ws_moveit/install/setup.bash
bass source ~/Documents/ws_moveit/install/setup.bash
end
else
echo (set_color red)"Error: bass is required for ROS2 environment. Install with: fisher install edc/bass"(set_color normal)
return 1

Binary file not shown.

View File

@@ -0,0 +1,409 @@
Panels:
- Class: rviz_common/Displays
Help Height: 0
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /RobotModel1/Description Topic1
- /MotionPlanning1/Scene Robot1/Links1
- /MotionPlanning1/Scene Robot1/Links1/link_51
Splitter Ratio: 0.5
Tree Height: 233
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_5:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Mass Properties:
Inertia: false
Mass: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz_default_plugins/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
gripper_left:
Value: true
gripper_right:
Value: true
link_1:
Value: true
link_2:
Value: true
link_3:
Value: true
link_4:
Value: true
link_5:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: false
Tree:
base_link:
link_1:
link_2:
link_3:
link_4:
link_5:
gripper_left:
{}
gripper_right:
{}
Update Interval: 0
Value: true
- Acceleration_Scaling_Factor: 0.1
Class: moveit_rviz_plugin/MotionPlanning
Enabled: true
Move Group Namespace: ""
MoveIt_Allow_Approximate_IK: false
MoveIt_Allow_External_Program: false
MoveIt_Allow_Replanning: false
MoveIt_Allow_Sensor_Positioning: false
MoveIt_Planning_Attempts: 10
MoveIt_Planning_Time: 5
MoveIt_Use_Cartesian_Path: false
MoveIt_Use_Constraint_Aware_IK: false
MoveIt_Workspace:
Center:
X: 0
Y: 0
Z: 0
Size:
X: 2
Y: 2
Z: 2
Name: MotionPlanning
Planned Path:
Color Enabled: false
Interrupt Display: false
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_5:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Loop Animation: false
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Show Robot Collision: false
Show Robot Visual: true
Show Trail: false
State Display Time: 3x
Trail Step Size: 1
Trajectory Topic: /display_planned_path
Use Sim Time: false
Planning Metrics:
Payload: 1
Show Joint Torques: false
Show Manipulability: false
Show Manipulability Index: false
Show Weight Limit: false
TextHeight: 0.07999999821186066
Planning Request:
Colliding Link Color: 255; 0; 0
Goal State Alpha: 1
Goal State Color: 250; 128; 0
Interactive Marker Size: 0
Joint Violation Color: 255; 0; 255
Planning Group: gripper
Query Goal State: true
Query Start State: false
Show Workspace: false
Start State Alpha: 1
Start State Color: 0; 255; 0
Planning Scene Topic: /monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 0.8999999761581421
Scene Color: 50; 230; 50
Scene Display Time: 0.009999999776482582
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
Scene Robot:
Attached Body Color: 150; 50; 150
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_5:
Alpha: 1
Show Axes: false
Show Trail: true
Value: true
Robot Alpha: 1
Show Robot Collision: false
Show Robot Visual: true
Value: true
Velocity_Scaling_Factor: 0.1
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 3.4432098865509033
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -0.299166202545166
Y: -0.3069069981575012
Z: 0.8311280012130737
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.3503985106945038
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.5403982400894165
Saved: ~
Window Geometry:
"":
collapsed: false
" - Trajectory Slider":
collapsed: false
Displays:
collapsed: false
Height: 854
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001ee000002b4fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000126000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffbffffffff0100000169000001880000017d00ffffff000000010000010f000002a3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000048000002a3000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004bd00000042fc0100000002fb0000000800540069006d00650100000000000004bd0000026f00fffffffb0000000800540069006d00650100000000000004500000000000000000000002c9000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1213
X: 400
Y: 84

View File

@@ -0,0 +1,12 @@
cmake_minimum_required(VERSION 3.8)
project(robot_bringup)
find_package(ament_cmake REQUIRED)
# Install directories
install(
DIRECTORY launch config
DESTINATION share/${PROJECT_NAME}
)
ament_package()

View File

@@ -0,0 +1,32 @@
controller_manager: # config file used by ros2_control
ros__parameters:
update_rate: 1 # Hz (Limit this a bit)
arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
gripper_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
arm_controller:
ros__parameters:
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
command_interfaces:
- position
state_interfaces:
- position
allow_nonzero_velocity_at_trajectory_end: true
gripper_controller:
ros__parameters:
joints:
- joint_6
command_interfaces:
- position
state_interfaces:
- position
allow_nonzero_velocity_at_trajectory_end: true

View File

@@ -0,0 +1,18 @@
<launch>
<let name="urdf_path"
value="$(find-pkg-share robot_description)/urdf/skyentific_robot.urdf.xacro" />
<let name="rviz_config_path"
value="$(find-pkg-share robot_bringup)/config/robot_moveit.rviz" />
<node pkg="robot_state_publisher" exec="robot_state_publisher">
<param name="robot_description"
value="$(command 'xacro $(var urdf_path)')" />
</node>
<node pkg="controller_manager" exec="ros2_control_node">
<param from="$(find-pkg-share robot_bringup)/config/skyentific_robot_controllers.yaml" />
</node>
<node pkg="controller_manager" exec="spawner" args="joint_state_broadcaster" />
<node pkg="controller_manager" exec="spawner" args="arm_controller" />
<node pkg="controller_manager" exec="spawner" args="gripper_controller" />
<include file="$(find-pkg-share robot_moveit_config)/launch/move_group.launch.py" />
<node pkg="rviz2" exec="rviz2" output="screen" args="-d $(var rviz_config_path)" />
</launch>

View File

@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>robot_bringup</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="wessel@go2it.eu">wessel</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,20 @@
cmake_minimum_required(VERSION 3.8)
project(robot_commander)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED) # find dependencies
find_package(rclcpp REQUIRED)
find_package(moveit_ros_planning_interface REQUIRED)
add_executable(test_moveit src/test_moveit.cpp)
ament_target_dependencies(test_moveit rclcpp moveit_ros_planning_interface)
install(TARGETS
test_moveit
DESTINATION lib/${PROJECT_NAME}/
)
ament_package()

View File

@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>robot_commander</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="wessel@go2it.eu">wessel</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>moveit_ros_planning_interface</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,36 @@
#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.hpp>
int main(int argc, char **argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared<rclcpp::Node>("test_moveit");
// we need a new thread at this point to spin node
// - thread with instructions to move the robot
// - thread to spin the node
// create single threaded executor
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
auto spinner = std::thread([&executor]() { executor.spin(); });
auto arm = moveit::planning_interface::MoveGroupInterface(node, "arm");
arm.setMaxVelocityScalingFactor(1.0);
arm.setMaxAccelerationScalingFactor(1.0);
auto gripper = moveit::planning_interface::MoveGroupInterface(node, "gripper");
arm.setStartStateToCurrentState();
arm.setNamedTarget("pose_1");
moveit::planning_interface::MoveGroupInterface::Plan plan1;
bool success1 = (arm.plan(plan1) == moveit::core::MoveItErrorCode::SUCCESS);
if (success1) {
arm.execute(plan1);
}
rclcpp::shutdown();
spinner.join();
return 0;
}

View File

@@ -10,6 +10,30 @@
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_2">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_3">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_4">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_5">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</ros2_control>
<ros2_control name="Gripper" type="system">

View File

@@ -0,0 +1,23 @@
moveit_setup_assistant_config:
urdf:
package: robot_description
relative_path: urdf/skyentific_robot.urdf.xacro
srdf:
relative_path: config/skyentific_robot.srdf
package_settings:
author_name: Wessel T
author_email: contact@wessel.gg
generated_timestamp: 1759396334
control_xacro:
command:
- position
state:
- position
modified_urdf:
xacros:
- control_xacro
control_xacro:
command:
- position
state:
- position

View File

@@ -0,0 +1,16 @@
cmake_minimum_required(VERSION 3.22)
project(robot_moveit_config)
find_package(ament_cmake REQUIRED)
ament_package()
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/launch")
install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
PATTERN "setup_assistant.launch" EXCLUDE)
endif()
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME})

View File

@@ -0,0 +1,9 @@
# Default initial positions for skyentific_robot's ros2_control fake system
initial_positions:
joint_1: 0
joint_2: 0
joint_3: 0
joint_4: 0
joint_5: 0
joint_6: 0

View File

@@ -0,0 +1,45 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
joint_1:
has_velocity_limits: true
max_velocity: 10.0
has_acceleration_limits: true
max_acceleration: 5.0
joint_2:
has_velocity_limits: true
max_velocity: 10.0
has_acceleration_limits: true
max_acceleration: 5.0
joint_3:
has_velocity_limits: true
max_velocity: 100.0
has_acceleration_limits: true
max_acceleration: 50.0
joint_4:
has_velocity_limits: true
max_velocity: 100.0
has_acceleration_limits: true
max_acceleration: 50.0
joint_5:
has_velocity_limits: true
max_velocity: 100.0
has_acceleration_limits: true
max_acceleration: 50.0
joint_6:
has_velocity_limits: true
max_velocity: 100.0
has_acceleration_limits: true
max_acceleration: 50.0
joint_7:
has_velocity_limits: true
max_velocity: 100.0
has_acceleration_limits: true
max_acceleration: 50.0

View File

@@ -0,0 +1,4 @@
arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001

View File

@@ -0,0 +1,51 @@
Panels:
- Class: rviz_common/Displays
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
- Class: rviz_common/Help
Name: Help
- Class: rviz_common/Views
Name: Views
Visualization Manager:
Displays:
- Class: rviz_default_plugins/Grid
Name: Grid
Value: true
- Class: moveit_rviz_plugin/MotionPlanning
Name: MotionPlanning
Planned Path:
Loop Animation: true
State Display Time: 0.05 s
Trajectory Topic: display_planned_path
Planning Scene Topic: monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Robot:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: base_link
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 2.0
Focal Point:
X: -0.1
Y: 0.25
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: base_link
Yaw: -0.623
Window Geometry:
Height: 975
QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Width: 1200

View File

@@ -0,0 +1,25 @@
# MoveIt uses this configuration for controller management
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
moveit_simple_controller_manager:
controller_names:
- arm_controller
- gripper_controller
arm_controller:
type: FollowJointTrajectory
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
action_ns: follow_joint_trajectory
default: true
gripper_controller:
type: FollowJointTrajectory
joints:
- joint_6
action_ns: follow_joint_trajectory
default: true

View File

@@ -0,0 +1,6 @@
# Limits for the Pilz planner
cartesian_limits:
max_trans_vel: 1.0
max_trans_acc: 2.25
max_trans_dec: -5.0
max_rot_vel: 1.57

View File

@@ -0,0 +1,38 @@
# This config file is used by ros2_control
controller_manager:
ros__parameters:
update_rate: 100 # Hz
arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
gripper_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
arm_controller:
ros__parameters:
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
command_interfaces:
- position
state_interfaces:
- position
allow_nonzero_velocity_at_trajectory_end: true
gripper_controller:
ros__parameters:
joints:
- joint_6
command_interfaces:
- position
state_interfaces:
- position
allow_nonzero_velocity_at_trajectory_end: true

View File

@@ -0,0 +1,23 @@
sensors:
- kinect_pointcloud
- kinect_depthimage
kinect_pointcloud:
filtered_cloud_topic: filtered_cloud
max_range: 5.0
max_update_rate: 1.0
padding_offset: 0.1
padding_scale: 1.0
point_cloud_topic: /head_mount_kinect/depth_registered/points
point_subsample: 1
sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
kinect_depthimage:
far_clipping_plane_distance: 5.0
filtered_cloud_topic: filtered_cloud
image_topic: /head_mount_kinect/depth_registered/image_raw
max_update_rate: 1.0
near_clipping_plane_distance: 0.3
padding_offset: 0.03
padding_scale: 4.0
queue_size: 5
sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
shadow_threshold: 0.2

View File

@@ -0,0 +1,50 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="skyentific_robot_ros2_control" params="name initial_positions_file">
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
<ros2_control name="${name}" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
</hardware>
<joint name="joint_1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_1']}</param>
</state_interface>
</joint>
<joint name="joint_2">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_2']}</param>
</state_interface>
</joint>
<joint name="joint_3">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_3']}</param>
</state_interface>
</joint>
<joint name="joint_4">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_4']}</param>
</state_interface>
</joint>
<joint name="joint_5">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_5']}</param>
</state_interface>
</joint>
<joint name="joint_6">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_6']}</param>
</state_interface>
</joint>
</ros2_control>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,73 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="skyentific_robot">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="arm">
<joint name="virtual_joint"/>
<joint name="joint_1"/>
<joint name="joint_2"/>
<joint name="joint_3"/>
<joint name="joint_4"/>
<joint name="joint_5"/>
</group>
<group name="gripper">
<joint name="joint_6"/>
<joint name="joint_7"/>
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="arm">
<joint name="joint_1" value="0"/>
<joint name="joint_2" value="0"/>
<joint name="joint_3" value="0"/>
<joint name="joint_4" value="0"/>
<joint name="joint_5" value="0"/>
</group_state>
<group_state name="closed" group="gripper">
<joint name="joint_6" value="-0.0119"/>
</group_state>
<group_state name="open" group="gripper">
<joint name="joint_6" value="0.0148"/>
</group_state>
<group_state name="pose_1" group="arm">
<joint name="joint_1" value="-0.5235"/>
<joint name="joint_2" value="-0.786"/>
<joint name="joint_3" value="-0.786"/>
<joint name="joint_4" value="-1.571"/>
<joint name="joint_5" value="-0.5235"/>
</group_state>
<group_state name="pose_2" group="arm">
<joint name="joint_1" value="0.5235"/>
<joint name="joint_2" value="-0.786"/>
<joint name="joint_3" value="-0.786"/>
<joint name="joint_4" value="-1.571"/>
<joint name="joint_5" value="0.5235"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="gripper" parent_link="link_5" group="gripper" parent_group="arm"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="base_link"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="gripper_left" link2="link_2" reason="Never"/>
<disable_collisions link1="gripper_left" link2="link_3" reason="Never"/>
<disable_collisions link1="gripper_left" link2="link_4" reason="Never"/>
<disable_collisions link1="gripper_left" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="gripper_right" link2="link_2" reason="Never"/>
<disable_collisions link1="gripper_right" link2="link_3" reason="Never"/>
<disable_collisions link1="gripper_right" link2="link_4" reason="Never"/>
<disable_collisions link1="gripper_right" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_4" reason="Never"/>
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Default"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
</robot>

View File

@@ -0,0 +1,14 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="skyentific_robot">
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
<!-- Import skyentific_robot urdf file -->
<xacro:include filename="$(find robot_description)/urdf/skyentific_robot.urdf.xacro" />
<!-- Import control_xacro -->
<xacro:include filename="skyentific_robot.ros2_control.xacro" />
<xacro:skyentific_robot_ros2_control name="FakeSystem" initial_positions_file="$(arg initial_positions_file)"/>
</robot>

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_demo_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_demo_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_move_group_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_move_group_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_moveit_rviz_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_moveit_rviz_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_rsp_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_rsp_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_setup_assistant_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_setup_assistant_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_spawn_controllers_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_spawn_controllers_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_static_virtual_joint_tfs_launch(moveit_config)

View File

@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_warehouse_db_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("skyentific_robot", package_name="robot_moveit_config").to_moveit_configs()
return generate_warehouse_db_launch(moveit_config)

View File

@@ -0,0 +1,52 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>robot_moveit_config</name>
<version>0.3.0</version>
<description>
An automatically generated package with all the configuration and launch files for using the skyentific_robot with the MoveIt Motion Planning Framework
</description>
<maintainer email="contact@wessel.gg">Wessel T</maintainer>
<license>BSD-3-Clause</license>
<url type="website">http://moveit.ros.org/</url>
<url type="bugtracker">https://github.com/moveit/moveit2/issues</url>
<url type="repository">https://github.com/moveit/moveit2</url>
<author email="contact@wessel.gg">Wessel T</author>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_kinematics</exec_depend>
<exec_depend>moveit_planners</exec_depend>
<exec_depend>moveit_simple_controller_manager</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>xacro</exec_depend>
<!-- The next 2 packages are required for the gazebo simulation.
We don't include them by default to prevent installing gazebo and all its dependencies. -->
<!-- <exec_depend>joint_trajectory_controller</exec_depend> -->
<!-- <exec_depend>gazebo_ros_control</exec_depend> -->
<exec_depend>controller_manager</exec_depend>
<exec_depend>moveit_configs_utils</exec_depend>
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_ros_visualization</exec_depend>
<exec_depend>moveit_ros_warehouse</exec_depend>
<exec_depend>moveit_setup_assistant</exec_depend>
<exec_depend>robot_description</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>rviz_common</exec_depend>
<exec_depend>rviz_default_plugins</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>warehouse_ros_mongo</exec_depend>
<exec_depend>xacro</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>