moveit2
The MoveIt Motion Planning Framework for ROS 2.
demo_pose.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_param_builder import ParameterBuilder
6 from moveit_configs_utils import MoveItConfigsBuilder
7 
8 
10  moveit_config = (
11  MoveItConfigsBuilder("moveit_resources_panda")
12  .robot_description(file_path="config/panda.urdf.xacro")
13  .joint_limits(file_path="config/hard_joint_limits.yaml")
14  .robot_description_kinematics()
15  .to_moveit_configs()
16  )
17 
18  # Get parameters for the Servo node
19  servo_params = {
20  "moveit_servo": ParameterBuilder("moveit_servo")
21  .yaml("config/panda_simulated_config.yaml")
22  .to_dict()
23  }
24 
25  # This filter parameter should be >1. Increase it for greater smoothing but slower motion.
26  low_pass_filter_coeff = {"butterworth_filter_coeff": 1.5}
27 
28  # RViz
29  rviz_config_file = (
30  get_package_share_directory("moveit_servo") + "/config/demo_rviz_config.rviz"
31  )
32  rviz_node = launch_ros.actions.Node(
33  package="rviz2",
34  executable="rviz2",
35  name="rviz2",
36  output="log",
37  arguments=["-d", rviz_config_file],
38  parameters=[
39  moveit_config.robot_description,
40  moveit_config.robot_description_semantic,
41  ],
42  )
43 
44  # ros2_control using FakeSystem as hardware
45  ros2_controllers_path = os.path.join(
46  get_package_share_directory("moveit_resources_panda_moveit_config"),
47  "config",
48  "ros2_controllers.yaml",
49  )
50  ros2_control_node = launch_ros.actions.Node(
51  package="controller_manager",
52  executable="ros2_control_node",
53  parameters=[ros2_controllers_path],
54  remappings=[
55  ("/controller_manager/robot_description", "/robot_description"),
56  ],
57  output="screen",
58  )
59 
60  joint_state_broadcaster_spawner = launch_ros.actions.Node(
61  package="controller_manager",
62  executable="spawner",
63  arguments=[
64  "joint_state_broadcaster",
65  "--controller-manager-timeout",
66  "300",
67  "--controller-manager",
68  "/controller_manager",
69  ],
70  )
71 
72  panda_arm_controller_spawner = launch_ros.actions.Node(
73  package="controller_manager",
74  executable="spawner",
75  arguments=["panda_arm_controller", "-c", "/controller_manager"],
76  )
77 
78  # Launch as much as possible in components
79  container = launch_ros.actions.ComposableNodeContainer(
80  name="moveit_servo_demo_container",
81  namespace="/",
82  package="rclcpp_components",
83  executable="component_container_mt",
84  composable_node_descriptions=[
85  launch_ros.descriptions.ComposableNode(
86  package="robot_state_publisher",
87  plugin="robot_state_publisher::RobotStatePublisher",
88  name="robot_state_publisher",
89  parameters=[moveit_config.robot_description],
90  ),
91  launch_ros.descriptions.ComposableNode(
92  package="tf2_ros",
93  plugin="tf2_ros::StaticTransformBroadcasterNode",
94  name="static_tf2_broadcaster",
95  parameters=[{"child_frame_id": "/panda_link0", "frame_id": "/world"}],
96  ),
97  ],
98  output="screen",
99  )
100  # Launch a standalone Servo node.
101  # As opposed to a node component, this may be necessary (for example) if Servo is running on a different PC
102  servo_node = launch_ros.actions.Node(
103  package="moveit_servo",
104  executable="demo_pose",
105  parameters=[
106  servo_params,
107  low_pass_filter_coeff,
108  moveit_config.robot_description,
109  moveit_config.robot_description_semantic,
110  moveit_config.robot_description_kinematics,
111  moveit_config.joint_limits,
112  ],
113  output="screen",
114  )
115 
116  return launch.LaunchDescription(
117  [
118  rviz_node,
119  ros2_control_node,
120  joint_state_broadcaster_spawner,
121  panda_arm_controller_spawner,
122  servo_node,
123  container,
124  ]
125  )
def generate_launch_description()