Class ROSClientsCache

Class Documentation

class ROSClientsCache

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.

Public Static Functions

template<typename ActionT>
static inline rclcpp_action::Client<ActionT>::SharedPtr get_or_create_action_client(rclcpp::Node::SharedPtr node, const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)

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.

template<typename ServiceT>
static inline rclcpp::Client<ServiceT>::SharedPtr get_or_create_service_client(rclcpp::Node::SharedPtr node, const std::string &service_name, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)

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.

template<typename MsgT>
static inline rclcpp::Publisher<MsgT>::SharedPtr get_or_create_publisher(rclcpp::Node::SharedPtr node, const std::string &topic_name, const rclcpp::QoS &qos_profile = rclcpp::QoS(10), rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)

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.

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_all()

Clear all clients 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 std::map<std::string, size_t> get_cache_stats()

Get statistics about all caches.

Returns:

A map with cache statistics.