16#ifndef YASMIN_ROS__ROS_CLIENTS_CACHE_HPP
17#define YASMIN_ROS__ROS_CLIENTS_CACHE_HPP
29#include "rclcpp/rclcpp.hpp"
30#include "rclcpp_action/rclcpp_action.hpp"
63 template <
typename ActionT>
64 static typename rclcpp_action::Client<ActionT>::SharedPtr
66 rclcpp::Node::SharedPtr node,
const std::string &action_name,
67 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr) {
70 std::string node_name = node->get_name();
74 std::make_tuple(node_name, action_type_name, action_name,
75 callback_group_name, std::type_index(
typeid(ActionT)));
77 std::lock_guard<std::recursive_mutex> lock(
get_lock());
81 auto it = action_clients.find(cache_key);
83 if (it != action_clients.end()) {
85 action_name.c_str(), action_type_name.c_str());
86 return std::static_pointer_cast<rclcpp_action::Client<ActionT>>(
92 action_name.c_str(), action_type_name.c_str());
94 auto action_client = rclcpp_action::create_client<ActionT>(
95 node, action_name, callback_group);
98 action_clients[cache_key] = std::static_pointer_cast<void>(action_client);
100 return action_client;
112 template <
typename ServiceT>
113 static typename rclcpp::Client<ServiceT>::SharedPtr
115 rclcpp::Node::SharedPtr node,
const std::string &service_name,
116 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr) {
119 std::string node_name = node->get_name();
123 std::make_tuple(node_name, service_type_name, service_name,
124 callback_group_name, std::type_index(
typeid(ServiceT)));
126 std::lock_guard<std::recursive_mutex> lock(
get_lock());
130 auto it = service_clients.find(cache_key);
132 if (it != service_clients.end()) {
133 YASMIN_LOG_INFO(
"Reusing existing service client for '%s' of type '%s'",
134 service_name.c_str(), service_type_name.c_str());
135 return std::static_pointer_cast<rclcpp::Client<ServiceT>>(it->second);
140 service_name.c_str(), service_type_name.c_str());
142#if __has_include("rclcpp/version.h")
143#include "rclcpp/version.h"
144#if RCLCPP_VERSION_GTE(28, 1, 9)
145 auto qos = rclcpp::QoS(
146 rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_services_default));
148 auto qos = rmw_qos_profile_services_default;
151 auto qos = rmw_qos_profile_services_default;
154 auto service_client =
155 node->create_client<ServiceT>(service_name, qos, callback_group);
158 service_clients[cache_key] = std::static_pointer_cast<void>(service_client);
160 return service_client;
173 template <
typename MsgT>
175 rclcpp::Node::SharedPtr node,
const std::string &topic_name,
176 const rclcpp::QoS &qos_profile = rclcpp::QoS(10),
177 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr) {
180 std::string node_name = node->get_name();
183 auto cache_key = std::make_tuple(node_name, msg_type_name, topic_name,
184 qos_hash, std::type_index(
typeid(MsgT)));
186 std::lock_guard<std::recursive_mutex> lock(
get_lock());
190 auto it = publishers.find(cache_key);
192 if (it != publishers.end()) {
193 YASMIN_LOG_INFO(
"Reusing existing publisher for topic '%s' of type '%s'",
194 topic_name.c_str(), msg_type_name.c_str());
195 return std::static_pointer_cast<rclcpp::Publisher<MsgT>>(it->second);
200 topic_name.c_str(), msg_type_name.c_str());
202 rclcpp::PublisherOptions options;
203 options.callback_group = callback_group;
206 node->create_publisher<MsgT>(topic_name, qos_profile, options);
209 publishers[cache_key] = std::static_pointer_cast<void>(publisher);
265 std::string, std::type_index>;
267 std::string, std::type_index>;
269 std::string, std::type_index>;
273 static std::map<ServiceClientKey, std::shared_ptr<void>> &
275 static std::map<PublisherKey, std::shared_ptr<void>> &
get_publishers();
278 static std::recursive_mutex &
get_lock();
287 return typeid(T).name();
306 template <
typename CallbackT>
309 std::ostringstream oss;
310 oss <<
typeid(CallbackT).name() <<
"_"
311 <<
reinterpret_cast<const void *
>(&callback);
Centralized cache for managing ROS 2 client objects.
Definition ros_clients_cache.hpp:52
static size_t get_service_clients_count()
Get the number of cached service clients.
Definition ros_clients_cache.cpp:76
static std::string get_callback_name(const CallbackT &callback)
Get a string representation of a callback function.
Definition ros_clients_cache.hpp:307
static std::map< std::string, size_t > get_cache_stats()
Get statistics about all caches.
Definition ros_clients_cache.cpp:86
static size_t get_publishers_count()
Get the number of cached publishers.
Definition ros_clients_cache.cpp:81
static void clear_all()
Clear all clients caches.
Definition ros_clients_cache.cpp:63
static std::recursive_mutex & get_lock()
Definition ros_clients_cache.cpp:40
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.
Definition ros_clients_cache.hpp:65
std::tuple< std::string, std::string, std::string, std::string, std::type_index > PublisherKey
Definition ros_clients_cache.hpp:268
static size_t get_action_clients_count()
Get the number of cached action clients.
Definition ros_clients_cache.cpp:71
static std::string get_callback_group_name(rclcpp::CallbackGroup::SharedPtr callback_group)
Get a string representation of a callback group.
Definition ros_clients_cache.cpp:99
static std::map< ActionClientKey, std::shared_ptr< void > > & get_action_clients()
Definition ros_clients_cache.cpp:23
static std::string get_type_name()
Get a string representation of a type.
Definition ros_clients_cache.hpp:286
static void clear_action_clients()
Clear the action clients cache.
Definition ros_clients_cache.cpp:45
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.
Definition ros_clients_cache.hpp:114
std::tuple< std::string, std::string, std::string, std::string, std::type_index > ActionClientKey
Definition ros_clients_cache.hpp:264
std::tuple< std::string, std::string, std::string, std::string, std::type_index > ServiceClientKey
Definition ros_clients_cache.hpp:266
static std::string hash_qos_profile(const rclcpp::QoS &qos_profile)
Create a hash for a QoS profile.
Definition ros_clients_cache.cpp:111
static void clear_publishers()
Clear the publishers cache.
Definition ros_clients_cache.cpp:57
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.
Definition ros_clients_cache.hpp:174
static std::map< ServiceClientKey, std::shared_ptr< void > > & get_service_clients()
Definition ros_clients_cache.cpp:29
static std::map< PublisherKey, std::shared_ptr< void > > & get_publishers()
Definition ros_clients_cache.cpp:35
static void clear_service_clients()
Clear the service clients cache.
Definition ros_clients_cache.cpp:51
#define YASMIN_LOG_INFO(text,...)
Definition logs.hpp:169
Definition action_state.hpp:37