Skip to content

Commit cb6ab8e

Browse files
committed
Adapt launch files to new organization of configuration and urdf files.
1 parent d71f2d7 commit cb6ab8e

File tree

4 files changed

+153
-46
lines changed

4 files changed

+153
-46
lines changed

ur5_moveit_config/launch/run_move_group.launch.py

Lines changed: 35 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,41 @@ def load_yaml(package_name, file_path):
2828
def generate_launch_description():
2929

3030
# planning_context
31-
robot_description_config = load_file('ur_description', 'urdf/ur5.urdf.xacro')
32-
robot_description = {'robot_description' : robot_description_config}
31+
# set ur robot
32+
robot_name = 'ur5'
33+
34+
# <robot_name> parameters files
35+
joint_limits_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
36+
robot_name, 'joint_limits.yaml')
37+
kinematics_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
38+
robot_name, 'default_kinematics.yaml')
39+
physical_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
40+
robot_name, 'physical_parameters.yaml')
41+
visual_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
42+
robot_name, 'visual_parameters.yaml')
43+
44+
# common parameters
45+
# If True, enable the safety limits controller
46+
safety_limits = False
47+
# The lower/upper limits in the safety controller
48+
safety_pos_margin = 0.15
49+
# Used to set k position in the safety controller
50+
safety_k_position = 20
51+
52+
# Get URDF via xacro
53+
robot_description_path = os.path.join(get_package_share_directory('ur_description'), 'urdf', 'ur.xacro')
54+
55+
robot_description_config = xacro.process_file(robot_description_path,
56+
mappings={'joint_limit_params': joint_limits_params,
57+
'kinematics_params': kinematics_params,
58+
'physical_params': physical_params,
59+
'visual_params': visual_params,
60+
'safety_limits': str(safety_limits).lower(),
61+
'safety_pos_margin': str(safety_pos_margin),
62+
'safety_k_position': str(safety_k_position)}
63+
)
64+
65+
robot_description = {'robot_description': robot_description_config.toxml()}
3366

3467
robot_description_semantic_config = load_file('ur5_moveit_config', 'config/ur5.srdf')
3568
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config}

ur_ros2_control_demos/launch/ur5e_run_move_group.launch.py

Lines changed: 38 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -30,11 +30,28 @@ def load_yaml(package_name, file_path):
3030

3131
def generate_launch_description():
3232

33-
# planning_context
34-
robot_description_path = os.path.join(
35-
get_package_share_directory('ur_description'),
36-
'urdf',
37-
'ur5_robot.urdf.xacro')
33+
# set ur robot
34+
robot_name = 'ur5e'
35+
36+
# <robot_name> parameters files
37+
joint_limits_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
38+
robot_name, 'joint_limits.yaml')
39+
kinematics_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
40+
robot_name, 'default_kinematics.yaml')
41+
physical_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
42+
robot_name, 'physical_parameters.yaml')
43+
visual_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
44+
robot_name, 'visual_parameters.yaml')
45+
46+
# common parameters
47+
# If True, enable the safety limits controller
48+
safety_limits = False
49+
# The lower/upper limits in the safety controller
50+
safety_pos_margin = 0.15
51+
# Used to set k position in the safety controller
52+
safety_k_position = 20
53+
54+
use_ros2_control = True
3855

3956
script_filename = os.path.join(
4057
get_package_share_directory('ur_robot_driver'),
@@ -51,30 +68,38 @@ def generate_launch_description():
5168
'resources',
5269
'rtde_output_recipe.txt')
5370

54-
use_ros2_control = True
71+
# Get URDF via xacro
72+
robot_description_path = os.path.join(get_package_share_directory('ur_description'), 'urdf', 'ur.xacro')
5573

5674
robot_description_config = xacro.process_file(robot_description_path,
57-
mappings={'use_ros2_control': 'true' if use_ros2_control else 'false',
75+
mappings={'joint_limit_params': joint_limits_params,
76+
'kinematics_params': kinematics_params,
77+
'physical_params': physical_params,
78+
'visual_params': visual_params,
79+
'safety_limits': str(safety_limits).lower(),
80+
'safety_pos_margin': str(safety_pos_margin),
81+
'safety_k_position': str(safety_k_position),
82+
'use_ros2_control': str(use_ros2_control).lower(),
5883
'script_filename': script_filename,
5984
'input_recipe_filename': input_recipe_filename,
6085
'output_recipe_filename': output_recipe_filename,
6186
'robot_ip': '10.0.1.186'}
62-
)
87+
)
6388

6489
robot_description = {'robot_description': robot_description_config.toxml()}
6590

66-
robot_description_semantic_config = load_file('ur5_moveit_config', 'config/ur5.srdf')
91+
robot_description_semantic_config = load_file(robot_name + '_moveit_config', 'config/' + robot_name + '.srdf')
6792
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config}
6893

69-
kinematics_yaml = load_yaml('ur5_moveit_config', 'config/kinematics.yaml')
94+
kinematics_yaml = load_yaml(robot_name + '_moveit_config', 'config/kinematics.yaml')
7095
robot_description_kinematics = { 'robot_description_kinematics' : kinematics_yaml }
7196

7297
# Planning Functionality
7398
ompl_planning_pipeline_config = { 'move_group' : {
7499
'planning_plugin' : 'ompl_interface/OMPLPlanner',
75100
'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""" ,
76101
'start_state_max_bounds_error' : 0.1 } }
77-
ompl_planning_yaml = load_yaml('ur5_moveit_config', 'config/ompl_planning.yaml')
102+
ompl_planning_yaml = load_yaml(robot_name + '_moveit_config', 'config/ompl_planning.yaml')
78103
ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml)
79104

80105
# Trajectory Execution Functionality
@@ -138,7 +163,7 @@ def generate_launch_description():
138163
{'warehouse_plugin': 'warehouse_ros_mongo::MongoDatabaseConnection'}],
139164
output='screen')
140165

141-
ur5_controller = os.path.join(
166+
ur_controller = os.path.join(
142167
get_package_share_directory('ur_ros2_control_demos'),
143168
'config',
144169
'ur5_system_position_only.yaml'
@@ -147,7 +172,7 @@ def generate_launch_description():
147172
ros2_control_node = Node(
148173
package='controller_manager',
149174
executable='ros2_control_node',
150-
parameters=[robot_description, ur5_controller],
175+
parameters=[robot_description, ur_controller],
151176
output={
152177
'stdout': 'screen',
153178
'stderr': 'screen',

ur_ros2_control_demos/launch/ur5e_servo_server_demo.launch.py

Lines changed: 44 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -29,38 +29,56 @@ def load_yaml(package_name, file_path):
2929

3030
def generate_launch_description():
3131

32-
ur5_controller = os.path.join(
33-
get_package_share_directory('ur_ros2_control_demos'),
34-
'config',
35-
'ur5_system_position_only.yaml'
36-
)
32+
# set ur robot
33+
robot_name = 'ur5e'
34+
35+
# <robot_name> parameters files
36+
joint_limits_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
37+
robot_name, 'joint_limits.yaml')
38+
kinematics_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
39+
robot_name, 'default_kinematics.yaml')
40+
physical_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
41+
robot_name, 'physical_parameters.yaml')
42+
visual_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
43+
robot_name, 'visual_parameters.yaml')
44+
45+
# common parameters
46+
# If True, enable the safety limits controller
47+
safety_limits = False
48+
# The lower/upper limits in the safety controller
49+
safety_pos_margin = 0.15
50+
# Used to set k position in the safety controller
51+
safety_k_position = 20
3752

38-
# Get URDF via xacro
39-
robot_description_path = os.path.join(
40-
get_package_share_directory('ur_description'),
41-
'urdf',
42-
'ur5_robot.urdf.xacro')
53+
use_ros2_control = True
4354

44-
# UR driver configuration files
4555
script_filename = os.path.join(
4656
get_package_share_directory('ur_robot_driver'),
4757
'resources',
4858
'ros_control.urscript')
4959

50-
output_recipe_filename = os.path.join(
60+
input_recipe_filename = os.path.join(
5161
get_package_share_directory('ur_robot_driver'),
5262
'resources',
53-
'rtde_output_recipe.txt')
63+
'rtde_input_recipe.txt')
5464

55-
input_recipe_filename = os.path.join(
65+
output_recipe_filename = os.path.join(
5666
get_package_share_directory('ur_robot_driver'),
5767
'resources',
58-
'rtde_input_recipe.txt')
68+
'rtde_output_recipe.txt')
5969

60-
use_ros2_control = True
70+
# Get URDF via xacro
71+
robot_description_path = os.path.join(get_package_share_directory('ur_description'), 'urdf', 'ur.xacro')
6172

6273
robot_description_config = xacro.process_file(robot_description_path,
63-
mappings={'use_ros2_control': 'true' if use_ros2_control else 'false',
74+
mappings={'joint_limit_params': joint_limits_params,
75+
'kinematics_params': kinematics_params,
76+
'physical_params': physical_params,
77+
'visual_params': visual_params,
78+
'safety_limits': str(safety_limits).lower(),
79+
'safety_pos_margin': str(safety_pos_margin),
80+
'safety_k_position': str(safety_k_position),
81+
'use_ros2_control': str(use_ros2_control).lower(),
6482
'script_filename': script_filename,
6583
'input_recipe_filename': input_recipe_filename,
6684
'output_recipe_filename': output_recipe_filename,
@@ -69,14 +87,19 @@ def generate_launch_description():
6987

7088
robot_description = {'robot_description': robot_description_config.toxml()}
7189

72-
# Get SRDF
73-
robot_description_semantic_config = load_file('ur5_moveit_config', 'config/ur5.srdf')
90+
robot_description_semantic_config = load_file(robot_name + '_moveit_config', 'config/' + robot_name + '.srdf')
7491
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config}
7592

7693
# Get parameters for the Servo node
77-
servo_yaml = load_yaml('ur_ros2_control_demos', 'config/ur5_servo_config.yaml')
94+
servo_yaml = load_yaml('ur_ros2_control_demos', 'config/ur5e_servo_config.yaml')
7895
servo_params = { 'moveit_servo' : servo_yaml }
7996

97+
ur_controller = os.path.join(
98+
get_package_share_directory('ur_ros2_control_demos'),
99+
'config',
100+
'ur5_system_position_only.yaml'
101+
)
102+
80103
# RViz
81104
rviz_config_file = get_package_share_directory('ur_ros2_control_demos') + "/config/rviz/demo_rviz_config.rviz"
82105
rviz_node = Node(package='rviz2',
@@ -114,7 +137,7 @@ def generate_launch_description():
114137
ros2_control_node = Node(
115138
package='controller_manager',
116139
executable='ros2_control_node',
117-
parameters=[robot_description, ur5_controller],
140+
parameters=[robot_description, ur_controller],
118141
output={
119142
'stdout': 'screen',
120143
'stderr': 'screen',

ur_ros2_control_demos/launch/ur5e_system_position_only.launch.py

Lines changed: 36 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -35,11 +35,28 @@ def generate_launch_description():
3535

3636
ld = LaunchDescription()
3737

38-
# Get URDF via xacro
39-
robot_description_path = os.path.join(
40-
get_package_share_directory('ur_description'),
41-
'urdf',
42-
'ur5_robot.urdf.xacro')
38+
# set ur robot
39+
robot_name = 'ur5e'
40+
41+
# <robot_name> parameters files
42+
joint_limits_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
43+
robot_name, 'joint_limits.yaml')
44+
kinematics_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
45+
robot_name, 'default_kinematics.yaml')
46+
physical_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
47+
robot_name, 'physical_parameters.yaml')
48+
visual_params = os.path.join(get_package_share_directory('ur_description'), 'config/' +
49+
robot_name, 'visual_parameters.yaml')
50+
51+
# common parameters
52+
# If True, enable the safety limits controller
53+
safety_limits = False
54+
# The lower/upper limits in the safety controller
55+
safety_pos_margin = 0.15
56+
# Used to set k position in the safety controller
57+
safety_k_position = 20
58+
59+
use_ros2_control = True
4360

4461
script_filename = os.path.join(
4562
get_package_share_directory('ur_robot_driver'),
@@ -56,10 +73,18 @@ def generate_launch_description():
5673
'resources',
5774
'rtde_output_recipe.txt')
5875

59-
use_ros2_control = True
76+
# Get URDF via xacro
77+
robot_description_path = os.path.join(get_package_share_directory('ur_description'), 'urdf', 'ur.xacro')
6078

6179
robot_description_config = xacro.process_file(robot_description_path,
62-
mappings={'use_ros2_control': 'true' if use_ros2_control else 'false',
80+
mappings={'joint_limit_params': joint_limits_params,
81+
'kinematics_params': kinematics_params,
82+
'physical_params': physical_params,
83+
'visual_params': visual_params,
84+
'safety_limits': str(safety_limits).lower(),
85+
'safety_pos_margin': str(safety_pos_margin),
86+
'safety_k_position': str(safety_k_position),
87+
'use_ros2_control': str(use_ros2_control).lower(),
6388
'script_filename': script_filename,
6489
'input_recipe_filename': input_recipe_filename,
6590
'output_recipe_filename': output_recipe_filename,
@@ -68,10 +93,11 @@ def generate_launch_description():
6893

6994
robot_description = {'robot_description': robot_description_config.toxml()}
7095

71-
robot_description_semantic_config = load_file('ur5_moveit_config', 'config/ur5.srdf')
96+
robot_description_semantic_config = load_file(robot_name + '_moveit_config', 'config/' + robot_name + '.srdf')
7297
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config}
7398

74-
ur5_controller = os.path.join(
99+
100+
ur_controller = os.path.join(
75101
get_package_share_directory('ur_ros2_control_demos'),
76102
'config',
77103
'ur5_system_position_only.yaml'
@@ -98,7 +124,7 @@ def generate_launch_description():
98124
ros2_control_node = Node(
99125
package='controller_manager',
100126
executable='ros2_control_node',
101-
parameters=[robot_description, ur5_controller],
127+
parameters=[robot_description, ur_controller],
102128
output={
103129
'stdout': 'screen',
104130
'stderr': 'screen',

0 commit comments

Comments
 (0)