C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
ros_clients_cache.hpp
Go to the documentation of this file.
1// Copyright (C) 2025 Miguel Ángel González Santamarta
2//
3// This program is free software: you can redistribute it and/or modify
4// it under the terms of the GNU General Public License as published by
5// the Free Software Foundation, either version 3 of the License, or
6// (at your option) any later version.
7//
8// This program is distributed in the hope that it will be useful,
9// but WITHOUT ANY WARRANTY; without even the implied warranty of
10// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11// GNU General Public License for more details.
12//
13// You should have received a copy of the GNU General Public License
14// along with this program. If not, see <https://www.gnu.org/licenses/>.
15
16#ifndef YASMIN_ROS__ROS_CLIENTS_CACHE_HPP
17#define YASMIN_ROS__ROS_CLIENTS_CACHE_HPP
18
19#include <functional>
20#include <map>
21#include <memory>
22#include <mutex>
23#include <sstream>
24#include <string>
25#include <tuple>
26#include <typeindex>
27#include <typeinfo>
28
29#include "rclcpp/rclcpp.hpp"
30#include "rclcpp_action/rclcpp_action.hpp"
31#include "yasmin/logs.hpp"
32
33namespace yasmin_ros {
34
53public:
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) {
68
69 // Create a unique key
70 std::string node_name = node->get_name();
71 std::string action_type_name = get_type_name<ActionT>();
72 std::string callback_group_name = get_callback_group_name(callback_group);
73 auto cache_key =
74 std::make_tuple(node_name, action_type_name, action_name,
75 callback_group_name, std::type_index(typeid(ActionT)));
76
77 std::lock_guard<std::recursive_mutex> lock(get_lock());
78
79 // Check if action client already exists in cache
80 auto &action_clients = get_action_clients();
81 auto it = action_clients.find(cache_key);
82
83 if (it != action_clients.end()) {
84 YASMIN_LOG_INFO("Reusing existing action client for '%s' of type '%s'",
85 action_name.c_str(), action_type_name.c_str());
86 return std::static_pointer_cast<rclcpp_action::Client<ActionT>>(
87 it->second);
88 }
89
90 // Create new action client if not in cache
91 YASMIN_LOG_INFO("Creating new action client for '%s' of type '%s'",
92 action_name.c_str(), action_type_name.c_str());
93
94 auto action_client = rclcpp_action::create_client<ActionT>(
95 node, action_name, callback_group);
96
97 // Store in cache (as void pointer for type erasure)
98 action_clients[cache_key] = std::static_pointer_cast<void>(action_client);
99
100 return action_client;
101 }
102
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) {
117
118 // Create a unique key
119 std::string node_name = node->get_name();
120 std::string service_type_name = get_type_name<ServiceT>();
121 std::string callback_group_name = get_callback_group_name(callback_group);
122 auto cache_key =
123 std::make_tuple(node_name, service_type_name, service_name,
124 callback_group_name, std::type_index(typeid(ServiceT)));
125
126 std::lock_guard<std::recursive_mutex> lock(get_lock());
127
128 // Check if service client already exists in cache
129 auto &service_clients = get_service_clients();
130 auto it = service_clients.find(cache_key);
131
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);
136 }
137
138 // Create new service client if not in cache
139 YASMIN_LOG_INFO("Creating new service client for '%s' of type '%s'",
140 service_name.c_str(), service_type_name.c_str());
141
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));
147#else
148 auto qos = rmw_qos_profile_services_default;
149#endif
150#else
151 auto qos = rmw_qos_profile_services_default;
152#endif
153
154 auto service_client =
155 node->create_client<ServiceT>(service_name, qos, callback_group);
156
157 // Store in cache (as void pointer for type erasure)
158 service_clients[cache_key] = std::static_pointer_cast<void>(service_client);
159
160 return service_client;
161 }
162
173 template <typename MsgT>
174 static typename rclcpp::Publisher<MsgT>::SharedPtr get_or_create_publisher(
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) {
178
179 // Create a unique key
180 std::string node_name = node->get_name();
181 std::string msg_type_name = get_type_name<MsgT>();
182 std::string qos_hash = hash_qos_profile(qos_profile);
183 auto cache_key = std::make_tuple(node_name, msg_type_name, topic_name,
184 qos_hash, std::type_index(typeid(MsgT)));
185
186 std::lock_guard<std::recursive_mutex> lock(get_lock());
187
188 // Check if publisher already exists in cache
189 auto &publishers = get_publishers();
190 auto it = publishers.find(cache_key);
191
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);
196 }
197
198 // Create new publisher if not in cache
199 YASMIN_LOG_INFO("Creating new publisher for topic '%s' of type '%s'",
200 topic_name.c_str(), msg_type_name.c_str());
201
202 rclcpp::PublisherOptions options;
203 options.callback_group = callback_group;
204
205 auto publisher =
206 node->create_publisher<MsgT>(topic_name, qos_profile, options);
207
208 // Store in cache (as void pointer for type erasure)
209 publishers[cache_key] = std::static_pointer_cast<void>(publisher);
210
211 return publisher;
212 }
213
217 static void clear_action_clients();
218
222 static void clear_service_clients();
223
227 static void clear_publishers();
228
232 static void clear_all();
233
239 static size_t get_action_clients_count();
240
246 static size_t get_service_clients_count();
247
253 static size_t get_publishers_count();
254
260 static std::map<std::string, size_t> get_cache_stats();
261
262private:
263 // Type alias for cache keys
264 using ActionClientKey = std::tuple<std::string, std::string, std::string,
265 std::string, std::type_index>;
266 using ServiceClientKey = std::tuple<std::string, std::string, std::string,
267 std::string, std::type_index>;
268 using PublisherKey = std::tuple<std::string, std::string, std::string,
269 std::string, std::type_index>;
270
271 // Static cache maps
272 static std::map<ActionClientKey, std::shared_ptr<void>> &get_action_clients();
273 static std::map<ServiceClientKey, std::shared_ptr<void>> &
275 static std::map<PublisherKey, std::shared_ptr<void>> &get_publishers();
276
277 // Static lock for thread-safe access
278 static std::recursive_mutex &get_lock();
279
286 template <typename T> static std::string get_type_name() {
287 return typeid(T).name();
288 }
289
296 static std::string
297 get_callback_group_name(rclcpp::CallbackGroup::SharedPtr callback_group);
298
306 template <typename CallbackT>
307 static std::string get_callback_name(const CallbackT &callback) {
308 // Use the address of the callback for uniqueness
309 std::ostringstream oss;
310 oss << typeid(CallbackT).name() << "_"
311 << reinterpret_cast<const void *>(&callback);
312 return oss.str();
313 }
314
321 static std::string hash_qos_profile(const rclcpp::QoS &qos_profile);
322};
323
324} // namespace yasmin_ros
325
326#endif // YASMIN_ROS__ROS_CLIENTS_CACHE_HPP
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