launch.actions package
Submodules
- launch.actions.append_environment_variable module
- launch.actions.conftest module
- launch.actions.declare_launch_argument module
- launch.actions.emit_event module
- launch.actions.execute_local module
ExecuteLocalExecuteLocal.__init__()ExecuteLocal.emulate_ttyExecuteLocal.execute()ExecuteLocal.get_asyncio_future()ExecuteLocal.get_stderr()ExecuteLocal.get_stdout()ExecuteLocal.get_sub_entities()ExecuteLocal.outputExecuteLocal.prepare()ExecuteLocal.process_descriptionExecuteLocal.process_detailsExecuteLocal.return_codeExecuteLocal.shellExecuteLocal.sigkill_timeoutExecuteLocal.sigterm_timeout
- launch.actions.execute_process module
- launch.actions.for_loop module
- launch.actions.group_action module
- launch.actions.include_launch_description module
- launch.actions.log_info module
- launch.actions.opaque_coroutine module
- launch.actions.opaque_function module
- launch.actions.pop_environment module
- launch.actions.pop_launch_configurations module
- launch.actions.push_environment module
- launch.actions.push_launch_configurations module
- launch.actions.register_event_handler module
- launch.actions.reset_environment module
- launch.actions.reset_launch_configurations module
- launch.actions.set_environment_variable module
- launch.actions.set_launch_configuration module
- launch.actions.shutdown_action module
- launch.actions.timer_action module
- launch.actions.unregister_event_handler module
- launch.actions.unset_environment_variable module
- launch.actions.unset_launch_configuration module
Module contents
actions Module.
- class launch.actions.AppendEnvironmentVariable[source]
Bases:
ActionAction that appends to an environment variable if it exists and sets it if it does not.
It can optionally prepend instead of appending. It can also optionally use a custom separator, with the default being a platform-specific separator, os.pathsep.
- __init__(name: str | Path | Substitution | Iterable[str | Path | Substitution], value: str | Path | Substitution | Iterable[str | Path | Substitution], prepend: bool | str | Path | Substitution | Iterable[str | Path | Substitution] = False, separator: str | Path | Substitution | Iterable[str | Path | Substitution] = ':', **kwargs) None[source]
Create an AppendEnvironmentVariable action.
All parameters can be provided as substitutions. A substitution for the prepend parameter will be coerced to bool following YAML rules.
- Parameters:
name – the name of the environment variable
value – the value to set or append
prepend – whether the value should be prepended instead
separator – the separator to use, defaulting to a platform-specific separator
- execute(context: LaunchContext) None[source]
Execute the action.
- property name: List[Substitution]
Getter for the name of the environment variable to be set or appended to.
- property prepend: List[Substitution] | int | float | bool | str | List[int | List[Substitution]] | List[float | List[Substitution]] | List[bool | List[Substitution]] | List[str | List[Substitution]]
Getter for the prepend flag.
- property separator: List[Substitution]
Getter for the separator.
- property value: List[Substitution]
Getter for the value of the environment variable to be set or appended.
- class launch.actions.DeclareLaunchArgument[source]
Bases:
ActionAction that declares a new launch argument.
A launch argument is stored in a “launch configuration” of the same name. See
launch.actions.SetLaunchConfigurationandlaunch.substitutions.LaunchConfiguration.Any launch arguments declared within a
launch.LaunchDescriptionwill be exposed as arguments when that launch description is included, e.g. as additional parameters in thelaunch.actions.IncludeLaunchDescriptionaction or as command-line arguments when launched withros2 launch ....In addition to the name, which is also where the argument result is stored, launch arguments may have a default value, a list of valid value choices, and a description. If a default value is given, then the argument becomes optional and the default value is placed in the launch configuration instead. If no default value is given and no value is given when including the launch description, then an error occurs. If a choice list is given, and the given value is not in it, an error occurs.
The default value may use Substitutions, but the name and description can only be Text, since they need a meaningful value before launching, e.g. when listing the command-line arguments.
Note that declaring a launch argument needs to be in a part of the launch description that is describable without launching. For example, if you declare a launch argument with this action from within a condition group or as a callback to an event handler, then it may not be possible for a tool like
ros2 launchto know about the argument before launching the launch description. In such cases, the argument will not be visible on the command line but may raise an exception if that argument is not satisfied once visited (and has no default value).Put another way, the post-condition of this action being visited is either that a launch configuration of the same name is set with a value or an exception is raised because none is set and there is no default value. However, the pre-condition does not guarantee that the argument was visible if behind condition or situational inclusions.
>>> ld = LaunchDescription([ ... DeclareLaunchArgument('simple_argument'), ... DeclareLaunchArgument('with_default_value', default_value='default'), ... DeclareLaunchArgument( ... 'with_default_and_description', ... default_value='some_default', ... description='this argument is used to configure ...'), ... DeclareLaunchArgument( ... 'mode', ... default_value='A', ... description='Choose between mode A and mode B', ... choices=['A', 'B']), ... # other actions here, ... ... ])
<launch> <arg name="simple_argument"/> <arg name="with_default_value" default_value="default"/> <arg name="with_default_and_description" default_value="some_default" description="this argument is used to configure ..."/> </launch>
- __init__(name: str, *, default_value: str | Path | Substitution | Iterable[str | Path | Substitution] | None = None, description: str | None = None, choices: List[str] | None = None, **kwargs) None[source]
Create a DeclareLaunchArgument action.
- property default_value: List[Substitution] | None
Getter for self.__default_value.
- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.EmitEvent[source]
Bases:
ActionAction that emits an event when executed.
- property event
Getter for self.__event.
- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.ExecuteLocal[source]
Bases:
ActionAction that begins executing a process on the local system and sets up event handlers.
- __init__(*, process_description: ~launch.descriptions.executable.Executable, shell: bool = False, sigterm_timeout: str | ~pathlib.Path | ~launch.substitution.Substitution | ~typing.Iterable[str | ~pathlib.Path | ~launch.substitution.Substitution] = <launch.substitutions.launch_configuration.LaunchConfiguration object>, sigkill_timeout: str | ~pathlib.Path | ~launch.substitution.Substitution | ~typing.Iterable[str | ~pathlib.Path | ~launch.substitution.Substitution] = <launch.substitutions.launch_configuration.LaunchConfiguration object>, emulate_tty: bool = False, output: str | ~pathlib.Path | ~launch.substitution.Substitution | ~typing.Iterable[str | ~pathlib.Path | ~launch.substitution.Substitution] = 'log', output_format: str = '[{this.process_description.final_name}] {line}', cached_output: bool = False, log_cmd: bool = False, on_exit: ~launch.launch_description_entity.LaunchDescriptionEntity | ~typing.Iterable[~launch.launch_description_entity.LaunchDescriptionEntity] | ~typing.Callable[[~launch.events.process.process_exited.ProcessExited, ~launch.launch_context.LaunchContext], ~launch.launch_description_entity.LaunchDescriptionEntity | ~typing.Iterable[~launch.launch_description_entity.LaunchDescriptionEntity] | None] | None = None, respawn: bool | str | ~pathlib.Path | ~launch.substitution.Substitution | ~typing.Iterable[str | ~pathlib.Path | ~launch.substitution.Substitution] = False, respawn_delay: float | None = None, respawn_max_retries: int = -1, **kwargs) None[source]
Construct an ExecuteLocal action.
Many arguments are passed eventually to
subprocess.Popen, so see the documentation for the class for additional details.This action, once executed, registers several event handlers for various process related events and will also emit events asynchronously when certain events related to the process occur.
Handled events include:
launch.events.process.ShutdownProcess:
begins standard shutdown procedure for a running executable
launch.events.process.SignalProcess:
passes the signal provided by the event to the running process
launch.events.process.ProcessStdin:
passes the text provided by the event to the stdin of the process
launch.events.Shutdown:
same as ShutdownProcess
Emitted events include:
launch.events.process.ProcessStarted:
emitted when the process starts
launch.events.process.ProcessExited:
emitted when the process exits
event contains return code
launch.events.process.ProcessStdout and launch.events.process.ProcessStderr:
emitted when the process produces data on either the stdout or stderr pipes
event contains the data from the pipe
Note that output is just stored in this class and has to be properly implemented by the event handlers for the process’s ProcessIO events.
- Param:
process_description the launch.descriptions.Executable to execute as a local process
- Param:
shell if True, a shell is used to execute the cmd
- Param:
sigterm_timeout time until shutdown should escalate to SIGTERM, as a string or a list of strings and Substitutions to be resolved at runtime, defaults to the LaunchConfiguration called ‘sigterm_timeout’
- Param:
sigkill_timeout time until escalating to SIGKILL after SIGTERM, as a string or a list of strings and Substitutions to be resolved at runtime, defaults to the LaunchConfiguration called ‘sigkill_timeout’
- Param:
emulate_tty emulate a tty (terminal), defaults to False, but can be overridden with the LaunchConfiguration called ‘emulate_tty’, the value of which is evaluated as true or false according to
evaluate_condition_expression(). ThrowsInvalidConditionExpressionErrorif the ‘emulate_tty’ configuration does not represent a boolean.- Param:
output configuration for process output logging. Defaults to ‘log’ i.e. log both stdout and stderr to launch main log file and stderr to the screen. Overridden externally by the OVERRIDE_LAUNCH_PROCESS_OUTPUT envvar value. See launch.logging.get_output_loggers() documentation for further reference on all available options.
- Param:
output_format for logging each output line, supporting str.format() substitutions with the following keys in scope: line to reference the raw output line and this to reference this action instance.
- Param:
log_cmd if True, prints the final cmd before executing the process, which is useful for debugging when substitutions are involved.
- Param:
cached_output if True, both stdout and stderr will be cached. Use get_stdout() and get_stderr() to read the buffered output.
- Param:
on_exit list of actions to execute upon process exit.
- Param:
respawn if ‘True’, relaunch the process that abnormally died. Either a boolean or a Substitution to be resolved at runtime. Defaults to ‘False’.
- Param:
respawn_delay a delay time to relaunch the died process if respawn is ‘True’.
- Param:
respawn_max_retries number of times to respawn the process if respawn is ‘True’. A negative value will respawn an infinite number of times (default behavior).
- property emulate_tty
Getter for emulate_tty.
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
This does the following: - register an event handler for the shutdown process event - register an event handler for the signal process event - register an event handler for the stdin event - configures logging for the IO process event - create a task for the coroutine that monitors the process
- get_asyncio_future() Future | None[source]
Return an asyncio Future, used to let the launch system know when we’re done.
- get_stderr()[source]
Get cached stdout.
- Raises:
RuntimeError – if cached_output is false.
- get_stdout()[source]
Get cached stdout.
- Raises:
RuntimeError – if cached_output is false.
- property output
Getter for output.
- prepare(context: LaunchContext)[source]
Prepare the action for execution.
- property process_description
Getter for process_description.
- property process_details
Getter for the process details, e.g. name, pid, cmd, etc., or None if not started.
- property return_code
Get the process return code, None if it hasn’t finished.
- property shell
Getter for shell.
- property sigkill_timeout
Getter for sigkill timeout.
- property sigterm_timeout
Getter for sigterm timeout.
- class launch.actions.ExecuteProcess[source]
Bases:
ExecuteLocalAction that begins executing a process and sets up event handlers for it.
Simple example:
>>> ld = LaunchDescription([ ... ExecuteProcess( ... cmd=['ls', '-las'], ... name='my_ls_process', # this is optional ... output='both', ... ), ... ])
<launch> <executable cmd="ls -las" name="my_ls_process" output="both"/> </launch>
Substitutions in the command:
>>> ld = LaunchDescription([ ... DeclareLaunchArgument(name='file_path', description='file path to cat'), ... ExecuteProcess( ... # each item of the command arguments' list can be: ... # a string ('cat'), ... # a substitution (`LaunchConfiguration('file_path')`), ... # or a list of string/substitutions ... # (`[LaunchConfiguration('directory'), '/file.txt']`) ... cmd=['cat', LaunchConfiguration('file_path')], ... ), ... ])
<launch> <arg name="file_path" description="path of the file to cat"/> <executable cmd="cat $(var file_path)"/> </launch>
Optional cli argument:
>>> ld = LaunchDescription([ ... DeclareLaunchArgument(name='open_gui', default_value='False'), ... ExecuteProcess( ... cmd=['my_cmd', '--open-gui'], ... condition=IfCondition(LaunchConfiguration('open_gui')), ... ), ... ExecuteProcess( ... cmd=['my_cmd'], ... condition=UnlessCondition(LaunchConfiguration('open_gui')), ... ), ... ])
<launch> <arg name="open_gui" description="when truthy, the gui will be opened"/> <executable cmd="my_cmd --open-gui" if="$(var open_gui)"/> <executable cmd="my_cmd" unless="$(var open_gui)"/> </launch>
Environment variables:
>>> ld = LaunchDescription([ ... ExecuteProcess( ... cmd=['my_cmd'], ... additional_env={'env_variable': 'env_var_value'}, ... ), ... ])
<launch> <executable cmd="my_cmd"> <env name="env_variable" value="env_var_value"/> </executable> </launch>
- __init__(*, cmd: Iterable[str | Path | Substitution | Iterable[str | Path | Substitution]], prefix: str | Path | Substitution | Iterable[str | Path | Substitution] | None = None, name: str | Path | Substitution | Iterable[str | Path | Substitution] | None = None, cwd: str | Path | Substitution | Iterable[str | Path | Substitution] | None = None, env: Dict[str | Path | Substitution | Iterable[str | Path | Substitution], str | Path | Substitution | Iterable[str | Path | Substitution]] | None = None, additional_env: Dict[str | Path | Substitution | Iterable[str | Path | Substitution], str | Path | Substitution | Iterable[str | Path | Substitution]] | None = None, **kwargs) None[source]
Construct an ExecuteProcess action.
Many arguments are passed eventually to
subprocess.Popen, so see the documentation for the class for additional details.This action, once executed, registers several event handlers for various process related events and will also emit events asynchronously when certain events related to the process occur.
Handled events include:
launch.events.process.ShutdownProcess:
begins standard shutdown procedure for a running executable
launch.events.process.SignalProcess:
passes the signal provided by the event to the running process
launch.events.process.ProcessStdin:
passes the text provided by the event to the stdin of the process
launch.events.Shutdown:
same as ShutdownProcess
Emitted events include:
launch.events.process.ProcessStarted:
emitted when the process starts
launch.events.process.ProcessExited:
emitted when the process exits
event contains return code
launch.events.process.ProcessStdout and launch.events.process.ProcessStderr:
emitted when the process produces data on either the stdout or stderr pipes
event contains the data from the pipe
Note that output is just stored in this class and has to be properly implemented by the event handlers for the process’s ProcessIO events.
- Param:
cmd a list where the first item is the executable and the rest are arguments to the executable, each item may be a string or a list of strings and Substitutions to be resolved at runtime
- Param:
cwd the directory in which to run the executable
- Param:
name the label used to represent the process, as a string or a Substitution to be resolved at runtime, defaults to the basename of the executable
- Param:
env dictionary of environment variables to be used, starting from a clean environment. If ‘None’, the current environment is used.
- Param:
additional_env dictionary of environment variables to be added. If ‘env’ was None, they are added to the current environment. If not, ‘env’ is updated with additional_env.
- Param:
shell if True, a shell is used to execute the cmd
- Param:
sigterm_timeout time until shutdown should escalate to SIGTERM, as a string or a list of strings and Substitutions to be resolved at runtime, defaults to the LaunchConfiguration called ‘sigterm_timeout’
- Param:
sigkill_timeout time until escalating to SIGKILL after SIGTERM, as a string or a list of strings and Substitutions to be resolved at runtime, defaults to the LaunchConfiguration called ‘sigkill_timeout’
- Param:
emulate_tty emulate a tty (terminal), defaults to False, but can be overridden with the LaunchConfiguration called ‘emulate_tty’, the value of which is evaluated as true or false according to
evaluate_condition_expression(). ThrowsInvalidConditionExpressionErrorif the ‘emulate_tty’ configuration does not represent a boolean.- Param:
prefix a set of commands/arguments to precede the cmd, used for things like gdb/valgrind and defaults to the LaunchConfiguration called ‘launch-prefix’. Note that a non-default prefix provided in a launch file will override the prefix provided via the launch-prefix launch configuration regardless of whether the launch-prefix-filter launch configuration is provided.
- Param:
output configuration for process output logging. Defaults to ‘log’ i.e. log both stdout and stderr to launch main log file and stderr to the screen. Overridden externally by the OVERRIDE_LAUNCH_PROCESS_OUTPUT envvar value. See launch.logging.get_output_loggers() documentation for further reference on all available options.
- Param:
output_format for logging each output line, supporting str.format() substitutions with the following keys in scope: line to reference the raw output line and this to reference this action instance.
- Param:
log_cmd if True, prints the final cmd before executing the process, which is useful for debugging when substitutions are involved.
- Param:
cached_output if True, both stdout and stderr will be cached. Use get_stdout() and get_stderr() to read the buffered output.
- Param:
on_exit list of actions to execute upon process exit.
- Param:
respawn if ‘True’, relaunch the process that abnormally died. Defaults to ‘False’.
- Param:
respawn_delay a delay time to relaunch the died process if respawn is ‘True’.
- Param:
respawn_max_retries number of times to respawn the process if respawn is ‘True’. A negative value will respawn an infinite number of times (default behavior).
- property additional_env
Getter for additional_env.
- property cmd
Getter for cmd.
- property cwd
Getter for cwd.
- property env
Getter for env.
- property name
Getter for name.
- classmethod parse(entity: Entity, parser: Parser, ignore: List[str] | None = None)[source]
Return the ExecuteProcess action and kwargs for constructing it.
- Param:
ignore A list of arguments that should be ignored while parsing. Intended for code reuse in derived classes (e.g.: launch_ros.actions.Node).
- class launch.actions.ForEach[source]
Bases:
ActionAction that iterates through sets of input values and uses them to instantiate entities.
Sets of input values are provided as semicolon-separated string YAML structures, which could be a substitution, such as a
launch.substitutions.LaunchConfiguration. Each iteration gets a set of input values it can use to instantiate entities. For example, the values can be used to create the same node but under different namespaces. The number of iterations is defined by the number of semicolon-separated sets of values. An empty string results in no iterations, while an empty YAML structure (e.g., ‘{}’) results in an iteration with no input values.When using this action directly through Python, for each iteration, the provided callback function is called with one set of values, and should return a list of entities. The names of the callback function parameters must match the keys in the YAML structure, and the expected types of the parameters correspond to the types of the values in the YAML structure (YAML type rules apply). The order of the callback function parameters does not matter. The callback function could also use **kwargs. Finally, default values can be defined through default values of callback function parameters, in which case they may be omitted from a set of values in the YAML string.
Simple example:
def for_each(id: int, name: str): return [ LogInfo(msg=f"robot '{name}' id={id}"), ] def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument( 'robots', default_value="{name: 'robotA', id: 1};{name: 'robotB', id: 2}"), ForEach(LaunchConfiguration('robots'), function=for_each), ])
When using this action through a frontend, provide entities to be instantiated for each loop iteration as child entities. Use a $(for-var) substitution (
ForEachVar) with the name of the for-each variable, e.g., $(for-var name). A default value can be provided for the variable if it is not available for a given iteration, e.g., $(for-var name default).Simple examples:
<launch> <arg name="robots" default="{name: 'robotA', id: 1};{name: 'robotB', id: 2}" /> <for_each values="$(var robots)" > <log message="'$(for-var name)' id=$(for-var id)" /> </for_each> </launch>
launch: - arg: name: robots default: "{name: 'robotA', id: 1};{name: 'robotB', id: 2}" - for_each: iter: $(var robots) children: - log: message: "'$(for-var name)' id=$(for-var id)"
The above examples would ouput the following log messages by default:
'robotA' id=1 'robotB' id=2
If the ‘robots’ launch argument was set to a different value:
robots:="{name: 'robotC', id: 3};{name: 'robotD', id: 4};{name: 'robotE', id: 5}"Then it would output:
'robotC' id=3 'robotD' id=4 'robotE' id=5
- SEPARATOR = ';'
- __init__(input_values: str | Path | Substitution | Iterable[str | Path | Substitution], *, function: Callable[[...], List[LaunchDescriptionEntity] | None], **kwargs) None[source]
Create a ForEach.
- Parameters:
input_values – the sets of inputs values to iterate over, provided as a semicolon-separated list of string YAML structures (e.g., flow style YAML strings separated by semicolons)
function – a function that receives values from each YAML structure and returns entities
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
Should be overridden by derived class, but by default does nothing.
- property input_values: List[Substitution]
- class launch.actions.ForLoop[source]
Bases:
ActionAction that instantiates entities through a function N times, e.g., based on a launch argument.
The number of iterations of the for-loop is defined by the provided length, which could be a substitution, such as a
launch.substitutions.LaunchConfiguration.When using this action directly through Python, for each loop iteration, the provided callback function is called with the index value, going from 0 to N (exclusive), and should return a list of entities. The callback function must have one parameter: i of type int.
Simple example:
def for_i(i: int): return [ LogInfo(msg=['i=', str(i)]), ] def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('num', default_value='2'), ForLoop(LaunchConfiguration('num'), function=for_i), ])
When using this action through a frontend, provide entities to be instantiated for each loop iteration as child entities. Use an $(index) substitution (
launch.substitutions.ForLoopIndex) with the index name of the for-loop.Simple examples:
<launch> <arg name="num" default="2" /> <for len="$(var num)" name="i" > <log message="i=$(index i)" /> </for> </launch>
launch: - arg: name: num default: '2' - for: len: $(var num) name: i children: - log: message: i=$(index i)
The above examples would ouput the following log messages by default:
i=0 i=1
If the ‘num’ launch argument was set to 5 (num:=5), then it would output:
i=0 i=1 i=2 i=3 i=4
- __init__(length: str | Path | Substitution | Iterable[str | Path | Substitution], *, function: _CallbackFunction, name: str | None = None, **kwargs) None[source]
Create a ForLoop.
- Parameters:
length – the length of the for-loop; must be convertible to int through int(), otherwise a ValueError will be raised during execution
function – a function that receives an integer loop index value (i) and returns entities
name – the for-loop name, used as the index name with the ForLoopIndex substitution
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
Should be overridden by derived class, but by default does nothing.
- property length: List[Substitution]
- class launch.actions.GroupAction[source]
Bases:
ActionAction that yields other actions.
This action is used to nest other actions without including a separate launch description, while also optionally having a condition (like all other actions), scoping and forwarding launch configurations and environment variables, and/or declaring launch configurations for just the group and its yielded actions.
When scoped=True, changes to launch configurations and environment variables are limited to the scope of actions in the group action.
When scoped=True and forwarding=True, all existing launch configurations and environment variables are available in the scoped context.
When scoped=True and forwarding=False, all existing launch configurations and environment variables are removed from the scoped context.
Any launch configuration defined in the launch_configurations dictionary will be set in the current context. When scoped=False these configurations will persist even after the GroupAction has completed. When scoped=True these configurations will only be available to actions in the GroupAction. When scoped=True and forwarding=False, the launch_configurations dictionary is evaluated before clearing, and then re-set in the cleared scoped context.
- __init__(actions: Iterable[Action], *, scoped: bool = True, forwarding: bool = True, launch_configurations: Dict[str | Path | Substitution | Iterable[str | Path | Substitution], str | Path | Substitution | Iterable[str | Path | Substitution]] | None = None, **left_over_kwargs) None[source]
Create a GroupAction.
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
- get_sub_entities() List[LaunchDescriptionEntity][source]
Return subentities.
- class launch.actions.IncludeLaunchDescription[source]
Bases:
ActionAction that includes a launch description source and yields its entities when visited.
It is possible to pass arguments to the launch description, which it declared with the
launch.actions.DeclareLaunchArgumentaction.If any given arguments do not match the name of any declared launch arguments, then they will still be set as Launch Configurations using the
launch.actions.SetLaunchConfigurationaction. This is done because it’s not always possible to detect all instances of the declare launch argument class in the given launch description.On the other side, an error will sometimes be raised if the given launch description declares a launch argument and its value is not provided to this action. It will only produce this error, however, if the declared launch argument is unconditional (sometimes the action that declares the launch argument will only be visited in certain circumstances) and if it does not have a default value on which to fall back.
Conditionally included launch arguments that do not have a default value will eventually raise an error if this best effort argument checking is unable to see an unsatisfied argument ahead of time.
For example, to include
my_pkg’sother_launch.pyand set launch arguments for it:def generate_launch_description(): return ([ SetLaunchConfiguration('arg1', 'value1'), IncludeLaunchDescription( AnyLaunchDescriptionSource([ PathJoinSubstitution([ FindPackageShare('my_pkg'), 'launch', 'other_launch.py', ]), ]), launch_arguments={ 'other_arg1': LaunchConfiguration('arg1'), 'other_arg2': 'value2', }.items(), ), ])
<launch> <let name="arg1" value="value1" /> <include file="$(find-pkg-share my_pkg)/launch/other_launch.py"> <let name="other_arg1" value="$(var arg1)" /> <let name="other_arg2" value="value2" /> </include> </launch>
launch: - let: name: 'arg1' value: 'value1' - include: file: '$(find-pkg-share my_pkg)/launch/other_launch.py' let: - name: 'other_arg1' value: '$(var arg1)' - name: 'other_arg2' value: 'value2'
Note
While frontends currently support both
letandargfor launch arguments, they are both converted intoSetLaunchConfigurationactions (let). The same launch argument should not be defined using bothletandarg.- __init__(launch_description_source: LaunchDescriptionSource | str | Path | Substitution | Iterable[str | Path | Substitution], *, launch_arguments: Iterable[Tuple[str | Path | Substitution | Iterable[str | Path | Substitution], str | Path | Substitution | Iterable[str | Path | Substitution]]] | None = None, **kwargs) None[source]
Create an IncludeLaunchDescription action.
- execute(context: LaunchContext) List[LaunchDescriptionEntity][source]
Execute the action.
- property launch_arguments: Sequence[Tuple[str | Path | Substitution | Iterable[str | Path | Substitution], str | Path | Substitution | Iterable[str | Path | Substitution]]]
Getter for self.__launch_arguments.
- property launch_description_source: LaunchDescriptionSource
Getter for self.__launch_description_source.
- class launch.actions.LogInfo[source]
Bases:
ActionAction that logs a message when executed.
- __init__(*, msg: str | Path | Substitution | Iterable[str | Path | Substitution], **kwargs)[source]
Create a LogInfo action.
- execute(context: LaunchContext) None[source]
Execute the action.
- property msg: List[Substitution]
Getter for self.__msg.
- class launch.actions.OpaqueCoroutine[source]
Bases:
ActionAction that adds a Python coroutine function to the launch run loop.
The signature of the coroutine function should be:
async def coroutine_func( context: LaunchContext, *args, **kwargs ): ...
if ignore_context is False on construction (currently the default), or
async def coroutine_func( *args, **kwargs ): ...
if ignore_context is True on construction.
- __init__(*, coroutine: Callable[[...], Awaitable[None]], args: Iterable[Any] | None = None, kwargs: Dict[str, Any] | None = None, ignore_context: bool = False, **left_over_kwargs) None[source]
Create an OpaqueCoroutine action.
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
- class launch.actions.OpaqueFunction[source]
Bases:
ActionAction that executes a Python function.
The signature of the function should be:
def function( context: LaunchContext, *args, **kwargs ) -> Optional[List[LaunchDescriptionEntity]]: ...
- __init__(*, function: Callable, args: Iterable[Any] | None = None, kwargs: Dict[str, Any] | None = None, **left_over_kwargs) None[source]
Create an OpaqueFunction action.
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
- class launch.actions.PopEnvironment[source]
Bases:
ActionAction that pops the state of environment variables from a stack.
The state can be stored initially by pushing onto the stack with the
launch.actions.PushEnvironmentaction.- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.PopLaunchConfigurations[source]
Bases:
ActionAction that pops the state of launch configurations from a stack.
The state can be stored initially by pushing onto the stack with the
launch.actions.PushLaunchConfigurationsaction.- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.PushEnvironment[source]
Bases:
ActionAction that pushes the current environment to a stack.
The state can be restored by popping the stack with the
launch.actions.PopEnvironmentaction.- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.PushLaunchConfigurations[source]
Bases:
ActionAction that pushes the current state of launch configurations to a stack.
The state can be restored by popping the stack with the
launch.actions.PopLaunchConfigurationsaction.- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.RegisterEventHandler[source]
Bases:
ActionAction that registers an event handler.
Event handlers that are registered in this action will not be matched to an event that is in the process of being handled. For example, if you have an event handler for event ‘Foo’, which returns an instance of RegisterEventHandler for a new event handler that handles the event ‘Foo’ as well, that event handler will not be matched with the instance of the ‘Foo’ event that caused it to be registered in the first place.
- __init__(event_handler: BaseEventHandler, **kwargs) None[source]
Create a RegisterEventHandler action.
- describe_conditional_sub_entities() List[Tuple[str, Iterable[LaunchDescriptionEntity]]][source]
Override describe_conditional_sub_entities from LaunchDescriptionEntity.
- property event_handler: BaseEventHandler
Getter for self.__event_handler.
- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.ResetEnvironment[source]
Bases:
ActionAction that resets the environment in the current context.
Clears any changes made by previous actions to the context environment. The environment is reset to the state it was in when the context was created, i.e. the contents of
os.environ.- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.ResetLaunchConfigurations[source]
Bases:
ActionAction that resets launch configurations in the current context.
This action can be used to clear the launch configurations from the context it was called in. It optionally can be given a dictionary with launch configurations to be set after clearing. Launch configurations given in the dictionary are evaluated before the context launch configurations are cleared. This allows launch configurations to be passed through the clearing of the context.
If launch_configurations is None or an empty dict then all launch configurations will be cleared.
If launch_configurations has entries (i.e. {‘foo’: ‘FOO’}) then these will be set after the clearing operation.
- __init__(launch_configurations: Dict[str | Path | Substitution | Iterable[str | Path | Substitution], str | Path | Substitution | Iterable[str | Path | Substitution]] | None = None, **kwargs) None[source]
Create an ResetLaunchConfigurations action.
- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.SetEnvironmentVariable[source]
Bases:
ActionAction that sets an environment variable.
- __init__(name: str | Path | Substitution | Iterable[str | Path | Substitution], value: str | Path | Substitution | Iterable[str | Path | Substitution], **kwargs) None[source]
Create a SetEnvironmentVariable action.
- execute(context: LaunchContext) None[source]
Execute the action.
- property name: List[Substitution]
Getter for the name of the environment variable to be set.
- property value: List[Substitution]
Getter for the value of the environment variable to be set.
- class launch.actions.SetLaunchConfiguration[source]
Bases:
ActionAction that sets a launch configuration by name.
Launch configurations can be accessed by the LaunchConfiguration substitution and are accessible after being set, even in included LaunchDescription’s, but can be scoped with groups.
- __init__(name: str | Path | Substitution | Iterable[str | Path | Substitution], value: str | Path | Substitution | Iterable[str | Path | Substitution], **kwargs) None[source]
Create a SetLaunchConfiguration action.
- execute(context: LaunchContext)[source]
Execute the action.
- property name: List[Substitution]
Getter for self.__name.
- classmethod parse(entity: Entity, parser: Parser)[source]
Return SetLaunchConfiguration action and kwargs for constructing it.
- property value: List[Substitution]
Getter for self.__value.
- class launch.actions.Shutdown[source]
Bases:
EmitEventAction that shuts down a launched system by emitting Shutdown when executed.
- execute(context: LaunchContext)[source]
Execute the action.
- class launch.actions.TimerAction[source]
Bases:
ActionAction that defers other entities until a period of time has passed, unless canceled.
All timers are “one-shot”, in that they only fire one time and never again.
Entities executed after the given period of time can access the launch configurations that exist at the time that the timer action executed, but changes made by them will not persist. This is similar to grouping the entities in a
launch.actions.GroupActionwithscoped=True.- __init__(*, period: float | str | Path | Substitution | Iterable[str | Path | Substitution], actions: Iterable[LaunchDescriptionEntity], cancel_on_shutdown: bool | str | Path | Substitution | Iterable[str | Path | Substitution] = True, **kwargs) None[source]
Create a TimerAction.
- Parameters:
period – the time (in seconds) to set the timer for
actions – an iterable containing actions to be executed on timeout
cancel_on_shutdown – whether to cancel the timer on launch shutdown
- property actions
- cancel() None[source]
Cancel this TimerAction.
Calling cancel will not fail if the timer has already finished or already been canceled or if the timer has not been started yet.
This function is not thread-safe and should be called only from under another coroutine.
- describe_conditional_sub_entities() List[Tuple[str, Iterable[LaunchDescriptionEntity]]][source]
Return the actions that will result when the timer expires, but was not canceled.
- execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]
Execute the action.
This does the following: - register a global event handler for TimerAction’s if not already done - create a task for the coroutine that waits until canceled or timeout - coroutine asynchronously fires event after timeout, if not canceled
- get_asyncio_future() Future | None[source]
Return an asyncio Future, used to let the launch system know when we’re done.
- handle(context: LaunchContext) LaunchDescriptionEntity | Iterable[LaunchDescriptionEntity] | None[source]
Handle firing of timer.
- classmethod parse(entity: Entity, parser: Parser)[source]
Return the Timer action and kwargs for constructing it.
- property period
- class launch.actions.UnregisterEventHandler[source]
Bases:
ActionAction that unregisters an event handler.
- __init__(event_handler: BaseEventHandler, **kwargs) None[source]
Create an UnregisterEventHandler action.
- property event_handler: BaseEventHandler
Getter for self.__event_handler.
- execute(context: LaunchContext)[source]
Execute the action.
- Raises:
ValueError – if the event handler has not been previously registered.
- class launch.actions.UnsetEnvironmentVariable[source]
Bases:
ActionAction that unsets an environment variable if it is set, otherwise does nothing.
- __init__(name: str | Path | Substitution | Iterable[str | Path | Substitution], **kwargs) None[source]
Create an UnsetEnvironmentVariable action.
- execute(context: LaunchContext) None[source]
Execute the action.
- property name: List[Substitution]
Getter for the name of the environment variable to be unset.
- class launch.actions.UnsetLaunchConfiguration[source]
Bases:
ActionAction that unsets a launch configuration by name.
If the given launch configuration name is no set already then nothing happens.
/sa
launch.actions.SetLaunchConfiguration- __init__(name: str | Path | Substitution | Iterable[str | Path | Substitution], **kwargs) None[source]
Create an UnsetLaunchConfiguration action.
- execute(context: LaunchContext)[source]
Execute the action.
- property name: List[Substitution]
Getter for self.__name.