rclpy.parameter_event_handler module
- class rclpy.parameter_event_handler.ParameterCallbackHandle(parameter_name: str, node_name: str, callback: Callable[[Parameter[Any]], None])
Bases:
object
- class rclpy.parameter_event_handler.ParameterEventCallbackHandle(callback: Callable[[rcl_interfaces.msg.ParameterEvent], None])
Bases:
object
- class rclpy.parameter_event_handler.ParameterEventHandler(node: Node, qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_parameter_events, callback_group: CallbackGroup | None = None, event_callbacks: SubscriptionEventCallbacks | None = None, qos_overriding_options: QoSOverridingOptions | None = None, raw: bool = False)
Bases:
object
Create ParameterEventHandler.
Usage example:
A class used to “handle” (monitor and respond to) changes to parameters. :param node: Used to subscribe to parameter_events topic :param qos_profile: A QoSProfile or a history depth to apply to the subscription.
In the case that a history depth is provided, the QoS history is set to KEEP_LAST, the QoS history depth is set to the value of the parameter, and all other QoS settings are set to their default values.
- Parameters:
callback_group – The callback group for the subscription. If
None
, then the default callback group for the node is used.event_callbacks – User-defined callbacks for middleware events.
qos_overriding_options – Options to customize QoS parameter overrides.
raw – If
True
, then received messages will be stored in raw binary representation.
- class Callbacks
Bases:
object
Create a Callbacks container for ParameterEventHandler.
Callbacks container is used to store and manage parameter and parameter-event callbacks
- add_parameter_callback(parameter_name: str, node_name: str, callback: Callable[[Parameter[Any]], None]) ParameterCallbackHandle
Add new parameter callback.
Callbacks are called in FILO manner.
- Parameters:
parameter_name – Name of a parameter to bind the callback to
node_name – Name of a node, that the parameter should be related to
callback – A callable to be called when a parameter event occurs
- Return ParameterCallbackHandle:
A handle that should be saved by the user so that the callback can be later removed.
- add_parameter_event_callback(callback: Callable[[rcl_interfaces.msg.ParameterEvent], None]) ParameterEventCallbackHandle
Add new parameter event callback.
Callbacks are called in FILO manner.
- Parameters:
callback – A callable to be referenced on a ParameterEvent
- Return ParameterEventCallbackHandle:
A handle that should be saved by the user so that the event_callback can be later removed.
- event_callback(event: rcl_interfaces.msg.ParameterEvent) None
Search for callback and execute it.
Method to be utilized by ParameterEventHandler object as a callback for subscription to a /parameter_events topic. Used to traverse parameter_callbacks dict and perform callbacks, related to Parameter, specified in event.
- Parameters:
event – ParameterEvent message. By design, originates from /parameter_events topic
- remove_parameter_callback(handle: ParameterCallbackHandle) None
Remove the parameter callback related to provided handle.
- Parameters:
handle – The handle of the callback that is to be removed
- remove_parameter_event_callback(handle: ParameterEventCallbackHandle) None
Remove the parameter event callback related to provided handle.
- Parameters:
handle – A handle of the callback that is to be removed
- add_parameter_callback(parameter_name: str, node_name: str, callback: Callable[[Parameter[Any]], None]) ParameterCallbackHandle
Add new parameter callback.
Callbacks are called in FILO manner.
- Parameters:
parameter_name – Name of a parameter to tie callback to
node_name – Name of a node, that the parameter should be related to
callback – A callable to be called when the parameter is modified
- Return ParameterCallbackHandle:
A handle that should be saved by the user so that the event_callback can be later removed.
- add_parameter_event_callback(callback: Callable[[rcl_interfaces.msg.ParameterEvent], None]) ParameterEventCallbackHandle
Add new parameter callback.
Callbacks are called in FILO manner.
- Parameters:
callback – A callable to be referenced on a ParameterEvent
- Return ParameterEventCallbackHandle:
A handle that should be saved by the user so that the event_callback can be later removed.
- destroy() None
- static get_parameter_from_event(event: rcl_interfaces.msg.ParameterEvent, parameter_name: str, node_name: str) Parameter[Any] | None
Get specified parameter value from ParameterEvent message.
- Parameters:
event – ParameterEvent message to be read
parameter_name – Name of a parameter to get from ParameterEvent message
node_name – Name of a node, that the parameter should be related to
- Return Optional[Parameter]:
If specified parameter is found, returns Parameter object. Otherwise, returns None
- static get_parameters_from_event(event: rcl_interfaces.msg.ParameterEvent) Iterable[Parameter[Any]]
Get all parameters from a ParameterEvent message.
- Parameters:
event – ParameterEvent message to read
- remove_parameter_callback(handle: ParameterCallbackHandle) None
Remove a ParameterCallbackHandle.
Perform no callbacks on this parameter events in the future.
- Parameters:
handle – ParameterCallbackHandle of a callback to be removed
- remove_parameter_event_callback(handle: ParameterEventCallbackHandle) None
Remove a ParameterEventCallbackHandle.
Perform no callbacks on parameter events in the future.
- Parameters:
handle – ParameterEventCallbackHandle of a callback to be removed