moveit2
The MoveIt Motion Planning Framework for ROS 2.
gtest_with_move_group.py
Go to the documentation of this file.
1 import os
2 import unittest
3 import launch_testing
4 
5 from ament_index_python.packages import get_package_share_directory
6 from moveit_configs_utils import MoveItConfigsBuilder
7 
8 from launch import LaunchDescription
9 from launch.actions import DeclareLaunchArgument, ExecuteProcess, TimerAction
10 from launch_ros.actions import Node
11 from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
12 from launch_testing.actions import ReadyToTest
13 
14 from moveit_configs_utils import MoveItConfigsBuilder
15 
16 
18  moveit_config = (
19  MoveItConfigsBuilder("moveit_resources_panda")
20  .robot_description(file_path="config/panda.urdf.xacro")
21  .planning_pipelines("ompl", ["ompl"])
22  .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml")
23  .to_moveit_configs()
24  )
25 
26  run_move_group_node = Node(
27  package="moveit_ros_move_group",
28  executable="move_group",
29  output="log",
30  parameters=[moveit_config.to_dict()],
31  )
32 
33  static_tf = Node(
34  package="tf2_ros",
35  executable="static_transform_publisher",
36  output="log",
37  arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "panda_link0"],
38  )
39 
40  robot_state_publisher = Node(
41  package="robot_state_publisher",
42  executable="robot_state_publisher",
43  name="robot_state_publisher",
44  output="log",
45  parameters=[moveit_config.robot_description],
46  )
47 
48  # ros2_control using FakeSystem as hardware
49  ros2_controllers_path = os.path.join(
50  get_package_share_directory("moveit_resources_panda_moveit_config"),
51  "config",
52  "ros2_controllers.yaml",
53  )
54  ros2_control_node = Node(
55  package="controller_manager",
56  executable="ros2_control_node",
57  parameters=[moveit_config.robot_description, ros2_controllers_path],
58  output="log",
59  )
60 
61  load_controllers = []
62  for controller in [
63  "panda_arm_controller",
64  "panda_hand_controller",
65  "joint_state_broadcaster",
66  ]:
67  load_controllers += [
68  ExecuteProcess(
69  cmd=["ros2 run controller_manager spawner {}".format(controller)],
70  shell=True,
71  output="log",
72  )
73  ]
74 
75  gtest_node = Node(
76  executable=PathJoinSubstitution(
77  [
78  LaunchConfiguration("test_binary_dir"),
79  LaunchConfiguration("test_executable"),
80  ]
81  ),
82  parameters=[moveit_config.to_dict()],
83  output="screen",
84  )
85 
86  return LaunchDescription(
87  [
88  DeclareLaunchArgument(
89  name="test_binary_dir",
90  description="Binary directory of package "
91  "containing test executables",
92  ),
93  static_tf,
94  robot_state_publisher,
95  ros2_control_node,
96  *load_controllers,
97  TimerAction(period=1.0, actions=[run_move_group_node]),
98  TimerAction(period=3.0, actions=[gtest_node]),
99  ReadyToTest(),
100  ]
101  ), {
102  "gtest_node": gtest_node,
103  }
104 
105 
106 class TestGTestWaitForCompletion(unittest.TestCase):
107  # Waits for test to complete, then waits a bit to make sure result files are generated
108  def test_gtest_run_complete(self, gtest_node):
109  self.proc_info.assertWaitForShutdown(gtest_node, timeout=4000.0)
110 
111 
112 @launch_testing.post_shutdown_test()
113 class TestGTestProcessPostShutdown(unittest.TestCase):
114  # Checks if the test has been completed with acceptable exit codes (successful codes)
115  def test_gtest_pass(self, proc_info, gtest_node):
116  launch_testing.asserts.assertExitCodes(
117  proc_info,
118  process=gtest_node,
119  # Allow -11 since ros2_control or warehouse_ros sometimes segfaults
120  # for unrelated reasons.
121  allowable_exit_codes=[0, -11],
122  )