Class ROSCommunicationsCache
Defined in File ros_communications_cache.hpp
Class Documentation
-
class ROSCommunicationsCache
Centralized cache for managing ROS 2 communication objects.
This class provides a thread-safe cache for storing and reusing ROS 2 communication objects such as publishers, subscribers, service clients, and action clients. This helps reduce resource usage and improves performance by avoiding duplicate creation of communication objects.
The cache is organized by communication type and uses unique keys based on:
Node name
Message/Service/Action type
Topic/Service/Action name
Callback group name (if applicable)
QoS profile (for publishers and subscribers)
All methods are thread-safe using internal locking mechanisms.
Public Static Functions
Get an existing action client from the cache or create a new one.
- Template Parameters:
ActionT – The type of the action.
- Parameters:
node – The ROS 2 node to use.
action_name – The name of the action.
callback_group – The callback group for the action client (optional).
- Returns:
A shared pointer to the cached or newly created action client.
Get an existing service client from the cache or create a new one.
- Template Parameters:
ServiceT – The type of the service.
- Parameters:
node – The ROS 2 node to use.
service_name – The name of the service.
callback_group – The callback group for the service client (optional).
- Returns:
A shared pointer to the cached or newly created service client.
Get an existing publisher from the cache or create a new one.
- Template Parameters:
MsgT – The type of the message.
- Parameters:
node – The ROS 2 node to use.
topic_name – The name of the topic.
qos_profile – The QoS profile for the publisher.
callback_group – The callback group for the publisher (optional).
- Returns:
A shared pointer to the cached or newly created publisher.
Get an existing subscription from the cache or create a new one.
Note: Subscriptions with different callbacks are considered different and will create separate subscription objects.
- Template Parameters:
MsgT – The type of the message.
CallbackT – The type of the callback function.
- Parameters:
node – The ROS 2 node to use.
topic_name – The name of the topic.
callback – The callback function for incoming messages.
qos_profile – The QoS profile for the subscription.
callback_group – The callback group for the subscription (optional).
- Returns:
A shared pointer to the cached or newly created subscription.
-
static void clear_action_clients()
Clear the action clients cache.
-
static void clear_service_clients()
Clear the service clients cache.
-
static void clear_publishers()
Clear the publishers cache.
-
static void clear_subscribers()
Clear the subscribers cache.
-
static void clear_all()
Clear all communication caches.
-
static size_t get_action_clients_count()
Get the number of cached action clients.
- Returns:
The number of cached action clients.
-
static size_t get_service_clients_count()
Get the number of cached service clients.
- Returns:
The number of cached service clients.
-
static size_t get_publishers_count()
Get the number of cached publishers.
- Returns:
The number of cached publishers.
-
static size_t get_subscribers_count()
Get the number of cached subscribers.
- Returns:
The number of cached subscribers.
-
static std::map<std::string, size_t> get_cache_stats()
Get statistics about all caches.
- Returns:
A map with cache statistics.