better_launch.elements.abstract_node module

class better_launch.elements.abstract_node.AbstractNode(package: str, executable: str, name: str, namespace: str, remaps: dict[str, str] = None, params: str | dict[str, Any] = None, *, output: Literal['screen', 'log', 'own_log', 'none'] | set[Literal['screen', 'log', 'own_log', 'none']] = 'screen')

Bases: object

property executable: str

How this node can be executed. This is not required to be an executable file. It’s meaning depends on the node implementation.

property fullname: str

The concatenation of this node’s namespace and name. Will always start with β€˜/’.

get_info_sheet() str

Returns a summary of this node’s information for display in a terminal.

Returns

str

A detailed description of this node.

get_published_services() dict[str, list[str]]

Get the ROS2 services provided by this node.

Returns

dict[str, list[str]]

The service topics and message types. Will be empty if is_ros2_connected() is False.

get_published_topics() dict[str, list[str]]

Get the ROS2 topics published by this node.

Returns

dict[str, list[str]]

The topics and their message types. Will be empty if is_ros2_connected() is False.

get_subscribed_topics() dict[str, list[str]]

Get the ROS2 topics this node is subscribed to.

Returns

dict[str, list[str]]

The topics and their message types. Will be empty if is_ros2_connected() is False.

is_lifecycle_node(timeout: float = 0.0) bool

Checks if this is a lifecycle node and initializes a : py:class:LifecycleManager if supported and not done so before.

Note that if you simply want to check whether this node supports lifecycle management right now, check whether lifecycle() is None will be considerably cheaper.

Whether a node supports lifecycle management can only be known from outside once its process is started and it has registered with ROS. When this is called while the node is alive and it supports lifecycle management, a LifecycleManager object will be initialized for it. This will persist even if the node is shutdown, but will obviously no longer provide useful functionality.

Note that at the time of writing (Jazzy), the ROS node registers with ROS before the lifecycle topics are created. This makes sense of course, but also means that there is a short window where the node is registered with ROS but not a lifecycle node yet. This can be a problem, especially on slower devices like a Raspberry Pi 3. In these cases I advise you follow this pattern:

node = Node(...)
# Wait until the node is registered in ROS
if node.is_ros2_connected(timeout=5.0):
    # Give the node some additional time to create its lifecycle topics
    if node.is_lifecycle_node(timeout=0.1):
        # Now the node can be managed
        node.lifecycle.transition(...)

Parameters

timeoutfloat, optional

How long to wait for the node to reveal its lifecycle capabilities. Wait forever if None.

Returns

bool

True if the node supports lifecycle management, False otherwise.

is_ros2_connected(timeout: float = 0.0) bool

Check whether this node is registered within ROS.

Parameters

timeoutfloat, optional

How long to wait for the node to sign up with ROS. Wait forever if None.

Returns

bool

True if the node can be discovered by ROS, False otherwise.

property is_running: bool

True if the node is currently running.

join(timeout: float = None) None

Join this node and return once it is shut down. Return immediately if it is not running.

Parameters

timeoutfloat, optional

How long to wait in seconds. Wait forever if None.

Raises

TimeoutError

If a timeout was set and the node is still running by the time it expires.

property lifecycle: LifecycleManager

Returns this node’s LifecyceManager.

Note: make sure to call is_lifecycle_node() before retrieving this object!

Returns

LifecycleManager

The object used for managing this node’s lifecycle. Will be None if lifecycle management is not supported or is_lifecycle_node has not been called before.

property name: str

The name of this node. If this represents a ROS node this will also be the name by which it is known in ROS.

property namespace: str

This node’s namespace.

property node_id: int
property package: str

The package this node can be found in.

property params: dict[str, Any]

The ROS params that were passed to this node. If a string was passed it is assumed to be a filepath and will be loaded with BetterLaunch.find().

property remaps: dict[str, str]

Any topic remaps that were passed to this node.

shutdown(reason: str, signum: int = Signals.SIGTERM, timeout: float = 0.0) None

Shutdown this node. Once this succeeds, is_running() will return False.

Parameters

reasonstr

A human-readable string describing why this node is being shutdown.

signumint, optional

The signal that should be send to the node (if supported).

timeoutfloat, optional

How long to wait for the node to shutdown before returning. Don’t wait if timeout is 0.0. Wait forever if timeout is None.

Raises

TimeoutError

If a timeout > 0 was set and the node did not shutdown before then.

start() None

Start this node. Once this succeeds, is_running() will return True.