3 from launch 
import LaunchDescription
 
    4 from launch.actions 
import (
 
    6     IncludeLaunchDescription,
 
    8 from launch.conditions 
import IfCondition
 
    9 from launch.launch_description_sources 
import PythonLaunchDescriptionSource
 
   10 from launch.substitutions 
import LaunchConfiguration
 
   12 from launch_ros.actions 
import Node
 
   13 from launch_ros.parameter_descriptions 
import ParameterValue
 
   15 from srdfdom.srdf 
import SRDF
 
   19     DeclareBooleanLaunchArg,
 
   24     """Launch file for robot state publisher (rsp)""" 
   26     ld = LaunchDescription()
 
   27     ld.add_action(DeclareLaunchArgument(
"publish_frequency", default_value=
"15.0"))
 
   31         package=
"robot_state_publisher",
 
   32         executable=
"robot_state_publisher",
 
   36             moveit_config.robot_description,
 
   38                 "publish_frequency": LaunchConfiguration(
"publish_frequency"),
 
   42     ld.add_action(rsp_node)
 
   48     """Launch file for rviz""" 
   49     ld = LaunchDescription()
 
   53         DeclareLaunchArgument(
 
   55             default_value=str(moveit_config.package_path / 
"config/moveit.rviz"),
 
   60         moveit_config.planning_pipelines,
 
   61         moveit_config.robot_description_kinematics,
 
   62         moveit_config.joint_limits,
 
   71         arguments=[
"-d", LaunchConfiguration(
"rviz_config")],
 
   72         parameters=rviz_parameters,
 
   79     """Launch file for MoveIt Setup Assistant""" 
   80     ld = LaunchDescription()
 
   85         package=
"moveit_setup_assistant",
 
   86         executable=
"moveit_setup_assistant",
 
   87         arguments=[[
"--config_pkg=", str(moveit_config.package_path)]],
 
   94     ld = LaunchDescription()
 
   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:
 
  104                     executable=
"static_transform_publisher",
 
  105                     name=f
"static_transform_publisher{name_counter}",
 
  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"]:
 
  127                 package=
"controller_manager",
 
  128                 executable=
"spawner",
 
  129                 arguments=[controller],
 
  137     """Launch file for warehouse database""" 
  138     ld = LaunchDescription()
 
  140         DeclareLaunchArgument(
 
  141             "moveit_warehouse_database_path",
 
  143                 moveit_config.package_path / 
"default_warehouse_mongo_db" 
  150     ld.add_action(DeclareLaunchArgument(
"moveit_warehouse_port", default_value=
"33829"))
 
  154         DeclareLaunchArgument(
"moveit_warehouse_host", default_value=
"localhost")
 
  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",
 
  170         package=
"warehouse_ros_mongo",
 
  171         executable=
"mongo_wrapper_ros.py",
 
  174         parameters=db_parameters,
 
  176     ld.add_action(db_node)
 
  180         package=
"moveit_ros_warehouse",
 
  181         executable=
"moveit_init_demo_warehouse",
 
  183         condition=IfCondition(LaunchConfiguration(
"reset")),
 
  185     ld.add_action(reset_node)
 
  191     ld = LaunchDescription()
 
  202         DeclareLaunchArgument(
 
  204             default_value=moveit_config.move_group_capabilities[
"capabilities"],
 
  209         DeclareLaunchArgument(
 
  210             "disable_capabilities",
 
  211             default_value=moveit_config.move_group_capabilities[
"disable_capabilities"],
 
  219     should_publish = LaunchConfiguration(
"publish_monitored_planning_scene")
 
  221     move_group_configuration = {
 
  222         "publish_robot_description_semantic": 
True,
 
  223         "allow_trajectory_execution": LaunchConfiguration(
"allow_trajectory_execution"),
 
  225         "capabilities": ParameterValue(
 
  226             LaunchConfiguration(
"capabilities"), value_type=str
 
  228         "disable_capabilities": ParameterValue(
 
  229             LaunchConfiguration(
"disable_capabilities"), value_type=str
 
  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,
 
  239     move_group_params = [
 
  240         moveit_config.to_dict(),
 
  241         move_group_configuration,
 
  246         package=
"moveit_ros_move_group",
 
  247         executable=
"move_group",
 
  248         commands_file=str(moveit_config.package_path / 
"launch" / 
"gdb_settings.gdb"),
 
  250         parameters=move_group_params,
 
  251         extra_debug_args=[
"--debug"],
 
  253         additional_env={
"DISPLAY": os.environ.get(
"DISPLAY", 
"")},
 
  260     Launches a self contained demo 
  262     launch_package_path is optional to use different launch and config packages 
  265      * static_virtual_joint_tfs 
  266      * robot_state_publisher 
  269      * warehouse_db (optional) 
  270      * ros2_control_node + controller spawners 
  272     if launch_package_path == 
None:
 
  273         launch_package_path = moveit_config.package_path
 
  275     ld = LaunchDescription()
 
  280             description=
"By default, we do not start a database (it can be large)",
 
  287             description=
"By default, we are not in debug mode",
 
  292     virtual_joints_launch = (
 
  293         launch_package_path / 
"launch/static_virtual_joint_tfs.launch.py" 
  296     if virtual_joints_launch.exists():
 
  298             IncludeLaunchDescription(
 
  299                 PythonLaunchDescriptionSource(str(virtual_joints_launch)),
 
  305         IncludeLaunchDescription(
 
  306             PythonLaunchDescriptionSource(
 
  307                 str(launch_package_path / 
"launch/rsp.launch.py")
 
  313         IncludeLaunchDescription(
 
  314             PythonLaunchDescriptionSource(
 
  315                 str(launch_package_path / 
"launch/move_group.launch.py")
 
  322         IncludeLaunchDescription(
 
  323             PythonLaunchDescriptionSource(
 
  324                 str(launch_package_path / 
"launch/moveit_rviz.launch.py")
 
  326             condition=IfCondition(LaunchConfiguration(
"use_rviz")),
 
  332         IncludeLaunchDescription(
 
  333             PythonLaunchDescriptionSource(
 
  334                 str(launch_package_path / 
"launch/warehouse_db.launch.py")
 
  336             condition=IfCondition(LaunchConfiguration(
"db")),
 
  343             package=
"controller_manager",
 
  344             executable=
"ros2_control_node",
 
  346                 moveit_config.robot_description,
 
  347                 str(moveit_config.package_path / 
"config/ros2_controllers.yaml"),
 
  353         IncludeLaunchDescription(
 
  354             PythonLaunchDescriptionSource(
 
  355                 str(launch_package_path / 
"launch/spawn_controllers.launch.py")
 
def add_debuggable_node(ld, package, executable, condition_name="debug", commands_file=None, extra_debug_args=None, **kwargs)
 
def generate_setup_assistant_launch(moveit_config)
 
def generate_moveit_rviz_launch(moveit_config)
 
def generate_demo_launch(moveit_config, launch_package_path=None)
 
def generate_rsp_launch(moveit_config)
 
def generate_spawn_controllers_launch(moveit_config)
 
def generate_static_virtual_joint_tfs_launch(moveit_config)
 
def generate_warehouse_db_launch(moveit_config)
 
def generate_move_group_launch(moveit_config)