16 .robot_description(file_path=
"config/panda.urdf.xacro")
21 launch_as_standalone_node = LaunchConfiguration(
22 "launch_as_standalone_node", default=
"true"
27 "moveit_servo": ParameterBuilder(
"moveit_servo")
28 .yaml(
"config/test_config_panda.yaml")
33 acceleration_filter_update_period = {
"update_period": 0.01}
34 planning_group_name = {
"planning_group_name":
"panda_arm"}
37 ros2_controllers_path = os.path.join(
38 get_package_share_directory(
"moveit_resources_panda_moveit_config"),
40 "ros2_controllers.yaml",
42 ros2_control_node = launch_ros.actions.Node(
43 package=
"controller_manager",
44 executable=
"ros2_control_node",
45 parameters=[ros2_controllers_path],
47 (
"/controller_manager/robot_description",
"/robot_description"),
52 joint_state_broadcaster_spawner = launch_ros.actions.Node(
53 package=
"controller_manager",
56 "joint_state_broadcaster",
57 "--controller-manager-timeout",
59 "--controller-manager",
60 "/controller_manager",
65 panda_arm_controller_spawner = launch_ros.actions.Node(
66 package=
"controller_manager",
68 arguments=[
"panda_arm_controller",
"-c",
"/controller_manager"],
72 container = launch_ros.actions.ComposableNodeContainer(
73 name=
"moveit_servo_demo_container",
75 package=
"rclcpp_components",
76 executable=
"component_container_mt",
77 composable_node_descriptions=[
80 launch_ros.descriptions.ComposableNode(
81 package=
"moveit_servo",
82 plugin=
"moveit_servo::ServoNode",
86 acceleration_filter_update_period,
88 moveit_config.robot_description,
89 moveit_config.robot_description_semantic,
90 moveit_config.robot_description_kinematics,
92 condition=UnlessCondition(launch_as_standalone_node),
94 launch_ros.descriptions.ComposableNode(
95 package=
"robot_state_publisher",
96 plugin=
"robot_state_publisher::RobotStatePublisher",
97 name=
"robot_state_publisher",
98 parameters=[moveit_config.robot_description],
100 launch_ros.descriptions.ComposableNode(
102 plugin=
"tf2_ros::StaticTransformBroadcasterNode",
103 name=
"static_tf2_broadcaster",
104 parameters=[{
"child_frame_id":
"/panda_link0",
"frame_id":
"/world"}],
111 servo_node = launch_ros.actions.Node(
112 package=
"moveit_servo",
113 executable=
"servo_node",
117 acceleration_filter_update_period,
119 moveit_config.robot_description,
120 moveit_config.robot_description_semantic,
121 moveit_config.robot_description_kinematics,
124 condition=IfCondition(launch_as_standalone_node),
127 servo_gtest = launch_ros.actions.Node(
128 executable=launch.substitutions.PathJoinSubstitution(
130 launch.substitutions.LaunchConfiguration(
"test_binary_dir"),
131 "moveit_servo_ros_integration_test",
137 return launch.LaunchDescription(
141 launch.actions.TimerAction(period=3.0, actions=[ros2_control_node]),
142 launch.actions.TimerAction(
143 period=5.0, actions=[joint_state_broadcaster_spawner]
145 launch.actions.TimerAction(
146 period=7.0, actions=[panda_arm_controller_spawner]
148 launch.actions.TimerAction(period=9.0, actions=[servo_gtest]),
149 launch_testing.actions.ReadyToTest(),
152 "servo_gtest": servo_gtest,
test_gtest_pass(self, proc_info, servo_gtest)