moveit2
The MoveIt Motion Planning Framework for ROS 2.
launches.py
Go to the documentation of this file.
1 import os
2 
3 from launch import LaunchDescription
4 from launch.actions import (
5  DeclareLaunchArgument,
6  IncludeLaunchDescription,
7 )
8 from launch.conditions import IfCondition
9 from launch.launch_description_sources import PythonLaunchDescriptionSource
10 from launch.substitutions import LaunchConfiguration
11 
12 from launch_ros.actions import Node
13 from launch_ros.parameter_descriptions import ParameterValue
14 
15 from srdfdom.srdf import SRDF
16 
18  add_debuggable_node,
19  DeclareBooleanLaunchArg,
20 )
21 
22 
23 def generate_rsp_launch(moveit_config):
24  """Launch file for robot state publisher (rsp)"""
25 
26  ld = LaunchDescription()
27  ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0"))
28 
29  # Given the published joint states, publish tf for the robot links and the robot description
30  rsp_node = Node(
31  package="robot_state_publisher",
32  executable="robot_state_publisher",
33  respawn=True,
34  output="screen",
35  parameters=[
36  moveit_config.robot_description,
37  {
38  "publish_frequency": LaunchConfiguration("publish_frequency"),
39  },
40  ],
41  )
42  ld.add_action(rsp_node)
43 
44  return ld
45 
46 
47 def generate_moveit_rviz_launch(moveit_config):
48  """Launch file for rviz"""
49  ld = LaunchDescription()
50 
51  ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False))
52  ld.add_action(
53  DeclareLaunchArgument(
54  "rviz_config",
55  default_value=str(moveit_config.package_path / "config/moveit.rviz"),
56  )
57  )
58 
59  rviz_parameters = [
60  moveit_config.planning_pipelines,
61  moveit_config.robot_description_kinematics,
62  moveit_config.joint_limits,
63  ]
64 
66  ld,
67  package="rviz2",
68  executable="rviz2",
69  output="log",
70  respawn=False,
71  arguments=["-d", LaunchConfiguration("rviz_config")],
72  parameters=rviz_parameters,
73  )
74 
75  return ld
76 
77 
79  """Launch file for MoveIt Setup Assistant"""
80  ld = LaunchDescription()
81 
82  ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False))
84  ld,
85  package="moveit_setup_assistant",
86  executable="moveit_setup_assistant",
87  arguments=[["--config_pkg=", str(moveit_config.package_path)]],
88  )
89 
90  return ld
91 
92 
94  ld = LaunchDescription()
95 
96  name_counter = 0
97 
98  for key, xml_contents in moveit_config.robot_description_semantic.items():
99  srdf = SRDF.from_xml_string(xml_contents)
100  for vj in srdf.virtual_joints:
101  ld.add_action(
102  Node(
103  package="tf2_ros",
104  executable="static_transform_publisher",
105  name=f"static_transform_publisher{name_counter}",
106  output="log",
107  arguments=[
108  "--frame-id",
109  vj.parent_frame,
110  "--child-frame-id",
111  vj.child_link,
112  ],
113  )
114  )
115  name_counter += 1
116  return ld
117 
118 
120  controller_names = moveit_config.trajectory_execution.get(
121  "moveit_simple_controller_manager", {}
122  ).get("controller_names", [])
123  ld = LaunchDescription()
124  for controller in controller_names + ["joint_state_broadcaster"]:
125  ld.add_action(
126  Node(
127  package="controller_manager",
128  executable="spawner",
129  arguments=[controller],
130  output="screen",
131  )
132  )
133  return ld
134 
135 
136 def generate_warehouse_db_launch(moveit_config):
137  """Launch file for warehouse database"""
138  ld = LaunchDescription()
139  ld.add_action(
140  DeclareLaunchArgument(
141  "moveit_warehouse_database_path",
142  default_value=str(
143  moveit_config.package_path / "default_warehouse_mongo_db"
144  ),
145  )
146  )
147  ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False))
148 
149  # The default DB port for moveit (not default MongoDB port to avoid potential conflicts)
150  ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829"))
151 
152  # The default DB host for moveit
153  ld.add_action(
154  DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost")
155  )
156 
157  # Load warehouse parameters
158  db_parameters = [
159  {
160  "overwrite": False,
161  "database_path": LaunchConfiguration("moveit_warehouse_database_path"),
162  "warehouse_port": LaunchConfiguration("moveit_warehouse_port"),
163  "warehouse_host": LaunchConfiguration("moveit_warehouse_host"),
164  "warehouse_exec": "mongod",
165  "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection",
166  },
167  ]
168  # Run the DB server
169  db_node = Node(
170  package="warehouse_ros_mongo",
171  executable="mongo_wrapper_ros.py",
172  # TODO(dlu): Figure out if this needs to be run in a specific directory
173  # (ROS 1 version set cwd="ROS_HOME")
174  parameters=db_parameters,
175  )
176  ld.add_action(db_node)
177 
178  # If we want to reset the database, run this node
179  reset_node = Node(
180  package="moveit_ros_warehouse",
181  executable="moveit_init_demo_warehouse",
182  output="screen",
183  condition=IfCondition(LaunchConfiguration("reset")),
184  )
185  ld.add_action(reset_node)
186 
187  return ld
188 
189 
190 def generate_move_group_launch(moveit_config):
191  ld = LaunchDescription()
192 
193  ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False))
194  ld.add_action(
195  DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True)
196  )
197  ld.add_action(
198  DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True)
199  )
200  # load non-default MoveGroup capabilities (space separated)
201  ld.add_action(
202  DeclareLaunchArgument(
203  "capabilities",
204  default_value=moveit_config.move_group_capabilities["capabilities"],
205  )
206  )
207  # inhibit these default MoveGroup capabilities (space separated)
208  ld.add_action(
209  DeclareLaunchArgument(
210  "disable_capabilities",
211  default_value=moveit_config.move_group_capabilities["disable_capabilities"],
212  )
213  )
214 
215  # do not copy dynamics information from /joint_states to internal robot monitoring
216  # default to false, because almost nothing in move_group relies on this information
217  ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False))
218 
219  should_publish = LaunchConfiguration("publish_monitored_planning_scene")
220 
221  move_group_configuration = {
222  "publish_robot_description_semantic": True,
223  "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"),
224  # Note: Wrapping the following values is necessary so that the parameter value can be the empty string
225  "capabilities": ParameterValue(
226  LaunchConfiguration("capabilities"), value_type=str
227  ),
228  "disable_capabilities": ParameterValue(
229  LaunchConfiguration("disable_capabilities"), value_type=str
230  ),
231  # Publish the planning scene of the physical robot so that rviz plugin can know actual robot
232  "publish_planning_scene": should_publish,
233  "publish_geometry_updates": should_publish,
234  "publish_state_updates": should_publish,
235  "publish_transforms_updates": should_publish,
236  "monitor_dynamics": False,
237  }
238 
239  move_group_params = [
240  moveit_config.to_dict(),
241  move_group_configuration,
242  ]
243 
245  ld,
246  package="moveit_ros_move_group",
247  executable="move_group",
248  commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"),
249  output="screen",
250  parameters=move_group_params,
251  extra_debug_args=["--debug"],
252  # Set the display variable, in case OpenGL code is used internally
253  additional_env={"DISPLAY": os.environ.get("DISPLAY", "")},
254  )
255  return ld
256 
257 
258 def generate_demo_launch(moveit_config, launch_package_path=None):
259  """
260  Launches a self contained demo
261 
262  launch_package_path is optional to use different launch and config packages
263 
264  Includes
265  * static_virtual_joint_tfs
266  * robot_state_publisher
267  * move_group
268  * moveit_rviz
269  * warehouse_db (optional)
270  * ros2_control_node + controller spawners
271  """
272  if launch_package_path == None:
273  launch_package_path = moveit_config.package_path
274 
275  ld = LaunchDescription()
276  ld.add_action(
278  "db",
279  default_value=False,
280  description="By default, we do not start a database (it can be large)",
281  )
282  )
283  ld.add_action(
285  "debug",
286  default_value=False,
287  description="By default, we are not in debug mode",
288  )
289  )
290  ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True))
291  # If there are virtual joints, broadcast static tf by including virtual_joints launch
292  virtual_joints_launch = (
293  launch_package_path / "launch/static_virtual_joint_tfs.launch.py"
294  )
295 
296  if virtual_joints_launch.exists():
297  ld.add_action(
298  IncludeLaunchDescription(
299  PythonLaunchDescriptionSource(str(virtual_joints_launch)),
300  )
301  )
302 
303  # Given the published joint states, publish tf for the robot links
304  ld.add_action(
305  IncludeLaunchDescription(
306  PythonLaunchDescriptionSource(
307  str(launch_package_path / "launch/rsp.launch.py")
308  ),
309  )
310  )
311 
312  ld.add_action(
313  IncludeLaunchDescription(
314  PythonLaunchDescriptionSource(
315  str(launch_package_path / "launch/move_group.launch.py")
316  ),
317  )
318  )
319 
320  # Run Rviz and load the default config to see the state of the move_group node
321  ld.add_action(
322  IncludeLaunchDescription(
323  PythonLaunchDescriptionSource(
324  str(launch_package_path / "launch/moveit_rviz.launch.py")
325  ),
326  condition=IfCondition(LaunchConfiguration("use_rviz")),
327  )
328  )
329 
330  # If database loading was enabled, start mongodb as well
331  ld.add_action(
332  IncludeLaunchDescription(
333  PythonLaunchDescriptionSource(
334  str(launch_package_path / "launch/warehouse_db.launch.py")
335  ),
336  condition=IfCondition(LaunchConfiguration("db")),
337  )
338  )
339 
340  # Fake joint driver
341  ld.add_action(
342  Node(
343  package="controller_manager",
344  executable="ros2_control_node",
345  parameters=[
346  str(moveit_config.package_path / "config/ros2_controllers.yaml"),
347  ],
348  remappings=[
349  ("/controller_manager/robot_description", "/robot_description"),
350  ],
351  )
352  )
353 
354  ld.add_action(
355  IncludeLaunchDescription(
356  PythonLaunchDescriptionSource(
357  str(launch_package_path / "launch/spawn_controllers.launch.py")
358  ),
359  )
360  )
361 
362  return ld
def add_debuggable_node(ld, package, executable, condition_name="debug", commands_file=None, extra_debug_args=None, **kwargs)
Definition: launch_utils.py:29
def generate_setup_assistant_launch(moveit_config)
Definition: launches.py:78
def generate_moveit_rviz_launch(moveit_config)
Definition: launches.py:47
def generate_demo_launch(moveit_config, launch_package_path=None)
Definition: launches.py:258
def generate_rsp_launch(moveit_config)
Definition: launches.py:23
def generate_spawn_controllers_launch(moveit_config)
Definition: launches.py:119
def generate_static_virtual_joint_tfs_launch(moveit_config)
Definition: launches.py:93
def generate_warehouse_db_launch(moveit_config)
Definition: launches.py:136
def generate_move_group_launch(moveit_config)
Definition: launches.py:190