14 .robot_description(file_path=
"config/panda.urdf.xacro")
20 launch_as_standalone_node = LaunchConfiguration(
21 "launch_as_standalone_node", default=
"false"
26 "moveit_servo": ParameterBuilder(
"moveit_servo")
27 .yaml(
"config/panda_simulated_config.yaml")
32 acceleration_filter_update_period = {
"update_period": 0.01}
33 planning_group_name = {
"planning_group_name":
"panda_arm"}
37 get_package_share_directory(
"moveit_servo")
38 +
"/config/demo_rviz_config_ros.rviz"
40 rviz_node = launch_ros.actions.Node(
45 arguments=[
"-d", rviz_config_file],
47 moveit_config.robot_description,
48 moveit_config.robot_description_semantic,
53 ros2_controllers_path = os.path.join(
54 get_package_share_directory(
"moveit_resources_panda_moveit_config"),
56 "ros2_controllers.yaml",
58 ros2_control_node = launch_ros.actions.Node(
59 package=
"controller_manager",
60 executable=
"ros2_control_node",
61 parameters=[ros2_controllers_path],
63 (
"/controller_manager/robot_description",
"/robot_description"),
68 joint_state_broadcaster_spawner = launch_ros.actions.Node(
69 package=
"controller_manager",
72 "joint_state_broadcaster",
73 "--controller-manager-timeout",
75 "--controller-manager",
76 "/controller_manager",
80 panda_arm_controller_spawner = launch_ros.actions.Node(
81 package=
"controller_manager",
83 arguments=[
"panda_arm_controller",
"-c",
"/controller_manager"],
87 container = launch_ros.actions.ComposableNodeContainer(
88 name=
"moveit_servo_demo_container",
90 package=
"rclcpp_components",
91 executable=
"component_container_mt",
92 composable_node_descriptions=[
95 launch_ros.descriptions.ComposableNode(
96 package=
"moveit_servo",
97 plugin=
"moveit_servo::ServoNode",
101 acceleration_filter_update_period,
103 moveit_config.robot_description,
104 moveit_config.robot_description_semantic,
105 moveit_config.robot_description_kinematics,
106 moveit_config.joint_limits,
108 condition=UnlessCondition(launch_as_standalone_node),
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],
116 launch_ros.descriptions.ComposableNode(
118 plugin=
"tf2_ros::StaticTransformBroadcasterNode",
119 name=
"static_tf2_broadcaster",
120 parameters=[{
"child_frame_id":
"/panda_link0",
"frame_id":
"/world"}],
127 servo_node = launch_ros.actions.Node(
128 package=
"moveit_servo",
129 executable=
"servo_node",
133 acceleration_filter_update_period,
135 moveit_config.robot_description,
136 moveit_config.robot_description_semantic,
137 moveit_config.robot_description_kinematics,
138 moveit_config.joint_limits,
141 condition=IfCondition(launch_as_standalone_node),
144 return launch.LaunchDescription(
148 joint_state_broadcaster_spawner,
149 panda_arm_controller_spawner,