moveit2
The MoveIt Motion Planning Framework for ROS 2.
demo.launch.py
Go to the documentation of this file.
1 import os
2 import yaml
3 from launch import LaunchDescription
4 from launch.actions import DeclareLaunchArgument
5 from launch.substitutions import LaunchConfiguration
6 from launch.conditions import IfCondition, UnlessCondition
7 from launch_ros.actions import Node
8 from launch.actions import ExecuteProcess
9 from ament_index_python.packages import get_package_share_directory
10 import xacro
11 
12 
13 def load_file(package_name, file_path):
14  package_path = get_package_share_directory(package_name)
15  absolute_file_path = os.path.join(package_path, file_path)
16 
17  try:
18  with open(absolute_file_path, "r") as file:
19  return file.read()
20  except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
21  return None
22 
23 
24 def load_yaml(package_name, file_path):
25  package_path = get_package_share_directory(package_name)
26  absolute_file_path = os.path.join(package_path, file_path)
27 
28  try:
29  with open(absolute_file_path, "r") as file:
30  return yaml.safe_load(file)
31  except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
32  return None
33 
34 
36 
37  # planning_context
38  robot_description_config = xacro.process_file(
39  os.path.join(
40  get_package_share_directory("moveit_resources_prbt_support"),
41  "urdf",
42  "prbt.xacro",
43  )
44  )
45  robot_description = {"robot_description": robot_description_config.toxml()}
46 
47  robot_description_semantic_config = xacro.process_file(
48  os.path.join(
49  get_package_share_directory("moveit_resources_prbt_moveit_config"),
50  "config",
51  "prbt.srdf.xacro",
52  )
53  )
54 
55  robot_description_semantic = {
56  "robot_description_semantic": robot_description_semantic_config.toxml()
57  }
58 
59  joint_limits_yaml = load_yaml(
60  "moveit_resources_prbt_moveit_config", "config/joint_limits.yaml"
61  )
62  pilz_cartesian_limits_yaml = load_yaml(
63  "moveit_resources_prbt_moveit_config", "config/pilz_cartesian_limits.yaml"
64  )
65  robot_description_planning = {
66  "robot_description_planning": {
67  **joint_limits_yaml,
68  **pilz_cartesian_limits_yaml,
69  }
70  }
71  kinematics_yaml = load_yaml(
72  "moveit_resources_prbt_moveit_config", "config/kinematics.yaml"
73  )
74  robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml}
75 
76  # Planning Functionality
77  planning_pipelines_config = {
78  "default_planning_pipeline": "ompl",
79  "planning_pipelines": ["pilz", "ompl"],
80  "pilz": {
81  "planning_plugin": "pilz_industrial_motion_planner/CommandPlanner",
82  "request_adapters": "",
83  "start_state_max_bounds_error": 0.1,
84  },
85  "ompl": {
86  "planning_plugin": "ompl_interface/OMPLPlanner",
87  "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""",
88  "start_state_max_bounds_error": 0.1,
89  },
90  }
91  ompl_planning_yaml = load_yaml(
92  "moveit_resources_prbt_moveit_config", "config/ompl_planning.yaml"
93  )
94  planning_pipelines_config["ompl"].update(ompl_planning_yaml)
95 
96  # Trajectory Execution Functionality
97  moveit_simple_controllers_yaml = load_yaml(
98  "moveit_resources_prbt_moveit_config", "config/prbt_controllers.yaml"
99  )
100  moveit_controllers = {
101  "moveit_simple_controller_manager": moveit_simple_controllers_yaml,
102  "moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager",
103  }
104 
105  trajectory_execution = {
106  "moveit_manage_controllers": True,
107  "trajectory_execution.allowed_execution_duration_scaling": 1.2,
108  "trajectory_execution.allowed_goal_duration_margin": 0.5,
109  "trajectory_execution.allowed_start_tolerance": 0.01,
110  }
111 
112  planning_scene_monitor_parameters = {
113  "publish_planning_scene": True,
114  "publish_geometry_updates": True,
115  "publish_state_updates": True,
116  "publish_transforms_updates": True,
117  }
118 
119  # Start the actual move_group node/action server
120  run_move_group_node = Node(
121  package="moveit_ros_move_group",
122  executable="move_group",
123  output="screen",
124  parameters=[
125  robot_description,
126  robot_description_semantic,
127  robot_description_kinematics,
128  robot_description_planning,
129  planning_pipelines_config,
130  trajectory_execution,
131  moveit_controllers,
132  planning_scene_monitor_parameters,
133  ],
134  )
135 
136  # RViz
137  rviz_base = os.path.join(
138  get_package_share_directory("moveit_resources_prbt_moveit_config"), "launch"
139  )
140  rviz_full_config = os.path.join(rviz_base, "moveit.rviz")
141  rviz_node = Node(
142  package="rviz2",
143  executable="rviz2",
144  name="rviz2",
145  output="log",
146  arguments=["-d", rviz_full_config],
147  parameters=[
148  robot_description,
149  robot_description_semantic,
150  robot_description_planning,
151  robot_description_kinematics,
152  planning_pipelines_config,
153  ],
154  )
155 
156  # Static TF
157  static_tf = Node(
158  package="tf2_ros",
159  executable="static_transform_publisher",
160  name="static_transform_publisher",
161  output="log",
162  arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "prbt_link0"],
163  )
164 
165  # Publish TF
166  robot_state_publisher = Node(
167  package="robot_state_publisher",
168  executable="robot_state_publisher",
169  name="robot_state_publisher",
170  output="both",
171  parameters=[robot_description],
172  )
173 
174  # ros2_control using FakeSystem as hardware
175  ros2_controllers_path = os.path.join(
176  get_package_share_directory("moveit_resources_prbt_moveit_config"),
177  "config",
178  "prbt_ros_controllers.yaml",
179  )
180  ros2_control_node = Node(
181  package="controller_manager",
182  executable="ros2_control_node",
183  parameters=[robot_description, ros2_controllers_path],
184  output="screen",
185  )
186 
187  joint_state_broadcaster_spawner = Node(
188  package="controller_manager",
189  executable="spawner",
190  arguments=[
191  "joint_state_broadcaster",
192  "--controller-manager",
193  "/controller_manager",
194  ],
195  )
196 
197  prbt_arm_controller_spawner = Node(
198  package="controller_manager",
199  executable="spawner",
200  arguments=[
201  "panda_joint_group_position_controller",
202  "-c",
203  "/controller_manager",
204  ],
205  )
206 
207  # Warehouse mongodb server
208  mongodb_server_node = Node(
209  package="warehouse_ros_mongo",
210  executable="mongo_wrapper_ros.py",
211  parameters=[
212  {"warehouse_port": 33829},
213  {"warehouse_host": "localhost"},
214  {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"},
215  ],
216  output="screen",
217  )
218 
219  return LaunchDescription(
220  [
221  rviz_node,
222  static_tf,
223  robot_state_publisher,
224  run_move_group_node,
225  ros2_control_node,
226  joint_state_broadcaster_spawner,
227  prbt_arm_controller_spawner,
228  mongodb_server_node,
229  ]
230  )
def load_yaml(package_name, file_path)
Definition: demo.launch.py:24
def generate_launch_description()
Definition: demo.launch.py:35
def load_file(package_name, file_path)
Definition: demo.launch.py:13