launch.actions.for_loop module

Module for the ForLoop action.

class launch.actions.for_loop.ForEach[source]

Bases: Action

Action 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

describe() str[source]

Return a description of this Action.

execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]

Execute the action.

Should be overridden by derived class, but by default does nothing.

property function: Callable[[int], List[LaunchDescriptionEntity] | None]
property input_values: List[Substitution]
classmethod parse(entity: Entity, parser: Parser)[source]

Return ForEach action and kwargs for constructing it.

class launch.actions.for_loop.ForLoop[source]

Bases: Action

Action 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

describe() str[source]

Return a description of this Action.

execute(context: LaunchContext) List[LaunchDescriptionEntity] | None[source]

Execute the action.

Should be overridden by derived class, but by default does nothing.

property function: Callable[[int], List[LaunchDescriptionEntity] | None]
property length: List[Substitution]
property name: str | None
classmethod parse(entity: Entity, parser: Parser)[source]

Return ForLoop action and kwargs for constructing it.