launch package

Subpackages

Submodules

Module contents

Main entry point for the launch package.

class launch.Action[source]

Bases: LaunchDescriptionEntity

LaunchDescriptionEntity that represents a user intention to do something.

The action describes the intention to do something, but also can be executed given a launch.LaunchContext at runtime.

__init__(*, condition: Condition | None = None) None[source]

Create an Action.

If the conditions argument is not None, the condition object will be evaluated while being visited and the action will only be executed if the condition evaluates to True.

Parameters:

condition – Either a Condition or None

property condition: Condition | None

Getter for condition.

describe() str[source]

Return a description of this Action.

describe_conditional_sub_entities() List[Tuple[str, Iterable[LaunchDescriptionEntity]]][source]

Override describe_conditional_sub_entities from LaunchDescriptionEntity.

describe_sub_entities() List[LaunchDescriptionEntity][source]

Override describe_sub_entities from LaunchDescriptionEntity.

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

Execute the action.

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

get_sub_entities() List[LaunchDescriptionEntity][source]

Return subentities.

static parse(entity: Entity, parser: Parser)[source]

Return the Action action and kwargs for constructing it.

This is only intended for code reuse. This class is not exposed with expose_action.

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

Override visit from LaunchDescriptionEntity so that it executes.

class launch.Condition[source]

Bases: object

Encapsulates a condition to be evaluated when launching.

The given predicate receives a launch context and is evaluated while launching, but must return True or False.

If a predicate is not set when evaluated, False is returned.

__init__(*, predicate: Callable[[LaunchContext], bool] | None = None) None[source]
describe() str[source]

Return a description of this Condition.

evaluate(context: LaunchContext) bool[source]

Evaluate the condition.

class launch.Event[source]

Bases: object

Event that can be emitted during runtime of a launched system.

name = 'launch.Event'
class launch.EventHandler[source]

Bases: BaseEventHandler

__init__(*, matcher: Callable[[Event], bool], entities: LaunchDescriptionEntity | Iterable[LaunchDescriptionEntity] | None = None, handle_once: bool = False) None[source]

Create an EventHandler.

Param:

matcher is a callable that takes an event and returns True if the event should be handled by this event handler, False otherwise.

Param:

entities is an LaunchDescriptionEntity or list of them, and is returned by handle() unconditionally if matcher returns True.

Param:

handle_once is a flag that, if True, unregisters this EventHandler after being handled once.

describe() Tuple[str, List[LaunchDescriptionEntity | Iterable[LaunchDescriptionEntity]]][source]

Return the description list with 0 as a string, and then LaunchDescriptionEntity’s.

property entities

Getter for entities.

handle(event: Event, context: LaunchContext) LaunchDescriptionEntity | Iterable[LaunchDescriptionEntity] | None[source]

Handle the given event.

exception launch.InvalidLaunchFileError[source]

Bases: Exception

Exception raised when the given launch file is not valid.

__init__(extension='', *, likely_errors=None)[source]

Create an InvalidLaunchFileError.

class launch.LaunchContext[source]

Bases: object

Runtime context used by various launch entities when being visited or executed.

__init__(*, argv: Iterable[str] | None = None, noninteractive: bool = False) None[source]

Create a LaunchContext.

Param:

argv stored in the context for access by the entities, None results in []

Param:

noninteractive if True (not default), this service will assume it has no terminal associated e.g. it is being executed from a non interactive script

add_completion_future(completion_future: Future) None[source]

Add an asyncio.Future to the list of futures that the LaunchService will wait on.

property argv

Getter for argv.

property asyncio_loop

Getter for asyncio_loop.

async emit_event(event: Event) None[source]

Emit an event.

emit_event_sync(event: Event) None[source]

Emit an event synchronously.

property environment: MutableMapping[str, str]

Getter for environment variables dictionary.

extend_globals(extensions: Dict[str, Any]) None[source]

Extend the context.locals object permanently with new members.

These “globals” are in the context.locals, but are overridden by overlapping keys provided by extend_locals().

extend_locals(extensions: Dict[str, Any]) None[source]

Extend the context.locals object with new members until popped.

get_locals_as_dict() Dict[str, Any][source]

Access the context locals as a dictionary.

property is_shutdown

Getter for is_shutdown.

property launch_configurations: Dict[str, str]

Getter for launch_configurations dictionary.

property locals

Getter for the locals.

property noninteractive

Getter for noninteractive.

perform_substitution(substitution: Substitution) str[source]

Perform substitution on given Substitution.

register_event_handler(event_handler: BaseEventHandler, append=False) None[source]

Register a event handler.

Parameters:

append – if ‘true’, the new event handler will be executed after the previously registered ones. If not, it will prepend the old handlers.

unregister_event_handler(event_handler: BaseEventHandler) None[source]

Unregister an event handler.

would_handle_event(event: Event) bool[source]

Check whether an event would be handled or not.

class launch.LaunchDescription[source]

Bases: LaunchDescriptionEntity

Description of a launch-able system.

The description is expressed by a collection of entities which represent the system architect’s intentions.

The description may also have arguments, which are declared by launch.actions.DeclareLaunchArgument actions within this launch description.

Arguments for this description may be accessed via the get_launch_arguments() method. The arguments are gathered by searching through the entities in this launch description and the descriptions of each entity (which may include entities yielded by those entities).

__init__(initial_entities: Iterable[LaunchDescriptionEntity] | None = None, *, deprecated_reason: str | None = None) None[source]

Create a LaunchDescription.

add_action(action: Action) None[source]

Add an action to the LaunchDescription.

add_entity(entity: LaunchDescriptionEntity) None[source]

Add an entity to the LaunchDescription.

property deprecated: bool

Getter for deprecated.

property deprecated_reason: str | None

Getter for deprecated.

Returns None if the launch description is not deprecated.

describe_sub_entities() List[LaunchDescriptionEntity][source]

Override describe_sub_entities from LaunchDescriptionEntity to return sub entities.

property entities: List[LaunchDescriptionEntity]

Getter for the entities.

get_launch_arguments(conditional_inclusion=False) List[DeclareLaunchArgument][source]

Return a list of launch.actions.DeclareLaunchArgument actions.

See get_launch_arguments_with_include_launch_description_actions() for more details.

get_launch_arguments_with_include_launch_description_actions(conditional_inclusion=False) List[Tuple[DeclareLaunchArgument, List[IncludeLaunchDescription]]][source]

Return a list of launch arguments with its associated include launch descriptions actions.

The first element of the tuple is a declare launch argument action. The second is None if the argument was declared at the top level of this launch description, if not it’s a list with all the nested include launch description actions involved.

This list is generated (never cached) by searching through this launch description for any instances of the action that declares launch arguments.

It will use launch.LaunchDescriptionEntity.describe_sub_entities() and launch.LaunchDescriptionEntity.describe_conditional_sub_entities() in order to discover as many instances of the declare launch argument actions as is possible. Also, specifically in the case of the launch.actions.IncludeLaunchDescription action, the method launch.LaunchDescriptionSource.try_get_launch_description_without_context() is used to attempt to load launch descriptions without the “runtime” context available. This function may fail, e.g. if the path to the launch file to include uses the values of launch configurations that have not been set yet, and in that case the failure is ignored and the arguments defined in those launch files will not be seen either.

Duplicate declarations of an argument are ignored, therefore the default value and description from the first instance of the argument declaration is used.

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

Override visit from LaunchDescriptionEntity to visit contained entities.

class launch.LaunchDescriptionEntity[source]

Bases: object

Single item in a launch description.

These entities are “visited” during different activities like “launching” or “introspection”. In each case, different methods of a LaunchDescriptionEntity may be called and those methods can be overridden and enhanced by derived classes.

When being introspected, each LaunchDescriptionEntity has its describe(), describe_sub_entities(), and describe_conditional_sub_entities() methods invoked in that order. These methods are given no contextual information, but are allowed to return a description in each case. See the methods for more information.

When being launched, each LaunchDescriptionEntity has its visit() method invoked. This method is given a LaunchContext and may optionally return a list of sub-entities which should also be immediately visited. After being visited, and before sub-entities or other entities are visited, the get_asyncio_future() method is invoked. This method may optionally return an asyncio.Future object which should be set to “done” when this entity’s on-going activities are finished. If there is no on-going activity, then None may be returned, which is what the default implementation in this class does.

describe() str[source]

Return a description of this entity as a string.

When inherited from, calling this base class’s default method is not required, and in fact it will raise NotImplementedError.

describe_conditional_sub_entities() List[Tuple[str, Iterable[LaunchDescriptionEntity]]][source]

Return a list of condition descriptions and lists of sub-entities.

The list of conditional sub-entities are made up of two item tuples, where the first item is a text description of the condition, and the second item is a list of sub-entities which would be visited if the condition is evaluated to be true during launch.

In the case of multiple layers of inheritance, you may wish to call the base class’s describe_conditional_sub_entities() and extend your own list of sub-entities depending on the behavior of your class, but calling this default method is not required.

describe_sub_entities() List[LaunchDescriptionEntity][source]

Return a list of sub-entities which need to be described as well.

The list may be empty.

The sub-entities in this list should always be returned when this entity is visited at runtime. If there are entities which are only returned under some condition, use the describe_conditional_sub_entities() method instead.

In the case of multiple layers of inheritance, you may wish to call other base class’s describe_sub_entities() and extend your own list of sub-entities depending on the behavior of your class, but calling this default method is not required.

get_asyncio_future() Future | None[source]

Return an asyncio Future, or None if there are no on-going tasks.

This method is always called after visit().

The returned future should be completed when there is no on-going asynchronous tasks associated with the entity.

This is used by the launch system to know when it is idle, i.e. when all entities have not only been visited, but also have been “completed”.

If the launch system is trying to shutdown, and this entity is not setting the returned future to done quickly enough, the launch system may call asyncio.Future.cancel(), which will cause anything awaiting this future to raise the CancelledError exception.

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

Visit the entity.

This is called for each entity in a launch description when being evaluated at runtime.

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

This method should not block, and should aim to be as fast as possible, because while this method is running other tasks and events cannot be handled. Blocking should be done asynchronously using Python’s asyncio. The loop can be accessed from the context with the asyncio_loop member.

Consider using the create_task(coroutine) method of the loop for asynchronous coroutines, or the run_in_executor() method of the loop for long running synchronous tasks.

This method is called from within the loop’s run_forever() or similar method, but it is not awaited by the called as it is not a coroutine itself.

If you have on-going asynchronous tasks, also override the get_asyncio_future() and use the future you return from it to let the launch system know when your entity is done with all pending work. As an example, an entity which ran a subprocess might wait until that subprocess exits before setting the future as “done” so that the launch system doesn’t exit until all child processes are joined.

class launch.LaunchDescriptionSource[source]

Bases: object

Encapsulation of a launch description, where it comes from, and how it was generated.

__init__(launch_description: LaunchDescription | None = None, location: str | Substitution | Iterable[str | Substitution] = '<string>', method: str = 'unspecified mechanism from a script') None[source]

Create a LaunchDescriptionSource.

For example, loading a file called example.launch.py for inclusion might end up setting location to /path/to/example.launch.py and the method to be interpreted python launch file.

Parameters:
  • launch_description – the launch description that this source represents

  • location – the location from where this launch description was loaded if applicable

  • method – the method by which the launch description was generated

get_launch_description(context: LaunchContext) LaunchDescription[source]

Get the LaunchDescription, loading it if necessary.

property location: str

Get the location of the launch description source as a string.

The string is either a list of Substitution instances converted to strings or the expanded path if get_launch_description() has been called.

property method: str

Getter for self.__method.

try_get_launch_description_without_context() LaunchDescription | None[source]

Attempt to load the LaunchDescription without a context, return None if unsuccessful.

This method is useful for trying to introspect the included launch description without visiting the user of this source.

class launch.LaunchIntrospector[source]

Bases: object

Provides an interface through which you can visit all entities of a LaunchDescription.

format_launch_description(launch_description: LaunchDescription) str[source]

Return a string representation of a LaunchDescription.

class launch.LaunchService[source]

Bases: object

Service that manages the event loop and runtime for launched system.

__init__(*, argv: Iterable[str] | None = None, noninteractive: bool = False, debug: bool = False) None[source]

Create a LaunchService.

Param:

argv stored in the context for access by the entities, None results in []

Param:

noninteractive if True (not default), this service will assume it has no terminal associated e.g. it is being executed from a non interactive script

Param:

debug if True (not default), asyncio the logger are seutp for debug

property context

Getter for context.

emit_event(event: Event) None[source]

Emit an event synchronously and thread-safely.

If the LaunchService is not running, the event is queued until it is.

property event_loop

Getter for the event loop being used in the thread running the launch service.

include_launch_description(launch_description: LaunchDescription) None[source]

Evaluate a given LaunchDescription and visits all of its entities.

This method is thread-safe.

run(*, shutdown_when_idle=True) int[source]

Run an event loop and visit all entities of all included LaunchDescription instances.

This should only ever be run from the main thread and not concurrently with asynchronous runs (see run_async() documentation).

Note that KeyboardInterrupt is caught and ignored, as signals are handled separately. After the run ends, this behavior is undone.

Param:

shutdown_when_idle if True (default), the service will shutdown when idle

Returns:

the return code (non-zero if there are any errors)

async run_async(*, shutdown_when_idle=True) int[source]

Visit all entities of all included LaunchDescription instances asynchronously.

This should only ever be run from the main thread and not concurrently with other asynchronous runs.

Param:

shutdown_when_idle if True (default), the service will shutdown when idle.

Returns:

the return code (non-zero if there are any errors)

shutdown(force_sync=False) Coroutine | None[source]

Shutdown all on-going activities and then stop the asyncio run loop.

This will cause the running LaunchService to eventually exit.

Does nothing if the LaunchService is not running.

This will return an awaitable coroutine if called from within the loop.

This method is thread-safe.

property task

Return asyncio task associated with this launch service.

class launch.Substitution[source]

Bases: object

Encapsulates a substitution to be performed at runtime.

describe() str[source]

Return a description of this substitution as a string.

When inherited from, calling this base class’s default method is not required.

perform(context: LaunchContext) str[source]

Perform the substitution, given the launch context, and return it as a string.

This should be overridden by the derived classes, and the default raises NotImplementedError.

Raises:

NotImplementedError