rclpy.parameter_event_handler module
- class rclpy.parameter_event_handler.ParameterCallbackHandle(parameter_name: str, node_name: str, callback: Callable[[rcl_interfaces.msg.Parameter], 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:
objectCreate 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:
objectCreate 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[[rcl_interfaces.msg.Parameter], 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[[rcl_interfaces.msg.Parameter], None]) ParameterCallbackHandle
Add new parameter callback.
Callbacks are called in FILO manner.
The configure_nodes_filter() function will affect the behavior of this function. If the node specified in this function isn’t included in the nodes specified in configure_nodes_filter(), the callback will never be called.
- 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.
- configure_nodes_filter(node_names: List[str] | None = None) bool
Configure which node parameter events will be received.
This function depends on rmw implementation support for content filtering. If middleware doesn’t support contentfilter, return false.
If node_names is empty, the configured node filter will be cleared.
If this function return true, only parameter events from the specified node will be received. It affects the behavior of the following two functions. - add_parameter_event_callback()
The callback will only be called for parameter events from the specified nodes which are configured in this function.
add_parameter_callback() The callback will only be called for parameter events from the specified nodes which are configured in this function and add_parameter_callback(). If the nodes specified in this function is different from the nodes specified in add_parameter_callback(), the callback will never be called.
- Parameters:
node_names – Node names to filter parameter events from
- Returns:
True if the filter was successfully applied, False otherwise.
- Raises:
RCLError if internal error occurred when calling the rcl function.
- destroy() None
- static get_parameter_from_event(event: rcl_interfaces.msg.ParameterEvent, parameter_name: str, node_name: str) rcl_interfaces.msg.Parameter | 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[rcl_interfaces.msg.Parameter]
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