rclpy.context module
- class rclpy.context.Context
Bases:
ContextManager
[Context
]Encapsulates the lifecycle of init and shutdown.
Context objects should not be reused, and are finalized in their destructor. Wraps the rcl_context_t type.
- Example:
>>> from rclpy.context import Context >>> with Context() as context: >>> context.ok() True
- destroy() None
- get_domain_id() int
Get domain id of context.
- property handle: rpyutils.import_c_library.Context | None
- init(args: List[str] | None = None, *, initialize_logging: bool = True, domain_id: int | None = None) None
Initialize ROS communications for a given context.
- Parameters:
args – List of command line arguments.
initialize_logging – Whether to initialize logging for the whole process. The default is to initialize logging.
domain_id – Which domain ID to use for this context. If None (the default), domain ID 0 is used.
- ok() bool
Check if context hasn’t been shut down.
- on_shutdown(callback: Callable[[], None]) None
Add a callback to be called on shutdown.
- shutdown() None
Shutdown this context.
- track_node(node: Node) None
Track a Node associated with this Context.
When the Context is destroyed, it will destroy every Node it tracks.
- Parameters:
node – The node to take a weak reference to.
- try_shutdown() None
Shutdown this context, if not already shutdown.
- untrack_node(node: Node) None
Stop tracking a Node associated with this Context.
If a Node is destroyed before the context, we no longer need to track it for destruction of the Context, so remove it here.