C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin_ros::ROSClientsCache Class Reference

Centralized cache for managing ROS 2 client objects. More...

#include <ros_clients_cache.hpp>

Static Public Member Functions

template<typename ActionT>
static 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<typename ServiceT>
static 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<typename MsgT>
static 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.
 
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.
 
static size_t get_service_clients_count ()
 Get the number of cached service clients.
 
static size_t get_publishers_count ()
 Get the number of cached publishers.
 
static std::map< std::string, size_t > get_cache_stats ()
 Get statistics about all caches.
 

Private Types

using ActionClientKey
 
using ServiceClientKey
 
using PublisherKey
 

Static Private Member Functions

static std::map< ActionClientKey, std::shared_ptr< void > > & get_action_clients ()
 
static std::map< ServiceClientKey, std::shared_ptr< void > > & get_service_clients ()
 
static std::map< PublisherKey, std::shared_ptr< void > > & get_publishers ()
 
static std::recursive_mutex & get_lock ()
 
template<typename T>
static std::string get_type_name ()
 Get a string representation of a type.
 
static std::string get_callback_group_name (rclcpp::CallbackGroup::SharedPtr callback_group)
 Get a string representation of a callback group.
 
template<typename CallbackT>
static std::string get_callback_name (const CallbackT &callback)
 Get a string representation of a callback function.
 
static std::string hash_qos_profile (const rclcpp::QoS &qos_profile)
 Create a hash for a QoS profile.
 

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 Typedef Documentation

◆ ActionClientKey

Initial value:
std::tuple<std::string, std::string, std::string,
std::string, std::type_index>

◆ PublisherKey

Initial value:
std::tuple<std::string, std::string, std::string,
std::string, std::type_index>

◆ ServiceClientKey

Initial value:
std::tuple<std::string, std::string, std::string,
std::string, std::type_index>

Member Function Documentation

◆ clear_action_clients()

void yasmin_ros::ROSClientsCache::clear_action_clients ( )
static

Clear the action clients cache.

◆ clear_all()

void yasmin_ros::ROSClientsCache::clear_all ( )
static

Clear all clients caches.

◆ clear_publishers()

void yasmin_ros::ROSClientsCache::clear_publishers ( )
static

Clear the publishers cache.

◆ clear_service_clients()

void yasmin_ros::ROSClientsCache::clear_service_clients ( )
static

Clear the service clients cache.

◆ get_action_clients()

std::map< ROSClientsCache::ActionClientKey, std::shared_ptr< void > > & yasmin_ros::ROSClientsCache::get_action_clients ( )
staticprivate

◆ get_action_clients_count()

size_t yasmin_ros::ROSClientsCache::get_action_clients_count ( )
static

Get the number of cached action clients.

Returns
The number of cached action clients.

◆ get_cache_stats()

std::map< std::string, size_t > yasmin_ros::ROSClientsCache::get_cache_stats ( )
static

Get statistics about all caches.

Returns
A map with cache statistics.

◆ get_callback_group_name()

std::string yasmin_ros::ROSClientsCache::get_callback_group_name ( rclcpp::CallbackGroup::SharedPtr callback_group)
staticprivate

Get a string representation of a callback group.

Parameters
callback_groupThe callback group to get the name from.
Returns
A string representation of the callback group.

◆ get_callback_name()

template<typename CallbackT>
static std::string yasmin_ros::ROSClientsCache::get_callback_name ( const CallbackT & callback)
inlinestaticprivate

Get a string representation of a callback function.

Template Parameters
CallbackTThe type of the callback function.
Parameters
callbackThe callback function to get the name from.
Returns
A string representation of the callback.

◆ get_lock()

std::recursive_mutex & yasmin_ros::ROSClientsCache::get_lock ( )
staticprivate

◆ get_or_create_action_client()

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

Get an existing action client from the cache or create a new one.

Template Parameters
ActionTThe type of the action.
Parameters
nodeThe ROS 2 node to use.
action_nameThe name of the action.
callback_groupThe callback group for the action client (optional).
Returns
A shared pointer to the cached or newly created action client.

◆ get_or_create_publisher()

template<typename MsgT>
static rclcpp::Publisher< MsgT >::SharedPtr yasmin_ros::ROSClientsCache::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 )
inlinestatic

Get an existing publisher from the cache or create a new one.

Template Parameters
MsgTThe type of the message.
Parameters
nodeThe ROS 2 node to use.
topic_nameThe name of the topic.
qos_profileThe QoS profile for the publisher.
callback_groupThe callback group for the publisher (optional).
Returns
A shared pointer to the cached or newly created publisher.

◆ get_or_create_service_client()

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

Get an existing service client from the cache or create a new one.

Template Parameters
ServiceTThe type of the service.
Parameters
nodeThe ROS 2 node to use.
service_nameThe name of the service.
callback_groupThe callback group for the service client (optional).
Returns
A shared pointer to the cached or newly created service client.

◆ get_publishers()

std::map< ROSClientsCache::PublisherKey, std::shared_ptr< void > > & yasmin_ros::ROSClientsCache::get_publishers ( )
staticprivate

◆ get_publishers_count()

size_t yasmin_ros::ROSClientsCache::get_publishers_count ( )
static

Get the number of cached publishers.

Returns
The number of cached publishers.

◆ get_service_clients()

std::map< ROSClientsCache::ServiceClientKey, std::shared_ptr< void > > & yasmin_ros::ROSClientsCache::get_service_clients ( )
staticprivate

◆ get_service_clients_count()

size_t yasmin_ros::ROSClientsCache::get_service_clients_count ( )
static

Get the number of cached service clients.

Returns
The number of cached service clients.

◆ get_type_name()

template<typename T>
static std::string yasmin_ros::ROSClientsCache::get_type_name ( )
inlinestaticprivate

Get a string representation of a type.

Template Parameters
TThe type to get the name from.
Returns
A string representation of the type.

◆ hash_qos_profile()

std::string yasmin_ros::ROSClientsCache::hash_qos_profile ( const rclcpp::QoS & qos_profile)
staticprivate

Create a hash for a QoS profile.

Parameters
qos_profileThe QoS profile to hash.
Returns
A string hash value for the QoS profile.

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