|
C++ YASMIN (Yet Another State MachINe)
|
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. | |
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:
All methods are thread-safe using internal locking mechanisms.
|
private |
|
private |
|
private |
|
static |
Clear the action clients cache.
|
static |
Clear all clients caches.
|
static |
Clear the publishers cache.
|
static |
Clear the service clients cache.
|
staticprivate |
|
static |
Get the number of cached action clients.
|
static |
Get statistics about all caches.
|
staticprivate |
Get a string representation of a callback group.
| callback_group | The callback group to get the name from. |
|
inlinestaticprivate |
Get a string representation of a callback function.
| CallbackT | The type of the callback function. |
| callback | The callback function to get the name from. |
|
staticprivate |
|
inlinestatic |
Get an existing action client from the cache or create a new one.
| ActionT | The type of the action. |
| node | The ROS 2 node to use. |
| action_name | The name of the action. |
| callback_group | The callback group for the action client (optional). |
|
inlinestatic |
Get an existing publisher from the cache or create a new one.
| MsgT | The type of the message. |
| 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). |
|
inlinestatic |
Get an existing service client from the cache or create a new one.
| ServiceT | The type of the service. |
| node | The ROS 2 node to use. |
| service_name | The name of the service. |
| callback_group | The callback group for the service client (optional). |
|
staticprivate |
|
static |
Get the number of cached publishers.
|
staticprivate |
|
static |
Get the number of cached service clients.
|
inlinestaticprivate |
Get a string representation of a type.
| T | The type to get the name from. |
|
staticprivate |
Create a hash for a QoS profile.
| qos_profile | The QoS profile to hash. |