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  # RViz
35  rviz_config_file = (
36  get_package_share_directory("moveit_servo")
37  + "/config/demo_rviz_config_ros.rviz"
38  )
39  rviz_node = launch_ros.actions.Node(
40  package="rviz2",
41  executable="rviz2",
42  name="rviz2",
43  output="log",
44  arguments=["-d", rviz_config_file],
45  parameters=[
46  moveit_config.robot_description,
47  moveit_config.robot_description_semantic,
48  ],
49  )
50 
51  # ros2_control using FakeSystem as hardware
52  ros2_controllers_path = os.path.join(
53  get_package_share_directory("moveit_resources_panda_moveit_config"),
54  "config",
55  "ros2_controllers.yaml",
56  )
57  ros2_control_node = launch_ros.actions.Node(
58  package="controller_manager",
59  executable="ros2_control_node",
60  parameters=[ros2_controllers_path],
61  remappings=[
62  ("/controller_manager/robot_description", "/robot_description"),
63  ],
64  output="screen",
65  )
66 
67  joint_state_broadcaster_spawner = launch_ros.actions.Node(
68  package="controller_manager",
69  executable="spawner",
70  arguments=[
71  "joint_state_broadcaster",
72  "--controller-manager-timeout",
73  "300",
74  "--controller-manager",
75  "/controller_manager",
76  ],
77  )
78 
79  panda_arm_controller_spawner = launch_ros.actions.Node(
80  package="controller_manager",
81  executable="spawner",
82  arguments=["panda_arm_controller", "-c", "/controller_manager"],
83  )
84 
85  # Launch as much as possible in components
86  container = launch_ros.actions.ComposableNodeContainer(
87  name="moveit_servo_demo_container",
88  namespace="/",
89  package="rclcpp_components",
90  executable="component_container_mt",
91  composable_node_descriptions=[
92  # Example of launching Servo as a node component
93  # Launching as a node component makes ROS 2 intraprocess communication more efficient.
94  launch_ros.descriptions.ComposableNode(
95  package="moveit_servo",
96  plugin="moveit_servo::ServoNode",
97  name="servo_node",
98  parameters=[
99  servo_params,
100  acceleration_filter_update_period,
101  planning_group_name,
102  moveit_config.robot_description,
103  moveit_config.robot_description_semantic,
104  moveit_config.robot_description_kinematics,
105  moveit_config.joint_limits,
106  ],
107  condition=UnlessCondition(launch_as_standalone_node),
108  ),
109  launch_ros.descriptions.ComposableNode(
110  package="robot_state_publisher",
111  plugin="robot_state_publisher::RobotStatePublisher",
112  name="robot_state_publisher",
113  parameters=[moveit_config.robot_description],
114  ),
115  launch_ros.descriptions.ComposableNode(
116  package="tf2_ros",
117  plugin="tf2_ros::StaticTransformBroadcasterNode",
118  name="static_tf2_broadcaster",
119  parameters=[{"child_frame_id": "/panda_link0", "frame_id": "/world"}],
120  ),
121  ],
122  output="screen",
123  )
124  # Launch a standalone Servo node.
125  # As opposed to a node component, this may be necessary (for example) if Servo is running on a different PC
126  servo_node = launch_ros.actions.Node(
127  package="moveit_servo",
128  executable="servo_node",
129  name="servo_node",
130  parameters=[
131  servo_params,
132  acceleration_filter_update_period,
133  planning_group_name,
134  moveit_config.robot_description,
135  moveit_config.robot_description_semantic,
136  moveit_config.robot_description_kinematics,
137  moveit_config.joint_limits,
138  ],
139  output="screen",
140  condition=IfCondition(launch_as_standalone_node),
141  )
142 
143  return launch.LaunchDescription(
144  [
145  rviz_node,
146  ros2_control_node,
147  joint_state_broadcaster_spawner,
148  panda_arm_controller_spawner,
149  servo_node,
150  container,
151  ]
152  )
def generate_launch_description()