Initialization, Shutdown, and Spinning
A collection of functions for writing a ROS program.
A typical ROS program consists of the following operations:
Initialization
Create one or more ROS nodes
Process node callbacks
Shutdown
Initialization is done by calling init()
for a particular Context
.
This must be done before any ROS nodes can be created.
Creating a ROS node is done by calling create_node()
or by instantiating a
Node
.
A node can be used to create common ROS entities like publishers, subscriptions, services,
and actions.
After a node is created, items of work can be done (e.g. subscription callbacks) by spinning on
the node.
The following functions can be used to process work that is waiting to be executed: spin()
,
spin_once()
, and spin_until_future_complete()
.
When finished with a previously initialized Context
(ie. done using
all ROS nodes associated with the context), the shutdown()
function should be called.
This will invalidate all entities derived from the context.
- class rclpy.InitContextManager(args: List[str] | None, context: Context | None, domain_id: int | None, signal_handler_options: rpyutils.import_c_library.SignalHandlerOptions | None)
A proxy object for initialization.
One of these is returned when calling rclpy.init, and can be used with context managers to properly cleanup after initialization.
- rclpy.create_node(node_name: str, *, context: Context | None = None, cli_args: List[str] | None = None, namespace: str | None = None, use_global_arguments: bool = True, enable_rosout: bool = True, start_parameter_services: bool = True, parameter_overrides: List[Parameter] | None = None, allow_undeclared_parameters: bool = False, automatically_declare_parameters_from_overrides: bool = False, enable_logger_service: bool = False) Node
Create an instance of
Node
.- Parameters:
node_name – A name to give to the node.
context – The context to associated with the node, or
None
for the default global context.cli_args – Command line arguments to be used by the node. Being specific to a ROS node, an implicit –ros-args scope flag always precedes these arguments.
namespace – The namespace prefix to apply to entities associated with the node (node name, topics, etc).
use_global_arguments –
False
if the node should ignore process-wide command line arguments.enable_rosout –
False
if the node should ignore rosout logging.start_parameter_services –
False
if the node should not create parameter services.parameter_overrides – A list of
Parameter
which are used to override the initial values of parameters declared on this node.allow_undeclared_parameters – if True undeclared parameters are allowed, default False. This option doesn’t affect parameter_overrides.
automatically_declare_parameters_from_overrides – If True, the “parameter overrides” will be used to implicitly declare parameters on the node during creation, default False.
enable_logger_service –
True
if ROS2 services are created to allow external nodes to get and set logger levels of this node. Otherwise, logger levels are only managed locally. That is, logger levels cannot be changed remotely.
- Returns:
An instance of the newly created node.
- rclpy.get_global_executor() Executor
- rclpy.init(*, args: List[str] | None = None, context: Context | None = None, domain_id: int | None = None, signal_handler_options: rpyutils.import_c_library.SignalHandlerOptions | None = None) InitContextManager
Initialize ROS communications for a given context.
- Parameters:
args – List of command line arguments.
context – The context to initialize. If
None
, then the default context is used (seeget_default_context()
).domain_id – ROS domain id.
signal_handler_options – Indicate which signal handlers to install. If None, SIGINT and SIGTERM will be installed when initializing the default context.
- Returns:
an InitContextManager that can be used with Python context managers to cleanup.
- rclpy.shutdown(*, context: Context | None = None, uninstall_handlers: bool | None = None) None
Shutdown a previously initialized context.
This will also shutdown the global executor.
- Parameters:
context – The context to invalidate. If
None
, then the default context is used (seeget_default_context()
).uninstall_handlers – If None, signal handlers will be uninstalled when shutting down the default context. If True, signal handlers will be uninstalled. If False, signal handlers won’t be uninstalled.
- rclpy.spin(node: Node, executor: Executor | None = None) None
Execute work and block until the context associated with the executor is shutdown.
Callbacks will be executed by the provided executor.
This function blocks.
- Parameters:
node – A node to add to the executor to check for work.
executor – The executor to use, or the global executor if
None
.
- rclpy.spin_once(node: Node, *, executor: Executor | None = None, timeout_sec: float | None = None) None
Execute one item of work or wait until a timeout expires.
One callback will be executed by the provided executor as long as that callback is ready before the timeout expires.
If no executor is provided (ie.
None
), then the global executor is used. It is possible the work done is for a node other than the one provided if the global executor has a partially completed coroutine.This method should not be called from multiple threads with the same node or executor argument.
- Parameters:
node – A node to add to the executor to check for work.
executor – The executor to use, or the global executor if
None
.timeout_sec – Seconds to wait. Block forever if
None
or negative. Don’t wait if 0.
- rclpy.spin_until_future_complete(node: Node, future: Future, executor: Executor | None = None, timeout_sec: float | None = None) None
Execute work until the future is complete.
Callbacks and other work will be executed by the provided executor until
future.done()
returnsTrue
or the context associated with the executor is shutdown.- Parameters:
node – A node to add to the executor to check for work.
future – The future object to wait on.
executor – The executor to use, or the global executor if
None
.timeout_sec – Seconds to wait. Block until the future is complete if
None
or negative. Don’t wait if 0.
- rclpy.try_shutdown(*, context: Context | None = None, uninstall_handlers: bool | None = None) None
Shutdown a previously initialized context if not already shutdown.
This will also shutdown the global executor.
- Parameters:
context – The context to invalidate. If
None
, then the default context is used (seeget_default_context()
).uninstall_handlers – If None, signal handlers will be uninstalled when shutting down the default context. If True, signal handlers will be uninstalled. If False, signal handlers won’t be uninstalled.