moveit2
The MoveIt Motion Planning Framework for ROS 2.
demo_ros_api.launch.py
Go to the documentation of this file.
1 import os
2 import launch
3 import launch_ros
4 from ament_index_python.packages import get_package_share_directory
5 from launch.conditions import IfCondition, UnlessCondition
6 from launch.substitutions import LaunchConfiguration
7 from launch_param_builder import ParameterBuilder
8 from moveit_configs_utils import MoveItConfigsBuilder
9 
10 
12  moveit_config = (
13  MoveItConfigsBuilder("moveit_resources_panda")
14  .robot_description(file_path="config/panda.urdf.xacro")
15  .joint_limits(file_path="config/hard_joint_limits.yaml")
16  .to_moveit_configs()
17  )
18 
19  # Launch Servo as a standalone node or as a "node component" for better latency/efficiency
20  launch_as_standalone_node = LaunchConfiguration(
21  "launch_as_standalone_node", default="false"
22  )
23 
24  # Get parameters for the Servo node
25  servo_params = {
26  "moveit_servo": ParameterBuilder("moveit_servo")
27  .yaml("config/panda_simulated_config.yaml")
28  .to_dict()
29  }
30 
31  # This sets the update rate and planning group name for the acceleration limiting filter.
32  acceleration_filter_update_period = {"update_period": 0.01}
33  planning_group_name = {"planning_group_name": "panda_arm"}
34 
35  # RViz
36  rviz_config_file = (
37  get_package_share_directory("moveit_servo")
38  + "/config/demo_rviz_config_ros.rviz"
39  )
40  rviz_node = launch_ros.actions.Node(
41  package="rviz2",
42  executable="rviz2",
43  name="rviz2",
44  output="log",
45  arguments=["-d", rviz_config_file],
46  parameters=[
47  moveit_config.robot_description,
48  moveit_config.robot_description_semantic,
49  ],
50  )
51 
52  # ros2_control using FakeSystem as hardware
53  ros2_controllers_path = os.path.join(
54  get_package_share_directory("moveit_resources_panda_moveit_config"),
55  "config",
56  "ros2_controllers.yaml",
57  )
58  ros2_control_node = launch_ros.actions.Node(
59  package="controller_manager",
60  executable="ros2_control_node",
61  parameters=[ros2_controllers_path],
62  remappings=[
63  ("/controller_manager/robot_description", "/robot_description"),
64  ],
65  output="screen",
66  )
67 
68  joint_state_broadcaster_spawner = launch_ros.actions.Node(
69  package="controller_manager",
70  executable="spawner",
71  arguments=[
72  "joint_state_broadcaster",
73  "--controller-manager-timeout",
74  "300",
75  "--controller-manager",
76  "/controller_manager",
77  ],
78  )
79 
80  panda_arm_controller_spawner = launch_ros.actions.Node(
81  package="controller_manager",
82  executable="spawner",
83  arguments=["panda_arm_controller", "-c", "/controller_manager"],
84  )
85 
86  # Launch as much as possible in components
87  container = launch_ros.actions.ComposableNodeContainer(
88  name="moveit_servo_demo_container",
89  namespace="/",
90  package="rclcpp_components",
91  executable="component_container_mt",
92  composable_node_descriptions=[
93  # Example of launching Servo as a node component
94  # Launching as a node component makes ROS 2 intraprocess communication more efficient.
95  launch_ros.descriptions.ComposableNode(
96  package="moveit_servo",
97  plugin="moveit_servo::ServoNode",
98  name="servo_node",
99  parameters=[
100  servo_params,
101  acceleration_filter_update_period,
102  planning_group_name,
103  moveit_config.robot_description,
104  moveit_config.robot_description_semantic,
105  moveit_config.robot_description_kinematics,
106  moveit_config.joint_limits,
107  ],
108  condition=UnlessCondition(launch_as_standalone_node),
109  ),
110  launch_ros.descriptions.ComposableNode(
111  package="robot_state_publisher",
112  plugin="robot_state_publisher::RobotStatePublisher",
113  name="robot_state_publisher",
114  parameters=[moveit_config.robot_description],
115  ),
116  launch_ros.descriptions.ComposableNode(
117  package="tf2_ros",
118  plugin="tf2_ros::StaticTransformBroadcasterNode",
119  name="static_tf2_broadcaster",
120  parameters=[{"child_frame_id": "/panda_link0", "frame_id": "/world"}],
121  ),
122  ],
123  output="screen",
124  )
125  # Launch a standalone Servo node.
126  # As opposed to a node component, this may be necessary (for example) if Servo is running on a different PC
127  servo_node = launch_ros.actions.Node(
128  package="moveit_servo",
129  executable="servo_node",
130  name="servo_node",
131  parameters=[
132  servo_params,
133  acceleration_filter_update_period,
134  planning_group_name,
135  moveit_config.robot_description,
136  moveit_config.robot_description_semantic,
137  moveit_config.robot_description_kinematics,
138  moveit_config.joint_limits,
139  ],
140  output="screen",
141  condition=IfCondition(launch_as_standalone_node),
142  )
143 
144  return launch.LaunchDescription(
145  [
146  rviz_node,
147  ros2_control_node,
148  joint_state_broadcaster_spawner,
149  panda_arm_controller_spawner,
150  servo_node,
151  container,
152  ]
153  )
def generate_launch_description()