def test_all_actions_are_matched(): """Test that all execution complete events are matched.""" an_action = LogInfo(msg='some message') other_action = LogInfo(msg='other message') event_handler = OnExecutionComplete(on_completion=lambda *args: None) assert event_handler.matches(ExecutionComplete(action=an_action)) assert event_handler.matches(ExecutionComplete(action=other_action))
def generate_launch_description(): set_tty_launch_config_action = launch.actions.SetLaunchConfiguration( "emulate_tty", "True") # Launch Description ld = launch.LaunchDescription() # Watchdog node watchdog_node = LifecycleNode(package='sw_watchdog', node_executable='simple_watchdog', node_namespace='', node_name='simple_docker_watchdog', output='screen', arguments=['220', '--publish', '--activate'] #arguments=['__log_level:=debug'] ) # Make the Watchdog node take the 'activate' transition watchdog_activate_trans_event = EmitEvent(event=ChangeState( lifecycle_node_matcher=launch.events.matches_action(watchdog_node), transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE, )) # When the watchdog reaches the 'inactive' state from 'active', log message # and restart monitored entity (via docker) watchdog_inactive_handler = RegisterEventHandler( OnStateTransition( target_lifecycle_node=watchdog_node, start_state='deactivating', goal_state='inactive', entities=[ # Log LogInfo(msg="Watchdog transitioned to 'INACTIVE' state."), # Restart the monitored entity OpaqueFunction(function=docker_restart), # Change state event (inactive -> active) watchdog_activate_trans_event, ], )) # When Shutdown is requested, clean up docker shutdown_handler = RegisterEventHandler( OnShutdown( on_shutdown=[ # Log LogInfo(msg="watchdog_in_docker was asked to shutdown."), # Clean up docker OpaqueFunction(function=docker_stop), ], )) # Add the actions to the launch description. # The order they are added reflects the order in which they will be executed ld.add_action(set_tty_launch_config_action) ld.add_action(OpaqueFunction(function=docker_run)) ld.add_action(watchdog_node) ld.add_action(watchdog_inactive_handler) ld.add_action(shutdown_handler) return ld
def test_single_action_is_matched(): """Test that only the target action execution complete event is matched.""" an_action = LogInfo(msg='some message') event_handler = OnExecutionComplete(target_action=an_action, on_completion=lambda *args: None) other_action = LogInfo(msg='other message') assert event_handler.matches(ExecutionComplete(action=an_action)) assert not event_handler.matches(ExecutionComplete(action=other_action))
def generate_launch_description(): share_dir = get_package_share_directory('ros2_ouster') parameter_file = LaunchConfiguration('params_file') node_name = 'ouster_driver' params_declare = DeclareLaunchArgument( 'params_file', default_value=os.path.join(share_dir, 'params', 'os1.yaml'), description='FPath to the ROS2 parameters file to use.') driver_node = LifecycleNode( package='ros2_ouster', executable='ouster_driver', name=node_name, output='screen', emulate_tty=True, parameters=[parameter_file], namespace='/', ) configure_event = EmitEvent(event=ChangeState( lifecycle_node_matcher=matches_action(driver_node), transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE, )) activate_event = RegisterEventHandler( OnStateTransition( target_lifecycle_node=driver_node, goal_state='inactive', entities=[ LogInfo( msg="[LifecycleLaunch] Ouster driver node is activating."), EmitEvent(event=ChangeState( lifecycle_node_matcher=matches_action(driver_node), transition_id=lifecycle_msgs.msg.Transition. TRANSITION_ACTIVATE, )), ], )) # TODO make lifecycle transition to shutdown before SIGINT shutdown_event = RegisterEventHandler( OnShutdown(on_shutdown=[ EmitEvent(event=ChangeState( lifecycle_node_matcher=matches_node_name(node_name=node_name), transition_id=lifecycle_msgs.msg.Transition. TRANSITION_ACTIVE_SHUTDOWN, )), LogInfo(msg="[LifecycleLaunch] Ouster driver node is exiting."), ], )) return LaunchDescription([ params_declare, driver_node, activate_event, configure_event, shutdown_event, ])
def test_log_info_methods(): """Test the methods of the LogInfo class.""" launch_context = LaunchContext() log_info = LogInfo(msg='') assert perform_substitutions(launch_context, log_info.msg) == '' log_info = LogInfo(msg='foo') assert perform_substitutions(launch_context, log_info.msg) == 'foo' log_info = LogInfo(msg=['foo', 'bar', 'baz']) assert perform_substitutions(launch_context, log_info.msg) == 'foobarbaz'
def generate_launch_description(): """Generate launch description with multiple components.""" container = ComposableNodeContainer( node_name='my_container', node_namespace='my_namespace', package='rclcpp_components', node_executable='component_container', composable_node_descriptions=[ ComposableNode(package='demo_nodes_cpp', node_plugin='demo_nodes_cpp::Talker', node_name='talker'), ComposableNode(package='sw_watchdog', node_plugin='sw_watchdog::SimpleHeartbeat', node_name='heartbeat', parameters=[{ 'period': 200 }], extra_arguments=[{ 'use_intra_process_comms': True }]), ], output='screen') # When Shutdown is requested (launch), clean up all child processes shutdown_handler = RegisterEventHandler( OnShutdown( on_shutdown=[ # Log LogInfo(msg="heartbeat_composition was asked to shutdown."), # Clean up OpaqueFunction(function=group_stop), ], )) return launch.LaunchDescription([container, shutdown_handler])
def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('my_msg', default_value='Hello World!', description='This is a description!'), LogInfo(msg=LaunchConfiguration('my_msg')) ])
def generate_launch_description(): # 0: Default QoSProfile(depth=10) qos_profile = LaunchConfiguration('qos_profile', default=0) param_dir = LaunchConfiguration( 'param_dir', default=os.path.join(get_package_share_directory('examples_rclcpp'), 'param', 'examples_parameter.yaml')) namespace = LaunchConfiguration('ns', default='example') return LaunchDescription([ LogInfo(msg=['Execute subscriber!!']), DeclareLaunchArgument('param_dir', default_value=param_dir, description='Specifying parameter direction'), DeclareLaunchArgument( 'qos_profile', default_value=qos_profile, description= 'Specifying qos_profile to publisher. Default QoSProfile(depth=10)' ), DeclareLaunchArgument('namespace', default_value='ns', description='Specifying namespace to node'), Node( node_namespace=namespace, package='examples_rclcpp', node_executable='subscriber', # node_name='observer', parameters=[param_dir], arguments=['-q', qos_profile], # remappings=[('count', 'count')], output='screen'), ])
def generate_launch_description(): config = DeclareLaunchArgument( 'yaml', default_value=join(get_package_share_directory('unbag2'), 'cfg', 'unbag2.yml'), description= 'path to the config file, by default the one stored in this package.') files = DeclareLaunchArgument( 'files', default_value='', description= 'string containing a list of all files/directories to try to read as ' 'bag files') config_param = LaunchConfiguration('yaml') files_param = LaunchConfiguration('files') return LaunchDescription([ files, config, LogInfo(msg=["Un-Bagging files: ", files_param]), Node(package='unbag2', executable='unbag2', output='screen', name='unbag2', parameters=[config_param, { 'files': files_param }]) ])
def generate_launch_description(): set_tty_launch_config_action = launch.actions.SetLaunchConfiguration( "emulate_tty", "True") watchdog_node = LifecycleNode( package='sw_watchdog', node_executable='windowed_watchdog', node_namespace='', node_name='windowed_watchdog', output='screen', arguments=['220', '3', '--publish', '--activate'] #arguments=['__log_level:=debug'] ) # When the watchdog reaches the 'inactive' state, log a message watchdog_inactive_handler = RegisterEventHandler( OnStateTransition( target_lifecycle_node=watchdog_node, goal_state='inactive', entities=[ # Log LogInfo(msg="Watchdog transitioned to 'INACTIVE' state."), ], )) return launch.LaunchDescription([ set_tty_launch_config_action, watchdog_node, watchdog_inactive_handler ])
def generate_launch_description(): executable = ExecutableInPackage(package='tf2_ros', executable='static_transform_publisher') exec_sick_scan2 = ExecutableInPackage(package='sick_scan2', executable='sick_generic_caller') ############################################################################################ # # modify your settings here: # print( "##########################################################################" ) print( "# ROS2 Driver for SICK SCANNER (SET YOUR SETTING ACCORDING TO YOUR SETUP!" ) print( "##########################################################################" ) print("Your Settings:") hostname = '192.168.0.71' port = "2112" name = "sick_tim_5xx" print("hostname [IP-address of scanner ]: " + hostname) print("port [IP-port of scanner ]: " + port) print("name [to identify scanner type]: " + name) print( "##########################################################################" ) print("# STARTING NODE") print( "##########################################################################" ) # TODO(wjwwood): Use a substitution to find share directory once this is implemented in launch urdf = os.path.join(get_package_share_directory('sick_scan2'), 'launch', 'single_rrbot.urdf') yamlFileName = os.path.join(get_package_share_directory('sick_scan2'), 'launch', 'sick_tim_5xx.yaml') # Yaml-File reserved for future use ... return LaunchDescription([ LogInfo(msg=['Try to start world <-> laser']), launch.actions.ExecuteProcess( cmd=[executable, '0', '0', '0', '0', '0', '0', 'world', 'laser'], output='screen'), # # YAML-File support seems to be buggy. ros2 param crashes ... # launch.actions.ExecuteProcess( # cmd=[exec_sick_scan2, '__params:='+yamlFileName], output='screen'), launch.actions.ExecuteProcess(cmd=[ exec_sick_scan2, '__hostname:=' + hostname + " __port:=" + port + " __name:=" + name ], output='screen') ])
def func_get_joyconfig_file_name(context): param_file = os.path.join( get_package_share_directory('raspimouse_ros2_examples'), 'config', 'joy_' + context.launch_configurations['joyconfig'] + '.yml') if os.path.exists(param_file): return [SetLaunchConfiguration('joyconfig_filename', param_file)] else: return [LogInfo(msg=param_file + " is not exist.")]
def func_get_joyconfig_filename(context): param_file = os.path.join( get_package_share_directory('consai2r2_teleop'), 'config', 'joy_' + context.launch_configurations['joyconfig'] + '.yaml') if os.path.exists(param_file): return [SetLaunchConfiguration('joyconfig_filename', param_file)] else: return [LogInfo(msg=param_file + ' is not exist.')]
def test_bad_construction(): """Test bad construction parameters.""" with pytest.raises(ValueError): OnExecutionComplete(target_action='not-an-action', on_completion=lambda *args: None) with pytest.raises(ValueError): OnExecutionComplete( target_action=LogInfo(msg='some message'), on_completion='not-a-callable-nor-an-action-iterable')
def generate_launch_description(): return LaunchDescription([ ############################################################# LogInfo(msg="launch realsense_ros2_camera"), Node( package="face_predictor", node_executable="face_predictor", output="screen", ), ])
def generate_launch_description(): return LaunchDescription([ LogInfo(msg=[ 'Including launch file located at: ', ThisLaunchFileDir(), '/nodes.launch.py' ]), IncludeLaunchDescription( PythonLaunchDescriptionSource( [ThisLaunchFileDir(), '/nodes.launch.py'])), ])
def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time') params_file = LaunchConfiguration('params_file') default_params_file = os.path.join( get_package_share_directory("slam_toolbox"), 'config', 'mapper_params_online_async.yaml') declare_use_sim_time_argument = DeclareLaunchArgument( 'use_sim_time', default_value='true', description='Use simulation/Gazebo clock') declare_params_file_cmd = DeclareLaunchArgument( 'params_file', default_value=default_params_file, description= 'Full path to the ROS2 parameters file to use for the slam_toolbox node' ) # If the provided param file doesn't have slam_toolbox params, we must pass the # default_params_file instead. This could happen due to automatic propagation of # LaunchArguments. See: # https://github.com/ros-planning/navigation2/pull/2243#issuecomment-800479866 has_node_params = HasNodeParams(source_file=params_file, node_name='slam_toolbox') actual_params_file = PythonExpression([ '"', params_file, '" if ', has_node_params, ' else "', default_params_file, '"' ]) log_param_change = LogInfo(msg=[ 'provided params_file ', params_file, ' does not contain slam_toolbox parameters. Using default: ', default_params_file ], condition=UnlessCondition(has_node_params)) start_async_slam_toolbox_node = Node( parameters=[actual_params_file, { 'use_sim_time': use_sim_time }], package='slam_toolbox', executable='async_slam_toolbox_node', name='slam_toolbox', output='screen') ld = LaunchDescription() ld.add_action(declare_use_sim_time_argument) ld.add_action(declare_params_file_cmd) ld.add_action(log_param_change) ld.add_action(start_async_slam_toolbox_node) return ld
def launch_setup(context): configs_dir = os.path.join(get_package_share_directory("ov_msckf"), "config") available_configs = os.listdir(configs_dir) config = LaunchConfiguration("config").perform(context) if not config in available_configs: return [ LogInfo( msg= "ERROR: unknown config: '{}' - Available configs are: {} - not starting OpenVINS" .format(config, ", ".join(available_configs))) ] config_path = os.path.join( get_package_share_directory("ov_msckf"), "config", config, "estimator_config.yaml", ) node1 = Node( package="ov_msckf", executable="run_subscribe_msckf", condition=IfCondition(LaunchConfiguration("ov_enable")), namespace=LaunchConfiguration("namespace"), parameters=[ { "verbosity": LaunchConfiguration("verbosity") }, { "use_stereo": LaunchConfiguration("use_stereo") }, { "max_cameras": LaunchConfiguration("max_cameras") }, { "config_path": config_path }, ], ) node2 = Node( package="rviz2", executable="rviz2", condition=IfCondition(LaunchConfiguration("rviz_enable")), arguments=[ "-d" + os.path.join(get_package_share_directory("ov_msckf"), "launch", "display_ros2.rviz"), "--ros-args", "--log-level", "warn", ], ) return [node1, node2]
def generate_launch_description(): return LaunchDescription([ LogInfo(msg=['Execute the rqt_example with turtlesim node.']), Node(namespace='turtle1', package='rqt_example', executable='rqt_example', name='rqt_example', output='screen'), Node(package='turtlesim', executable='turtlesim_node', name='turtlesim', output='screen') ])
def generate_launch_description(): """Launch the example.launch.py launch file.""" return LaunchDescription([ LogInfo(msg=[ 'Including launch file located at: ', ThisLaunchFileDir(), '/example.launch.py' ]), IncludeLaunchDescription( PythonLaunchDescriptionSource( [ThisLaunchFileDir(), '/example.launch.py']), launch_arguments={'node_prefix': 'FOO'}.items(), ), ])
def generate_launch_description(): emit_shutdown_action = launch.actions.Shutdown( reason='launch is shutting down') return LaunchDescription([ Node(package='petra_drivers', node_executable='Screen', node_name='Screen', output='screen'), #Node( # package='petra_drivers', # node_executable='Keyboard', # node_name='Keyboard', # output='screen' #), #Node( # package='petra_drivers', # node_executable='RobotDummy', # node_name='RobotDummy' #), Node(package='petra_services', node_executable='Communication', node_name='Communication'), Node(package='petra_services', node_executable='Navigation2Dummy', node_name='Navigation2Dummy'), Node(package='petra_services', node_executable='PatientMonitoringDummy', node_name='PatientMonitoringDummy'), Node(package='petra_drivers', node_executable='PairingModuleDummy', node_name='PairingModuleDummy'), Node(package='petra_drivers', node_executable='ManipulatorDummy', node_name='ManipulatorDummy'), Node(package='petra_drivers', node_executable='BatteryDummy', node_name='BatteryDummy'), Node( package='petra_central_control', node_executable='PeTRACentralControl', node_name='PeTRACentralControl', output='screen', on_exit=[ LogInfo(msg=[ "PeTRACentralControl has stopped. Stopping everything..." ]), emit_shutdown_action ], ) ])
def generate_launch_description(): return LaunchDescription([ LogInfo(msg=['Execute two launch files!!']), IncludeLaunchDescription( PythonLaunchDescriptionSource( [ThisLaunchFileDir(), '/pub.launch.py']), launch_arguments={'ns': 'new_examples'}.items(), ), IncludeLaunchDescription( PythonLaunchDescriptionSource( [ThisLaunchFileDir(), '/sub.launch.py']), launch_arguments={'ns': 'new_examples'}.items(), ), ])
def generate_launch_description(): # [RECOMMENDED] If you want handle arguments out of this launch file, # you have to set LaunchConfiguration # If you set arguments below, you can't access topic_name CLI or other launch files # qos_profile = 0 # 0: Default QoSProfile(depth=10) qos_profile = LaunchConfiguration('qos_profile', default=0) namespace = LaunchConfiguration('ns', default='example') return LaunchDescription([ LogInfo(msg=['Execute two ' 'publisher' 's has different node name!!']), # [RECOMMENDED] This func allows you to expose the arguments DeclareLaunchArgument( 'topic_name', default_value='count', description='Specifying topic name to publisher'), DeclareLaunchArgument( 'qos_profile', default_value=qos_profile, description= 'Specifying qos_profile to publisher. Default QoSProfile(depth=10)' ), DeclareLaunchArgument('namespace', default_value='ns', description='Specifying namespace to node'), Node(node_namespace=namespace, package='examples_rclcpp', node_executable='publisher', node_name='first_pub', parameters=[{ 'message': 'First Pub' }], arguments=['-q', qos_profile], output='screen'), Node(node_namespace=namespace, package='examples_rclcpp', node_executable='publisher', node_name='second_pub', parameters=[{ 'message': 'Second Pub' }], arguments=['-q', qos_profile], output='screen'), ])
def generate_test_description(): """Launch the example.launch.py launch file.""" return LaunchDescription([ LogInfo(msg=[ 'Including launch file located at: ', get_package_share_directory('pub_sub_tests'), '/pub_sub_launch.py' ]), IncludeLaunchDescription( PythonLaunchDescriptionSource([ get_package_share_directory('pub_sub_tests'), '/pub_sub_launch.py' ]), launch_arguments={'node_prefix': 'FOO'}.items(), ), launch_testing.actions.ReadyToTest(), ])
def generate_launch_description(): param_dir = LaunchConfiguration( 'param_dir', default=os.path.join( get_package_share_directory('turtlebot3_fake_node'), 'param', TURTLEBOT3_MODEL + '.yaml')) rviz_dir = LaunchConfiguration( 'rviz_dir', default=os.path.join( get_package_share_directory('turtlebot3_fake_node'), 'launch')) use_sim_time = LaunchConfiguration('use_sim_time', default='false') urdf_file_name = 'turtlebot3_' + TURTLEBOT3_MODEL + '.urdf' urdf = os.path.join( get_package_share_directory('turtlebot3_description'), 'urdf', urdf_file_name) return LaunchDescription([ LogInfo(msg=['Execute Turtlebot3 Fake Node!!']), DeclareLaunchArgument( 'param_dir', default_value=param_dir, description='Specifying parameter direction'), IncludeLaunchDescription( PythonLaunchDescriptionSource([rviz_dir, '/rviz2.launch.py'])), Node( package='turtlebot3_fake_node', node_executable='turtlebot3_fake_node', parameters=[param_dir], output='screen'), Node( package='robot_state_publisher', node_executable='robot_state_publisher', node_name='robot_state_publisher', output='screen', parameters=[{'use_sim_time': use_sim_time}], arguments=[urdf]), ])
def generate_launch_description(): ld = LaunchDescription() use_sim_time = LaunchConfiguration('use_sim_time', default='false') package_name = 'robot_sim' urdf_name = "robot.urdf" package_path = FindPackageShare(package=package_name).find(package_name) urdf_path = os.path.join(package_path, 'urdf', urdf_name) param_path = os.path.join(package_path, 'param', 'params.yaml') launch_path = os.path.join(package_path, 'launch') with open(urdf_path, 'r') as urdf: robot_desc = urdf.read() info = LogInfo(msg=['Execute Robot Sim']) robot_sim_node = Node(package=package_name, executable='robot_sim', parameters=[param_path], output='screen') robot_state_publisher_node = Node(package='robot_state_publisher', executable='robot_state_publisher', name='robot_state_publisher', output='screen', arguments=[urdf_path], parameters=[{ 'use_sim_time': use_sim_time, 'robot_description': robot_desc }]) rviz_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join(launch_path, 'rviz2.launch.py'))) ld.add_action(info) ld.add_action(robot_sim_node) ld.add_action(robot_state_publisher_node) ld.add_action(rviz_launch) return ld
def generate_launch_description(): """Launch the example.launch.py launch file.""" return LaunchDescription([ launch.actions.DeclareLaunchArgument( 'image1', default_value='bar.png', description='image arg that overlaps with included arg', ), LogInfo(msg=[ 'Including launch file located at: ', ThisLaunchFileDir(), '/example.launch.py' ]), IncludeLaunchDescription( PythonLaunchDescriptionSource( [ThisLaunchFileDir(), '/example.launch.py']), launch_arguments={'node_name': 'bar'}.items(), ), ])
def generate_launch_description(): ld = LaunchDescription([ LogInfo(msg = ['Launch ;'+PACKAGE_NAME]), ]) node = launch_ros.actions.LifecycleNode( node_name = PACKAGE_NAME, package = PACKAGE_NAME, node_executable = NODE_EXECUTABLE, node_namespace = NODE_NAMESPACE, parameters=[], output = 'screen', ) # When the node reaches the 'inactive' state, make it to the 'activate' evt_hwnd = launch.actions.RegisterEventHandler( launch_ros.event_handlers.OnStateTransition( target_lifecycle_node = node, goal_state='inactive', entities=[ launch.actions.LogInfo( msg = PACKAGE_NAME + " reached the 'inactive' state, 'activating'."), launch.actions.EmitEvent( event=launch_ros.events.lifecycle.ChangeState( lifecycle_node_matcher=launch.events.matches_action(node), transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE, )), ], ) ) # Make the node take the 'configure' transition. emit_configure_transition = launch.actions.EmitEvent( event=launch_ros.events.lifecycle.ChangeState( lifecycle_node_matcher=launch.events.matches_action(node), transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE, ) ) ld.add_action(evt_hwnd) ld.add_action(node) ld.add_action(emit_configure_transition) return ld
def generate_launch_description(): auto_activate = LaunchConfiguration('auto_activate', default='False') namespace = LaunchConfiguration('ns', default='example') return LaunchDescription([ LogInfo(msg=['Execute lifecycle node!!']), DeclareLaunchArgument('auto_activate', default_value=auto_activate, description='Specifying auto activate node'), DeclareLaunchArgument('ns', default_value=namespace, description='Specifying namespace to node'), Node(node_namespace=namespace, package='examples_lifecycle', node_executable='robot', parameters=[{ 'robot_name': 'C3PO' }], arguments=['-a', auto_activate], output='screen'), ])
def generate_launch_description(): usb_port = LaunchConfiguration('usb_port', default='/dev/ttyUSB0') baud_rate = LaunchConfiguration('baud_rate', default=1000000) param_dir = LaunchConfiguration( 'param_dir', default=os.path.join( get_package_share_directory('pincher_x100_controller'), 'param', 'pincher_x100_controller_params.yaml')) return LaunchDescription([ LogInfo(msg=['Execute PincherX 100 Controller!!']), DeclareLaunchArgument('param_dir', default_value=param_dir, description='Specifying parameter direction'), Node( package='pincher_x100_controller', node_executable='pincher_x100_controller', # node_name='pc_x_controller', parameters=[param_dir], arguments=['-d', usb_port, baud_rate], output='screen'), ])