Skip to content

Commit 5f6fd85

Browse files
author
AndyZe
committed
Add move_group launch file
1 parent 458b60d commit 5f6fd85

File tree

1 file changed

+111
-0
lines changed

1 file changed

+111
-0
lines changed
Lines changed: 111 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,111 @@
1+
import os
2+
import yaml
3+
from launch import LaunchDescription
4+
from launch_ros.actions import Node
5+
from ament_index_python.packages import get_package_share_directory
6+
7+
def load_file(package_name, file_path):
8+
package_path = get_package_share_directory(package_name)
9+
absolute_file_path = os.path.join(package_path, file_path)
10+
11+
try:
12+
with open(absolute_file_path, 'r') as file:
13+
return file.read()
14+
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
15+
return None
16+
17+
def load_yaml(package_name, file_path):
18+
package_path = get_package_share_directory(package_name)
19+
absolute_file_path = os.path.join(package_path, file_path)
20+
21+
try:
22+
with open(absolute_file_path, 'r') as file:
23+
return yaml.safe_load(file)
24+
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
25+
return None
26+
27+
28+
def generate_launch_description():
29+
30+
# planning_context
31+
robot_description_config = load_file('ur_description', 'urdf/ur5.urdf.xacro')
32+
robot_description = {'robot_description' : robot_description_config}
33+
34+
robot_description_semantic_config = load_file('ur5_moveit_config', 'config/ur5.srdf')
35+
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config}
36+
37+
kinematics_yaml = load_yaml('ur5_moveit_config', 'config/kinematics.yaml')
38+
robot_description_kinematics = { 'robot_description_kinematics' : kinematics_yaml }
39+
40+
# Planning Functionality
41+
ompl_planning_pipeline_config = { 'move_group' : {
42+
'planning_plugin' : 'ompl_interface/OMPLPlanner',
43+
'request_adapters' : """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""" ,
44+
'start_state_max_bounds_error' : 0.1 } }
45+
ompl_planning_yaml = load_yaml('ur5_moveit_config', 'config/ompl_planning.yaml')
46+
ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml)
47+
48+
# Trajectory Execution Functionality
49+
controllers_yaml = load_yaml('run_move_group', 'config/controllers.yaml')
50+
moveit_controllers = { 'moveit_simple_controller_manager' : controllers_yaml,
51+
'moveit_controller_manager': 'moveit_simple_controller_manager/MoveItSimpleControllerManager'}
52+
53+
trajectory_execution = {'moveit_manage_controllers': True,
54+
'trajectory_execution.allowed_execution_duration_scaling': 1.2,
55+
'trajectory_execution.allowed_goal_duration_margin': 0.5,
56+
'trajectory_execution.allowed_start_tolerance': 0.01}
57+
58+
planning_scene_monitor_parameters = {"publish_planning_scene": True,
59+
"publish_geometry_updates": True,
60+
"publish_state_updates": True,
61+
"publish_transforms_updates": True}
62+
63+
# Start the actual move_group node/action server
64+
run_move_group_node = Node(package='moveit_ros_move_group',
65+
executable='move_group',
66+
output='screen',
67+
parameters=[robot_description,
68+
robot_description_semantic,
69+
kinematics_yaml,
70+
ompl_planning_pipeline_config,
71+
trajectory_execution,
72+
moveit_controllers,
73+
planning_scene_monitor_parameters])
74+
75+
# RViz
76+
rviz_config_file = get_package_share_directory('ur_description') + "/config/view_robot.rviz"
77+
rviz_node = Node(package='rviz2',
78+
executable='rviz2',
79+
name='rviz2',
80+
output='log',
81+
arguments=['-d', rviz_config_file],
82+
parameters=[robot_description,
83+
robot_description_semantic,
84+
ompl_planning_pipeline_config,
85+
kinematics_yaml])
86+
87+
# Static TF
88+
static_tf = Node(package='tf2_ros',
89+
executable='static_transform_publisher',
90+
name='static_transform_publisher',
91+
output='log',
92+
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'world', 'base_link'])
93+
94+
# Publish TF
95+
robot_state_publisher = Node(package='robot_state_publisher',
96+
executable='robot_state_publisher',
97+
name='robot_state_publisher',
98+
output='both',
99+
parameters=[robot_description])
100+
101+
# TODO(andyz): fake_joint_driver conflicts with the current ros2_controller commits
102+
# # Fake joint driver
103+
# fake_joint_driver_node = Node(package='fake_joint_driver',
104+
# executable='fake_joint_driver_node',
105+
# parameters=[{'controller_name': 'panda_arm_controller'},
106+
# os.path.join(get_package_share_directory("run_move_group"), "config", "panda_controllers.yaml"),
107+
# os.path.join(get_package_share_directory("run_move_group"), "config", "start_positions.yaml"),
108+
# robot_description]
109+
# )
110+
111+
return LaunchDescription([ rviz_node, static_tf, robot_state_publisher, run_move_group_node ])

0 commit comments

Comments
 (0)