ros_sugar.launch.launcher#

Launcher

Module Contents#

Classes#

Launcher

Launcher is a class created to provide a more pythonic way to launch and configure ROS nodes.

API#

class ros_sugar.launch.launcher.Launcher(namespace: str = '', config_file: str | None = None, enable_monitoring: bool = True)#

Launcher is a class created to provide a more pythonic way to launch and configure ROS nodes.

Launcher starts a pre-configured component or a set of components as ROS2 nodes. Launcher can also manage a set of Events-Actions through its internal Monitor node (See Monitor class).

Available options:

  • Provide a ROS2 namespace to all the components

  • Provide a YAML config file.

  • Enable/Disable events monitoring

Launcher forwards all the provided Events to its internal Monitor, when the Monitor detects an Event trigger it emits an InternalEvent back to the Launcher. Execution of the Action is done directly by the Launcher or a request is forwarded to the Monitor depending on the selected run method (multi-processes or multi-threaded).

Note

While Launcher supports executing standard ROS2 launch actions. Launcher does not support standard ROS2 launch events for the current version.

add_pkg(components: List[ros_sugar.core.component.BaseComponent], package_name: Optional[str] = None, executable_entry_point: Optional[str] = None, events_actions: Dict[ros_sugar.core.event.Event, Union[ros_sugar.core.action.Action, launch.action.Action, List[Union[ros_sugar.core.action.Action, launch.action.Action]]]] | None = None, multi_processing: bool = False, activate_all_components_on_start: bool = False, components_to_activate_on_start: Optional[List[ros_sugar.core.component.BaseComponent]] = None)#

Add component or a set of components to the launcher from one ROS2 package based on ros_sugar

Parameters:
  • components (List[BaseComponent]) – Component to launch and manage

  • package_name (str, optional) – Components ROS2 package name. Required for multi-process run, defaults to None

  • executable_entry_point (str, optional) – Components ROS2 entry point name. Required for multi-process run, defaults to “executable”

  • events_actions (Dict[ Event, Union[Action, ROSLaunchAction, List[Union[Action, ROSLaunchAction]]] ] | None, optional) – Events/Actions to monitor, defaults to None

  • multi_processing (bool, optional) – Run the components in multi-processes, otherwise runs in multi-threading, defaults to False

  • activate_all_components_on_start (bool, optional) – To activate all the ROS2 lifecycle nodes on bringup, defaults to False

  • components_to_activate_on_start (Optional[List[BaseComponent]], optional) – Set of components to activate on bringup, defaults to None

start(node_name: str, **_) launch.some_entities_type.SomeEntitiesType#

Action to start a node: configure + activate

Parameters:

node_name (str) – description

Returns:

Launch actions

Return type:

List[SomeEntitiesType]

stop(node_name: str, **_) launch.some_entities_type.SomeEntitiesType#

Action to stop a node: deactivate

Parameters:

node_name (str) – description

Returns:

Launch actions

Return type:

List[SomeEntitiesType]

restart(node_name: str, **_) launch.some_entities_type.SomeEntitiesType#

Action to restart a node: deactivate + activate

Parameters:

node_name (str) – description

Returns:

Launch actions

Return type:

List[SomeEntitiesType]

property fallback_rate: Dict#

fallback_rate.

Return type:

Dict

on_fail(action_name: str, max_retries: Optional[int] = None) None#

Set the fallback strategy (action) on any fail for all components

Parameters:
  • action (Union[List[Action], Action]) – Action to be executed on failure

  • max_retries (Optional[int], optional) – Maximum number of action execution retries. None is equivalent to unlimited retries, defaults to None

configure(config_file: str, component_name: str | None = None)#

Configure components managed by the Orchestrator

Parameters:
  • config_file (str) – Path to configuration file (yaml)

  • component_name (str | None, optional) – Configure one component with given name, defaults to None

add_py_executable(path_to_executable: str, name: str = 'python3')#

Adds a python executable to the launcher as a separate process

Parameters:
  • path_to_executable (str) – description

  • name (str, optional) – description, defaults to ‘python3’

add_method(method: Callable | Awaitable, args: Iterable | None = None, kwargs: Dict | None = None)#

Adds a method action to launch

Parameters:
  • method (Callable | Awaitable) – description

  • args (Iterable | None, optional) – description, defaults to None

  • kwargs (Dict | None, optional) – description, defaults to None

bringup(config_file: str | None = None, introspect: bool = False, launch_debug: bool = False, ros_log_level: str = 'info')#

Bring up the Launcher