moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
servo_ros_integration.test.py
Go to the documentation of this file.
1import os
2import launch
3import unittest
4import launch_ros
5import launch_testing
6from ament_index_python.packages import get_package_share_directory
7from moveit_configs_utils import MoveItConfigsBuilder
8from launch_param_builder import ParameterBuilder
9from launch.conditions import IfCondition, UnlessCondition
10from launch.substitutions import LaunchConfiguration
11
12
14 moveit_config = (
15 MoveItConfigsBuilder("moveit_resources_panda")
16 .robot_description(file_path="config/panda.urdf.xacro")
17 .to_moveit_configs()
18 )
19
20 # Launch Servo as a standalone node or as a "node component" for better latency/efficiency
21 launch_as_standalone_node = LaunchConfiguration(
22 "launch_as_standalone_node", default="true"
23 )
24
25 # Get parameters for the Servo node
26 servo_params = {
27 "moveit_servo": ParameterBuilder("moveit_servo")
28 .yaml("config/test_config_panda.yaml")
29 .to_dict()
30 }
31
32 # This sets the update rate and planning group name for the acceleration limiting filter.
33 acceleration_filter_update_period = {"update_period": 0.01}
34 planning_group_name = {"planning_group_name": "panda_arm"}
35
36 # ros2_control using FakeSystem as hardware
37 ros2_controllers_path = os.path.join(
38 get_package_share_directory("moveit_resources_panda_moveit_config"),
39 "config",
40 "ros2_controllers.yaml",
41 )
42 ros2_control_node = launch_ros.actions.Node(
43 package="controller_manager",
44 executable="ros2_control_node",
45 parameters=[ros2_controllers_path],
46 remappings=[
47 ("/controller_manager/robot_description", "/robot_description"),
48 ],
49 output="screen",
50 )
51
52 joint_state_broadcaster_spawner = launch_ros.actions.Node(
53 package="controller_manager",
54 executable="spawner",
55 arguments=[
56 "joint_state_broadcaster",
57 "--controller-manager-timeout",
58 "300",
59 "--controller-manager",
60 "/controller_manager",
61 ],
62 output="screen",
63 )
64
65 panda_arm_controller_spawner = launch_ros.actions.Node(
66 package="controller_manager",
67 executable="spawner",
68 arguments=["panda_arm_controller", "-c", "/controller_manager"],
69 )
70
71 # Launch as much as possible in components
72 container = launch_ros.actions.ComposableNodeContainer(
73 name="moveit_servo_demo_container",
74 namespace="/",
75 package="rclcpp_components",
76 executable="component_container_mt",
77 composable_node_descriptions=[
78 # Example of launching Servo as a node component
79 # Launching as a node component makes ROS 2 intraprocess communication more efficient.
80 launch_ros.descriptions.ComposableNode(
81 package="moveit_servo",
82 plugin="moveit_servo::ServoNode",
83 name="servo_node",
84 parameters=[
85 servo_params,
86 acceleration_filter_update_period,
87 planning_group_name,
88 moveit_config.robot_description,
89 moveit_config.robot_description_semantic,
90 moveit_config.robot_description_kinematics,
91 ],
92 condition=UnlessCondition(launch_as_standalone_node),
93 ),
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],
99 ),
100 launch_ros.descriptions.ComposableNode(
101 package="tf2_ros",
102 plugin="tf2_ros::StaticTransformBroadcasterNode",
103 name="static_tf2_broadcaster",
104 parameters=[{"child_frame_id": "/panda_link0", "frame_id": "/world"}],
105 ),
106 ],
107 output="screen",
108 )
109 # Launch a standalone Servo node.
110 # As opposed to a node component, this may be necessary (for example) if Servo is running on a different PC
111 servo_node = launch_ros.actions.Node(
112 package="moveit_servo",
113 executable="servo_node",
114 name="servo_node",
115 parameters=[
116 servo_params,
117 acceleration_filter_update_period,
118 planning_group_name,
119 moveit_config.robot_description,
120 moveit_config.robot_description_semantic,
121 moveit_config.robot_description_kinematics,
122 ],
123 output="screen",
124 condition=IfCondition(launch_as_standalone_node),
125 )
126
127 servo_gtest = launch_ros.actions.Node(
128 executable=launch.substitutions.PathJoinSubstitution(
129 [
130 launch.substitutions.LaunchConfiguration("test_binary_dir"),
131 "moveit_servo_ros_integration_test",
132 ]
133 ),
134 output="screen",
135 )
136
137 return launch.LaunchDescription(
138 [
139 servo_node,
140 container,
141 launch.actions.TimerAction(period=3.0, actions=[ros2_control_node]),
142 launch.actions.TimerAction(
143 period=5.0, actions=[joint_state_broadcaster_spawner]
144 ),
145 launch.actions.TimerAction(
146 period=7.0, actions=[panda_arm_controller_spawner]
147 ),
148 launch.actions.TimerAction(period=9.0, actions=[servo_gtest]),
149 launch_testing.actions.ReadyToTest(),
150 ]
151 ), {
152 "servo_gtest": servo_gtest,
153 }
154
155
156class TestGTestWaitForCompletion(unittest.TestCase):
157 # Waits for test to complete, then waits a bit to make sure result files are generated
158 def test_gtest_run_complete(self, servo_gtest):
159 self.proc_info.assertWaitForShutdown(servo_gtest, timeout=4000.0)
160
161
162@launch_testing.post_shutdown_test()
163class TestGTestProcessPostShutdown(unittest.TestCase):
164 # Checks if the test has been completed with acceptable exit codes (successful codes)
165 def test_gtest_pass(self, proc_info, servo_gtest):
166 launch_testing.asserts.assertExitCodes(proc_info, process=servo_gtest)