rclpy.lifecycle package
Submodules
- rclpy.lifecycle.managed_entity module
- rclpy.lifecycle.node module
CreateLifecyclePublisherArgs
LifecycleNode
LifecycleNodeArgs
LifecycleNodeArgs.allow_undeclared_parameters
LifecycleNodeArgs.automatically_declare_parameters_from_overrides
LifecycleNodeArgs.cli_args
LifecycleNodeArgs.context
LifecycleNodeArgs.enable_logger_service
LifecycleNodeArgs.enable_rosout
LifecycleNodeArgs.namespace
LifecycleNodeArgs.parameter_overrides
LifecycleNodeArgs.start_parameter_services
LifecycleNodeArgs.use_global_arguments
LifecycleNodeMixin
LifecycleNodeMixin.add_managed_entity()
LifecycleNodeMixin.create_lifecycle_publisher()
LifecycleNodeMixin.destroy_lifecycle_publisher()
LifecycleNodeMixin.on_activate()
LifecycleNodeMixin.on_cleanup()
LifecycleNodeMixin.on_configure()
LifecycleNodeMixin.on_deactivate()
LifecycleNodeMixin.on_error()
LifecycleNodeMixin.on_shutdown()
LifecycleNodeMixin.trigger_activate()
LifecycleNodeMixin.trigger_cleanup()
LifecycleNodeMixin.trigger_configure()
LifecycleNodeMixin.trigger_deactivate()
LifecycleNodeMixin.trigger_shutdown()
LifecycleState
- rclpy.lifecycle.publisher module
Module contents
- class rclpy.lifecycle.LifecycleNode(node_name: str, *, enable_communication_interface: bool = True, **kwargs: Unpack[LifecycleNodeArgs])
Bases:
LifecycleNodeMixin
,Node
A ROS 2 managed node.
This class extends Node with the methods provided by LifecycleNodeMixin. Methods in LifecycleNodeMixin override the ones in Node.
Create a lifecycle node.
See rclpy.lifecycle.LifecycleNodeMixin.__init__() and rclpy.node.Node() for the documentation of each parameter.
- class rclpy.lifecycle.LifecycleNodeMixin(*, enable_communication_interface: bool = True, callback_group: CallbackGroup | None = None)
Bases:
ManagedEntity
Mixin class to share as most code as possible between Node and LifecycleNode.
This class is not useful if not used in multiple inheritance together with Node, as it access attributes created by Node directly here!
Initialize a lifecycle node.
- Parameters:
enable_communication_interface – Creates the lifecycle nodes services and publisher if True.
callback_group – Callback group that will be used by all the lifecycle node services.
- add_managed_entity(entity: ManagedEntity) None
- create_lifecycle_publisher(msg_type: Type[MsgT], topic: str, qos_profile: rclpy.qos.QoSProfile | int, *, publisher_class: None = None, **kwargs: Unpack[CreateLifecyclePublisherArgs]) LifecyclePublisher[MsgT]
- destroy_lifecycle_publisher(publisher: LifecyclePublisher[Any]) bool
- on_activate(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle an activating transition.
This is the default on_activate() callback. It will call all on_activate() callbacks of managed entities, giving up at the first entity that returns TransitionCallbackReturn.FAILURE or TransitionCallbackReturn.ERROR.
It’s possible to override this callback if the default behavior is not desired. If you only want to extend what this callback does, make sure to call super().on_activate() in derived classes.
- on_cleanup(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle a cleaning up transition.
This is the default on_cleanup() callback. It will call all on_cleanup() callbacks of managed entities, giving up at the first entity that returns TransitionCallbackReturn.FAILURE or TransitionCallbackReturn.ERROR.
It’s possible to override this callback if the default behavior is not desired. If you only want to extend what this callback does, make sure to call super().on_cleanup() in derived classes.
- on_configure(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle a configuring transition.
This is the default on_configure() callback. It will call all on_configure() callbacks of managed entities, giving up at the first entity that returns TransitionCallbackReturn.FAILURE or TransitionCallbackReturn.ERROR.
It’s possible to override this callback if the default behavior is not desired. If you only want to extend what this callback does, make sure to call super().on_configure() in derived classes.
- on_deactivate(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle a deactivating transition.
This is the default on_deactivate() callback. It will call all on_deactivate() callbacks of managed entities, giving up at the first entity that returns TransitionCallbackReturn.FAILURE or TransitionCallbackReturn.ERROR.
It’s possible to override this callback if the default behavior is not desired. If you only want to extend what this callback does, make sure to call super().on_deactivate() in derived classes.
- on_error(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle a transition error.
This is the default on_error() callback. It will call all on_error() callbacks of managed entities, giving up at the first entity that returns TransitionCallbackReturn.FAILURE or TransitionCallbackReturn.ERROR.
It’s possible to override this callback if the default behavior is not desired. If you only want to extend what this callback does, make sure to call super().on_error() in derived classes.
- on_shutdown(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle a shutting down transition.
This is the default on_shutdown() callback. It will call all on_shutdown() callbacks of managed entities, giving up at the first entity that returns TransitionCallbackReturn.FAILURE or TransitionCallbackReturn.ERROR.
It’s possible to override this callback if the default behavior is not desired. If you only want to extend what this callback does, make sure to call super().on_shutdown() in derived classes.
- trigger_activate() rpyutils.import_c_library.TransitionCallbackReturnType
- trigger_cleanup() rpyutils.import_c_library.TransitionCallbackReturnType
- trigger_configure() rpyutils.import_c_library.TransitionCallbackReturnType
- trigger_deactivate() rpyutils.import_c_library.TransitionCallbackReturnType
- trigger_shutdown() rpyutils.import_c_library.TransitionCallbackReturnType
- class rclpy.lifecycle.LifecyclePublisher(*args: Unpack[LifecyclePublisherArgs[MsgT]], **kwargs: Unpack[LifecyclePublisherKWArgs[MsgT]])
Bases:
SimpleManagedEntity
,Publisher
[MsgT
]Managed publisher entity.
- publish(msg: MsgT | bytes) None
Publish a message if the lifecycle publisher is enabled.
See rclpy.publisher.Publisher.publish() for more details.
- class rclpy.lifecycle.LifecycleState(label, state_id)
Bases:
NamedTuple
Create new instance of LifecycleState(label, state_id)
- label: str
Alias for field number 0
- state_id: int
Alias for field number 1
- class rclpy.lifecycle.ManagedEntity
Bases:
object
- on_activate(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle activate transition request.
- on_cleanup(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle cleanup transition request.
- on_configure(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle configure transition request.
- on_deactivate(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle deactivate transition request.
- on_error(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle error transition request.
- on_shutdown(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle shutdown transition request.
- class rclpy.lifecycle.SimpleManagedEntity
Bases:
ManagedEntity
A simple managed entity that only sets a flag when activated/deactivated.
- property is_activated: bool
- on_activate(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle activate transition request.
- on_deactivate(state: LifecycleState) rpyutils.import_c_library.TransitionCallbackReturnType
Handle deactivate transition request.
- static when_enabled(wrapped: None, *, when_not_enabled: Callable[[...], None] | None = None) Callable[[Callable[[...], None]], Callable[[...], None]]
- static when_enabled(wrapped: Callable[[...], None], *, when_not_enabled: Callable[[...], None] | None = None) Callable[[...], None]