moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
move_group_ompl_constraints.test.py
Go to the documentation of this file.
1import os
2import sys
3import unittest
4
5import launch_testing.asserts
6
7sys.path.append(os.path.dirname(__file__))
8from move_group_launch_test_common import generate_move_group_test_description
9
10
12 return generate_move_group_test_description(
13 gtest_name="move_group_ompl_constraints_test"
14 )
15
16
17class TestGTestProcessActive(unittest.TestCase):
19 self,
20 proc_info,
21 ompl_constraint_test,
22 run_move_group_node,
23 static_tf,
24 robot_state_publisher,
25 ros2_control_node,
26 ):
27 proc_info.assertWaitForShutdown(ompl_constraint_test, timeout=4000.0)
28
29
30@launch_testing.post_shutdown_test()
31class TestGTestProcessPostShutdown(unittest.TestCase):
33 self,
34 proc_info,
35 ompl_constraint_test,
36 run_move_group_node,
37 static_tf,
38 robot_state_publisher,
39 ros2_control_node,
40 ):
41 launch_testing.asserts.assertExitCodes(proc_info, process=ompl_constraint_test)
test_gtest_run_complete(self, proc_info, ompl_constraint_test, run_move_group_node, static_tf, robot_state_publisher, ros2_control_node)
test_gtest_pass(self, proc_info, ompl_constraint_test, run_move_group_node, static_tf, robot_state_publisher, ros2_control_node)