Python YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin_ros.ros_clients_cache.ROSClientsCache Class Reference

Public Member Functions

ActionClient get_or_create_action_client (cls, Node node, Type action_type, str action_name, CallbackGroup callback_group=None)
 
Client get_or_create_service_client (cls, Node node, Type service_type, str service_name, CallbackGroup callback_group=None)
 
Publisher get_or_create_publisher (cls, Node node, Type msg_type, str topic_name, QoSProfile qos_profile=10, CallbackGroup callback_group=None)
 
None clear_action_clients (cls)
 
None clear_service_clients (cls)
 
None clear_publishers (cls)
 
None clear_all (cls)
 
int get_action_clients_count (cls)
 
int get_service_clients_count (cls)
 
int get_publishers_count (cls)
 
Dict[str, int] get_cache_stats (cls)
 

Static Protected Member Functions

int _hash_qos_profile (Any qos_profile)
 
str _get_callback_group_name (CallbackGroup callback_group)
 
str _get_callback_name (callable callback)
 

Static Protected Attributes

dict _action_clients = {}
 Cache for action clients Key: (node_name, action_type_name, action_name, callback_group_name) Value: ActionClient instance.
 
dict _service_clients = {}
 Cache for service clients Key: (node_name, service_type_name, service_name, callback_group_name) Value: Client instance.
 
dict _publishers = {}
 Cache for publishers Key: (node_name, msg_type_name, topic_name, qos_hash) Value: Publisher instance.
 
RLock _lock = RLock()
 Lock for thread-safe access to all caches.
 

Detailed Description

Centralized cache for managing ROS 2 client objects.

This class provides a thread-safe cache for storing and reusing ROS 2 client
objects such as publishers, service clients, and action clients.
This helps reduce resource usage and improves performance by avoiding duplicate
creation of client objects.

The cache is organized by client type and uses unique keys based on:
- Node name
- Message/Service/Action type
- Topic/Service/Action name
- Callback group name
- QoS profile

All methods are thread-safe using internal locking mechanisms.

Member Function Documentation

◆ _get_callback_group_name()

str yasmin_ros.ros_clients_cache.ROSClientsCache._get_callback_group_name ( CallbackGroup callback_group)
staticprotected
Get a string representation of a callback group.

Args:
    callback_group: The callback group to get the name from.

Returns:
    str: A string representation of the callback group.

◆ _get_callback_name()

str yasmin_ros.ros_clients_cache.ROSClientsCache._get_callback_name ( callable callback)
staticprotected
Get a string representation of a callback function.

Args:
    callback: The callback function to get the name from.

Returns:
    str: A string representation of the callback.

◆ _hash_qos_profile()

int yasmin_ros.ros_clients_cache.ROSClientsCache._hash_qos_profile ( Any qos_profile)
staticprotected
Create a hash for a QoS profile.

Args:
    qos_profile: The QoS profile to hash (can be int or QoSProfile).

Returns:
    int: A hash value for the QoS profile.

◆ clear_action_clients()

None yasmin_ros.ros_clients_cache.ROSClientsCache.clear_action_clients ( cls)
Clear the action clients cache.

◆ clear_all()

None yasmin_ros.ros_clients_cache.ROSClientsCache.clear_all ( cls)
Clear all client caches.

◆ clear_publishers()

None yasmin_ros.ros_clients_cache.ROSClientsCache.clear_publishers ( cls)
Clear the publishers cache.

◆ clear_service_clients()

None yasmin_ros.ros_clients_cache.ROSClientsCache.clear_service_clients ( cls)
Clear the service clients cache.

◆ get_action_clients_count()

int yasmin_ros.ros_clients_cache.ROSClientsCache.get_action_clients_count ( cls)
Get the number of cached action clients.

Returns:
    int: The number of cached action clients.

◆ get_cache_stats()

Dict[str, int] yasmin_ros.ros_clients_cache.ROSClientsCache.get_cache_stats ( cls)
Get statistics about all caches.

Returns:
    Dict[str, int]: A dictionary with cache statistics.

◆ get_or_create_action_client()

ActionClient yasmin_ros.ros_clients_cache.ROSClientsCache.get_or_create_action_client ( cls,
Node node,
Type action_type,
str action_name,
CallbackGroup callback_group = None )
Get an existing action client from the cache or create a new one.

Args:
    node (Node): The ROS 2 node to use.
    action_type (Type): The type of the action.
    action_name (str): The name of the action.
    callback_group (CallbackGroup, optional): The callback group for the action client.

Returns:
    ActionClient: The cached or newly created action client.

◆ get_or_create_publisher()

Publisher yasmin_ros.ros_clients_cache.ROSClientsCache.get_or_create_publisher ( cls,
Node node,
Type msg_type,
str topic_name,
QoSProfile qos_profile = 10,
CallbackGroup callback_group = None )
Get an existing publisher from the cache or create a new one.

Args:
    node (Node): The ROS 2 node to use.
    msg_type (Type): The type of the message.
    topic_name (str): The name of the topic.
    qos_profile (QoSProfile, optional): The QoS profile for the publisher.
    callback_group (CallbackGroup, optional): The callback group for the publisher.

Returns:
    Publisher: The cached or newly created publisher.

◆ get_or_create_service_client()

Client yasmin_ros.ros_clients_cache.ROSClientsCache.get_or_create_service_client ( cls,
Node node,
Type service_type,
str service_name,
CallbackGroup callback_group = None )
Get an existing service client from the cache or create a new one.

Args:
    node (Node): The ROS 2 node to use.
    service_type (Type): The type of the service.
    service_name (str): The name of the service.
    callback_group (CallbackGroup, optional): The callback group for the service client.

Returns:
    Client: The cached or newly created service client.

◆ get_publishers_count()

int yasmin_ros.ros_clients_cache.ROSClientsCache.get_publishers_count ( cls)
Get the number of cached publishers.

Returns:
    int: The number of cached publishers.

◆ get_service_clients_count()

int yasmin_ros.ros_clients_cache.ROSClientsCache.get_service_clients_count ( cls)
Get the number of cached service clients.

Returns:
    int: The number of cached service clients.

Member Data Documentation

◆ _action_clients

yasmin_ros.ros_clients_cache.ROSClientsCache._action_clients = {}
staticprotected

Cache for action clients Key: (node_name, action_type_name, action_name, callback_group_name) Value: ActionClient instance.

◆ _lock

RLock yasmin_ros.ros_clients_cache.ROSClientsCache._lock = RLock()
staticprotected

Lock for thread-safe access to all caches.

◆ _publishers

yasmin_ros.ros_clients_cache.ROSClientsCache._publishers = {}
staticprotected

Cache for publishers Key: (node_name, msg_type_name, topic_name, qos_hash) Value: Publisher instance.

◆ _service_clients

yasmin_ros.ros_clients_cache.ROSClientsCache._service_clients = {}
staticprotected

Cache for service clients Key: (node_name, service_type_name, service_name, callback_group_name) Value: Client instance.


The documentation for this class was generated from the following file: