6 from ament_index_python.packages
import get_package_share_directory
7 from moveit_configs_utils
import MoveItConfigsBuilder
13 .robot_description(file_path=
"config/panda.urdf.xacro")
18 ros2_controllers_path = os.path.join(
21 "ros2_controllers.yaml",
23 ros2_control_node = launch_ros.actions.Node(
24 package=
"controller_manager",
25 executable=
"ros2_control_node",
26 parameters=[ros2_controllers_path],
28 (
"/controller_manager/robot_description",
"/robot_description"),
33 joint_state_broadcaster_spawner = launch_ros.actions.Node(
34 package=
"controller_manager",
37 "joint_state_broadcaster",
38 "--controller-manager-timeout",
40 "--controller-manager",
41 "/controller_manager",
46 panda_arm_controller_spawner = launch_ros.actions.Node(
47 package=
"controller_manager",
49 arguments=[
"panda_arm_controller",
"-c",
"/controller_manager"],
52 psm_gtest = launch_ros.actions.Node(
53 executable=launch.substitutions.PathJoinSubstitution(
55 launch.substitutions.LaunchConfiguration(
"test_binary_dir"),
56 "planning_scene_monitor_test",
60 moveit_config.to_dict(),
65 return launch.LaunchDescription(
67 launch.actions.TimerAction(period=2.0, actions=[ros2_control_node]),
68 launch.actions.TimerAction(
69 period=4.0, actions=[joint_state_broadcaster_spawner]
71 launch.actions.TimerAction(
72 period=6.0, actions=[panda_arm_controller_spawner]
74 launch.actions.TimerAction(period=9.0, actions=[psm_gtest]),
75 launch_testing.actions.ReadyToTest(),
78 "psm_gtest": psm_gtest,
85 self.proc_info.assertWaitForShutdown(psm_gtest, timeout=4000.0)
88 @launch_testing.post_shutdown_test()
92 launch_testing.asserts.assertExitCodes(proc_info, process=psm_gtest)
def test_gtest_pass(self, proc_info, psm_gtest)
def test_gtest_run_complete(self, psm_gtest)
def get_package_share_directory(pkg_name)
def generate_test_description()