launch_ros.actions.set_parameters_from_file module

Module for the SetParametersFromFile action.

class launch_ros.actions.set_parameters_from_file.SetParametersFromFile(*args: Any, **kwargs: Any)

Bases: Action

Action that sets parameters for all nodes in scope based on a given yaml file.

e.g. ```python3

LaunchDescription([

…, GroupAction(

actions = [

…, SetParametersFromFile(‘path/to/file.yaml’), …, Node(…), // the params will be passed to this node …,

]

), Node(…), // here it won’t be passed, as it’s not in the same scope …

])

``` ```xml <launch>

<group>

<set_parameters_from_file filename=’/path/to/file.yaml’/> <node …/> // Node in scope, params will be passed

</group> <node …/> // Node not in scope, params won’t be passed

</launch>

```

execute(context: launch.launch_context.LaunchContext)

Execute the action.

classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)

Return SetParameterFromFile action and kwargs for constructing it.

launch_ros.actions.set_parameters_from_file.expose_action(_)