1 from ament_index_python.packages
import get_package_share_path
2 from launch
import LaunchDescription
4 from launch_ros.actions
import Node
12 rdf_path = get_package_share_path(
"moveit_ros_planning") /
"rdf_loader"
13 test_data_path = rdf_path /
"test" /
"data"
15 kermit_urdf = open(test_data_path /
"kermit.urdf").read()
16 kermit_srdf = open(test_data_path /
"kermit.srdf").read()
18 boring_urdf_node = Node(
19 package=
"moveit_ros_planning",
20 executable=
"boring_string_publisher",
24 "topic":
"topic_description",
25 "content_path": str(test_data_path /
"gonzo.urdf"),
29 boring_srdf_node = Node(
30 package=
"moveit_ros_planning",
31 executable=
"boring_string_publisher",
35 "topic":
"topic_description_semantic",
36 "content_path": str(test_data_path /
"gonzo.srdf"),
41 integration_node = Node(
42 package=
"moveit_ros_planning",
43 executable=
"test_rdf_integration",
46 "robot_description": kermit_urdf,
47 "robot_description_semantic": kermit_srdf,
50 "DNE_semantic_timeout": 1.0,
61 launch_testing.actions.ReadyToTest(),
64 {
"integration_node": integration_node},
71 proc_info.assertWaitForShutdown(integration_node, timeout=4000.0)
74 @launch_testing.post_shutdown_test()
78 launch_testing.asserts.assertExitCodes(proc_info, process=integration_node)
def test_gtest_pass(self, proc_info, integration_node)
def test_gtest_run_complete(self, proc_info, integration_node)
def generate_test_description()