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