launch_ros.actions package
Submodules
- launch_ros.actions.composable_node_container module
- launch_ros.actions.lifecycle_node module
- launch_ros.actions.lifecycle_transition module
- launch_ros.actions.load_composable_nodes module
- launch_ros.actions.node module
- launch_ros.actions.push_ros_namespace module
- launch_ros.actions.ros_timer module
- launch_ros.actions.set_parameter module
- launch_ros.actions.set_parameters_from_file module
- launch_ros.actions.set_remap module
- launch_ros.actions.set_ros_log_dir module
- launch_ros.actions.set_use_sim_time module
Module contents
actions Module.
- class launch_ros.actions.ComposableNodeContainer(*args: Any, **kwargs: Any)
Bases:
Node
Action that executes a container ROS node for composable ROS nodes.
- execute(context: launch.launch_context.LaunchContext) List[launch.action.Action] | None
Execute the action.
Most work is delegated to
launch_ros.actions.Node.execute()
, except for the composable nodes load action if it applies.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Parse node_container.
- class launch_ros.actions.LifecycleNode(*args: Any, **kwargs: Any)
Bases:
Node
Action that executes a ROS lifecycle node.
- execute(context: launch.LaunchContext) List[launch.action.Action] | None
Execute the action.
Delegated to
launch.actions.ExecuteProcess.execute()
.
- get_lifecycle_event_manager()
- property is_lifecycle_node
- property node_autostart
Getter for autostart.
- class launch_ros.actions.LifecycleTransition(*args: Any, **kwargs: Any)
Bases:
Action
An action that simplifies execution of lifecyle transitions.
- execute(context: launch.LaunchContext) List[launch.action.Action] | None
Execute the LifecycleTransition action.
- :return Returns a list of actions to be executed to achieve specified transitions.
These are EventHandlers and EventEmitters for ChangeState and StateTransition events of the nodes indicated.
- transition_targets = {lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE: {'goal_state': 'active', 'start_state': 'activating'}, lifecycle_msgs.msg.Transition.TRANSITION_ACTIVE_SHUTDOWN: {'goal_state': 'finalized', 'start_state': 'shuttingdown'}, lifecycle_msgs.msg.Transition.TRANSITION_CLEANUP: {'goal_state': 'unconfigured', 'start_state': 'cleaningup'}, lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE: {'goal_state': 'inactive', 'start_state': 'configuring'}, lifecycle_msgs.msg.Transition.TRANSITION_DEACTIVATE: {'goal_state': 'inactive', 'start_state': 'deactivating'}, lifecycle_msgs.msg.Transition.TRANSITION_INACTIVE_SHUTDOWN: {'goal_state': 'finalized', 'start_state': 'shuttingdown'}, lifecycle_msgs.msg.Transition.TRANSITION_UNCONFIGURED_SHUTDOWN: {'goal_state': 'finalized', 'start_state': 'shuttingdown'}}
- class launch_ros.actions.LoadComposableNodes(*args: Any, **kwargs: Any)
Bases:
Action
Action that loads composable ROS nodes into a running container.
- execute(context: launch.launch_context.LaunchContext) List[launch.action.Action] | None
Execute the action.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Parse load_composable_node.
- class launch_ros.actions.Node(*args: Any, **kwargs: Any)
Bases:
ExecuteProcess
Action that executes a ROS node.
- UNSPECIFIED_NODE_NAME = '<node_name_unspecified>'
- UNSPECIFIED_NODE_NAMESPACE = '<node_namespace_unspecified>'
- execute(context: launch.launch_context.LaunchContext) List[launch.action.Action] | None
Execute the action.
Delegated to
launch.actions.ExecuteProcess.execute()
.
- property expanded_node_namespace
Getter for expanded_node_namespace.
- property expanded_remapping_rules
Getter for expanded_remappings.
- is_node_name_fully_specified()
- property node_executable
Getter for node_executable.
- property node_name
Getter for node_name.
- property node_package
Getter for node_package.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Parse node.
- static parse_nested_parameters(params, parser)
Normalize parameters as expected by Node constructor argument.
- class launch_ros.actions.PushROSNamespace(*args: Any, **kwargs: Any)
Bases:
Action
Action that pushes the ros namespace.
It’s automatically popped when used inside a scoped GroupAction. There’s no other way of popping it.
- execute(context: launch.launch_context.LaunchContext)
Execute the action.
- property namespace: List[launch.Substitution]
Getter for self.__namespace.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Return PushROSNamespace action and kwargs for constructing it.
- launch_ros.actions.PushRosNamespace
alias of
PushROSNamespace
- class launch_ros.actions.ROSTimer(*args: Any, **kwargs: Any)
Bases:
TimerAction
Action that defers other entities until a period of time has passed, unless canceled.
This timer uses ROS time instead of wall clock time. To enable the use of sim time, you must also use the SetUseSimTime action. All timers are “one-shot”, in that they only fire one time and never again.
- describe() str
Return a description of this ROSTimer.
- execute(context: launch.launch_context.LaunchContext)
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Return the ROSTimer action and kwargs for constructing it.
- class launch_ros.actions.SetParameter(*args: Any, **kwargs: Any)
Bases:
Action
Action that sets a parameter in the current context.
This parameter will be set in all the nodes launched in the same scope. e.g.: ```python3
- LaunchDescription([
…, GroupAction(
- actions = [
…, SetParameter(name=’my_param’, value=’2’), …, Node(…), // the param will be passed to this node …,
]
), Node(…), // here it won’t be passed, as it’s not in the same scope …
])
- execute(context: launch.launch_context.LaunchContext)
Execute the action.
- property name: Sequence[launch.substitution.Substitution]
Getter for name.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Return SetParameter action and kwargs for constructing it.
- property value: Sequence[launch.substitution.Substitution] | Sequence[Sequence[launch.substitution.Substitution]] | str | int | float | bool | Sequence[str] | Sequence[int] | Sequence[float] | Sequence[bool] | bytes | ParameterValue
Getter for value.
- class launch_ros.actions.SetParametersFromFile(*args: Any, **kwargs: Any)
Bases:
Action
Action that sets parameters for all nodes in scope based on a given yaml file.
- 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 …
])
- <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.
- class launch_ros.actions.SetROSLogDir(*args: Any, **kwargs: Any)
Bases:
Action
Action that sets the ros log directory.
This is done by setting the ROS_LOG_DIR environment variable, which will influence all processes started after that time, in which ros was initialized.
This can be used in combination with launch.actions.GroupAction and its
scoped=true
option to provide scoped changes to this environment variable.Note this will not affect nodes loaded into component containers which were started before this action is executed.
- execute(context: launch.launch_context.LaunchContext)
Execute the action.
- property log_dir: List[launch.Substitution]
Getter for self.__log_dir.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Return SetROSLogDir action and kwargs for constructing it.
- class launch_ros.actions.SetRemap(*args: Any, **kwargs: Any)
Bases:
Action
Action that sets a remapping rule in the current context.
This remapping rule will be passed to all the nodes launched in the same scope, overriding the ones specified in the Node action constructor. e.g.: ```python3
- LaunchDescription([
…, GroupAction(
- actions = [
…, SetRemap(src=’asd’, dst=’bsd’), …, Node(…), // the remap rule will be passed to this node …,
]
), Node(…), // here it won’t be passed, as it’s not in the same scope …
])
- property dst: List[launch.Substitution]
Getter for dst.
- execute(context: launch.launch_context.LaunchContext)
Execute the action.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Return SetRemap action and kwargs for constructing it.
- property src: List[launch.Substitution]
Getter for src.
- class launch_ros.actions.SetUseSimTime(*args: Any, **kwargs: Any)
Bases:
Action
Action that sets the ‘use_sim_time’ parameter in the current context.
- execute(context: launch.launch_context.LaunchContext)
Execute the action.
- classmethod parse(entity: launch.frontend.Entity, parser: launch.frontend.Parser)
Return SetUseSimTime action and kwargs for constructing it.
- property value: bool
Getter for value.