ld.add_action( Node(package='tsim', executable='requester', name='requester', output='screen', additional_env={'PYTHONUNBUFFERED': '1'}, parameters=[parameter_path])) ld.add_action( Node(package='tsim', executable='autopilot', name='autopilot', output='screen', additional_env={'PYTHONUNBUFFERED': '1'}, prefix='xterm -e')) return ld if __name__ == '__main__': ld = generate_launch_description() print('Starting introspection of launch description...\n') print(launch.LaunchIntrospector().format_launch_description(ld)) print('\nStarting launch of launch description...\n') #ls = LaunchService(debug=True) ls = launch.LaunchService() ls.include_launch_description(ld) ls.run(shutdown_when_idle=False)
def print_a_python_launch_file(*, python_launch_file_path): """Print the description of a Python launch file to the console.""" launch_description = get_launch_description_from_python_launch_file( python_launch_file_path) print(launch.LaunchIntrospector().format_launch_description( launch_description))
def main(argv=sys.argv[1:]): """Main.""" ld = launch.LaunchDescription() # Prepare the talker node. talker_node = launch_ros.actions.LifecycleNode( node_name='talker', package='lifecycle', node_executable='lifecycle_talker', output='screen') # When the talker reaches the 'inactive' state, make it take the 'activate' transition. register_event_handler_for_talker_reaches_inactive_state = launch.actions.RegisterEventHandler( launch_ros.event_handlers.OnStateTransition( target_lifecycle_node=talker_node, goal_state='inactive', entities=[ launch.actions.LogInfo( msg= "node 'talker' reached the 'inactive' state, 'activating'." ), launch.actions.EmitEvent( event=launch_ros.events.lifecycle.ChangeState( lifecycle_node_matcher=launch.events.matches_action( talker_node), transition_id=lifecycle_msgs.msg.Transition. TRANSITION_ACTIVATE, )), ], )) # When the talker node reaches the 'active' state, log a message and start the listener node. register_event_handler_for_talker_reaches_active_state = launch.actions.RegisterEventHandler( launch_ros.event_handlers.OnStateTransition( target_lifecycle_node=talker_node, goal_state='active', entities=[ launch.actions.LogInfo( msg= "node 'talker' reached the 'active' state, launching 'listener'." ), launch_ros.actions.LifecycleNode( node_name='listener', package='lifecycle', node_executable='lifecycle_listener', output='screen'), ], )) # Make the talker node take the 'configure' transition. emit_event_to_request_that_talker_does_configure_transition = launch.actions.EmitEvent( event=launch_ros.events.lifecycle.ChangeState( lifecycle_node_matcher=launch.events.matches_action(talker_node), transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE, )) # Add the actions to the launch description. # The order they are added reflects the order in which they will be executed. ld.add_action(register_event_handler_for_talker_reaches_inactive_state) ld.add_action(register_event_handler_for_talker_reaches_active_state) ld.add_action(talker_node) ld.add_action(emit_event_to_request_that_talker_does_configure_transition) print('Starting introspection of launch description...') print('') print(launch.LaunchIntrospector().format_launch_description(ld)) print('') print('Starting launch of launch description...') print('') # ls = launch.LaunchService(argv=argv, debug=True) ls = launch.LaunchService(argv=argv) ls.include_launch_description(get_default_launch_description()) ls.include_launch_description(ld) return ls.run()