launch.actions.execute_process module

Module for the ExecuteProcess action.

class launch.actions.execute_process.ExecuteProcess[source]

Bases: ExecuteLocal

Action 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 | Substitution | Iterable[str | Substitution]], prefix: str | Substitution | Iterable[str | Substitution] | None = None, name: str | Substitution | Iterable[str | Substitution] | None = None, cwd: str | Substitution | Iterable[str | Substitution] | None = None, env: Dict[str | Substitution | Iterable[str | Substitution], str | Substitution | Iterable[str | Substitution]] | None = None, additional_env: Dict[str | Substitution | Iterable[str | Substitution], str | Substitution | Iterable[str | 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(). Throws InvalidConditionExpressionError if 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).