def generate_test_description(): # Component yaml files are grouped in separate namespaces robot_description_config = load_file("moveit_resources_panda_description", "urdf/panda.urdf") robot_description = {"robot_description": robot_description_config} robot_description_semantic_config = load_file( "moveit_resources_panda_moveit_config", "config/panda.srdf") robot_description_semantic = { "robot_description_semantic": robot_description_semantic_config } kinematics_yaml = load_yaml("moveit_resources_panda_moveit_config", "config/kinematics.yaml") robot_description_kinematics = { "robot_description_kinematics": kinematics_yaml } joint_limits_yaml = { "robot_description_planning": load_yaml("moveit_resources_panda_moveit_config", "config/joint_limits.yaml") } test_param = load_yaml("moveit_kinematics", "config/panda-kdl-singular-test.yaml") panda_kdl_singular = Node( package="moveit_kinematics", executable="test_kinematics_plugin", name="panda_kdl_singular", parameters=[ robot_description, robot_description_semantic, robot_description_kinematics, joint_limits_yaml, test_param, ], output="screen", ) return ( LaunchDescription([ panda_kdl_singular, KeepAliveProc(), launch_testing.actions.ReadyToTest(), ]), { "panda_kdl_singular": panda_kdl_singular }, )
def generate_test_description(): robot_description_config = load_file("moveit_resources_fanuc_description", "urdf/fanuc.urdf") robot_description = {"robot_description": robot_description_config} robot_description_semantic_config = load_file( "moveit_resources_fanuc_moveit_config", "config/fanuc.srdf") robot_description_semantic = { "robot_description_semantic": robot_description_semantic_config } kinematics_yaml = load_yaml("moveit_resources_fanuc_moveit_config", "config/kinematics.yaml") robot_description_kinematics = { "robot_description_kinematics": kinematics_yaml } joint_limits_yaml = { "robot_description_planning": load_yaml("moveit_resources_fanuc_moveit_config", "config/joint_limits.yaml") } test_param = load_yaml("moveit_kinematics", "config/fanuc-lma-singular-test.yaml") fanuc_lma_singular = Node( package="moveit_kinematics", executable="test_kinematics_plugin", name="fanuc_lma_singular", parameters=[ robot_description, robot_description_semantic, robot_description_kinematics, joint_limits_yaml, test_param, ], output="screen", ) return ( LaunchDescription([ fanuc_lma_singular, KeepAliveProc(), launch_testing.actions.ReadyToTest(), ]), { "fanuc_lma_singular": fanuc_lma_singular }, )
def generate_test_description(): # Component yaml files are grouped in separate namespaces robot_description_config = load_file("moveit_resources_fanuc_description", "urdf/fanuc.urdf") robot_description = {"robot_description": robot_description_config} robot_description_semantic_config = load_file( "moveit_resources_fanuc_moveit_config", "config/fanuc.srdf") robot_description_semantic = { "robot_description_semantic": robot_description_semantic_config } kinematics_yaml = load_yaml("moveit_resources_fanuc_moveit_config", "config/kinematics.yaml") robot_description_kinematics = { "robot_description_kinematics": kinematics_yaml } test_param = load_yaml("moveit_kinematics", "config/fanuc-lma-test.yaml") fanuc_lma = Node( package="moveit_kinematics", executable="test_kinematics_plugin", name="fanuc_lma", parameters=[ robot_description, robot_description_semantic, robot_description_kinematics, test_param, ], output="screen", ) return ( LaunchDescription([ fanuc_lma, KeepAliveProc(), launch_testing.actions.ReadyToTest(), ]), { "fanuc_lma": fanuc_lma }, )
def test_wait_for_wrong_process(self): data = [] self.launch_description.add_entity( launch.actions.RegisterEventHandler( StdoutReadyListener( target_action=KeepAliveProc( ), # We never launched this process ready_txt='Ready', actions=[ launch.actions.OpaqueFunction( function=lambda context: data.append('ok')) ]))) launch_service = launch.LaunchService() launch_service.include_launch_description(self.launch_description) launch_service.run() # We should not get confused by output from another proc self.assertNotIn('ok', data)
def generate_test_description(): return LaunchDescription([KeepAliveProc(), ReadyToTest()])