ros2_control - jazzy
Loading...
Searching...
No Matches
handle.hpp
1// Copyright 2020 PAL Robotics S.L.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef HARDWARE_INTERFACE__HANDLE_HPP_
16#define HARDWARE_INTERFACE__HANDLE_HPP_
17
18#include <fmt/compile.h>
19
20#include <algorithm>
21#include <atomic>
22#include <functional>
23#include <limits>
24#include <memory>
25#include <mutex>
26#include <optional>
27#include <shared_mutex>
28#include <string>
29#include <utility>
30#include <variant>
31
32#include "hardware_interface/hardware_info.hpp"
33#include "hardware_interface/introspection.hpp"
34#include "hardware_interface/lexical_casts.hpp"
35#include "hardware_interface/macros.hpp"
36
37namespace
38{
39#ifndef _WIN32
40template <typename T>
41std::string get_type_name()
42{
43 int status = 0;
44 std::unique_ptr<char[], void (*)(void *)> res{
45 abi::__cxa_demangle(typeid(T).name(), nullptr, nullptr, &status), std::free};
46 return (status == 0) ? res.get() : typeid(T).name();
47}
48#else
49// not supported on Windows, use typeid directly
50template <typename T>
51std::string get_type_name()
52{
53 return typeid(T).name();
54}
55#endif
56} // namespace
57
58namespace hardware_interface
59{
60
61using HANDLE_DATATYPE = std::variant<std::monostate, double, bool>;
62
64class Handle
65{
66public:
67 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
68 Handle(const std::string & prefix_name, const std::string & interface_name, double * value_ptr)
69 : prefix_name_(prefix_name),
70 interface_name_(interface_name),
71 handle_name_(prefix_name_ + "/" + interface_name_),
72 value_ptr_(value_ptr)
73 {
74 }
75
76 explicit Handle(
77 const std::string & prefix_name, const std::string & interface_name,
78 const std::string & data_type = "double", const std::string & initial_value = "")
79 : prefix_name_(prefix_name),
80 interface_name_(interface_name),
81 handle_name_(prefix_name_ + "/" + interface_name_),
82 data_type_(data_type)
83 {
84 // As soon as multiple datatypes are used in HANDLE_DATATYPE
85 // we need to initialize according the type passed in interface description
86 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
87 {
88 try
89 {
90 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
91 : hardware_interface::stod(initial_value);
92 value_ptr_ = std::get_if<double>(&value_);
93 }
94 catch (const std::invalid_argument & err)
95 {
96 throw std::invalid_argument(
97 fmt::format(
98 FMT_COMPILE(
99 "Invalid initial value : '{}' parsed for interface : '{}' with type : '{}'"),
100 initial_value, handle_name_, data_type_.to_string()));
101 }
102 }
103 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
104 {
105 value_ptr_ = nullptr;
106 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
107 }
108 else
109 {
110 throw std::runtime_error(
111 fmt::format(
112 FMT_COMPILE(
113 "Invalid data type : '{}' for interface : {}. Supported types are double and bool."),
114 data_type, handle_name_));
115 }
116 }
117
118 explicit Handle(const InterfaceDescription & interface_description)
119 : Handle(
120 interface_description.get_prefix_name(), interface_description.get_interface_name(),
121 interface_description.get_data_type_string(),
122 interface_description.interface_info.initial_value)
123 {
124 }
125
126 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
127
128 explicit Handle(const std::string & interface_name)
129 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
130 {
131 }
132
133 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
134
135 explicit Handle(const char * interface_name)
136 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
137 {
138 }
139
140 Handle(const Handle & other) noexcept { copy(other); }
141
142 Handle & operator=(const Handle & other)
143 {
144 if (this != &other)
145 {
146 copy(other);
147 }
148 return *this;
149 }
150
151 Handle(Handle && other) noexcept { swap(*this, other); }
152
153 Handle & operator=(Handle && other)
154 {
155 swap(*this, other);
156 return *this;
157 }
158
159 virtual ~Handle() = default;
160
162 inline operator bool() const { return value_ptr_ != nullptr; }
163
164 const std::string & get_name() const { return handle_name_; }
165
166 const std::string & get_interface_name() const { return interface_name_; }
167
168 [[deprecated(
169 "Replaced by get_name method, which is semantically more correct")]] const std::string &
170 get_full_name() const
171 {
172 return get_name();
173 }
174
175 const std::string & get_prefix_name() const { return prefix_name_; }
176
177 [[deprecated(
178 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
179 "removed by the ROS 2 Kilted Kaiju release.")]]
180 double get_value() const
181 {
182 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
183 if (!lock.owns_lock())
184 {
185 return std::numeric_limits<double>::quiet_NaN();
186 }
187 // BEGIN (Handle export change): for backward compatibility
188 // TODO(Manuel) return value_ if old functionality is removed
189 THROW_ON_NULLPTR(value_ptr_);
190 return *value_ptr_;
191 // END
192 }
193
204 template <typename T = double>
205 [[nodiscard]] std::optional<T> get_optional() const
206 {
207 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
208 return get_optional<T>(lock);
209 }
221 template <typename T = double>
222 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
223 {
224 if (!lock.owns_lock())
225 {
226 return std::nullopt;
227 }
228 // BEGIN (Handle export change): for backward compatibility
229 // TODO(saikishor) return value_ if old functionality is removed
230 if constexpr (std::is_same_v<T, double>)
231 {
232 // If the template is of type double, check if the value_ptr_ is not nullptr
233 THROW_ON_NULLPTR(value_ptr_);
234 return *value_ptr_;
235 }
236 try
237 {
238 return std::get<T>(value_);
239 }
240 catch (const std::bad_variant_access & err)
241 {
242 throw std::runtime_error(
243 fmt::format(
244 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
245 get_type_name<T>(), get_name(), data_type_.to_string()));
246 }
247 // END
248 }
249
261 template <typename T>
262 [[deprecated(
263 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
264 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]] bool
265 get_value(T & value) const
266 {
267 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
268 if (!lock.owns_lock())
269 {
270 return false;
271 }
272 // BEGIN (Handle export change): for backward compatibility
273 // TODO(Manuel) return value_ if old functionality is removed
274 if constexpr (std::is_same_v<T, double>)
275 {
276 // If the template is of type double, check if the value_ptr_ is not nullptr
277 THROW_ON_NULLPTR(value_ptr_);
278 value = *value_ptr_;
279 }
280 else
281 {
282 try
283 {
284 value = std::get<T>(value_);
285 }
286 catch (const std::bad_variant_access & err)
287 {
288 throw std::runtime_error(
289 fmt::format(
290 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
291 get_type_name<T>(), get_name(), data_type_.to_string()));
292 }
293 }
294 return true;
295 // END
296 }
297
309 template <typename T>
310 [[nodiscard]] bool set_value(const T & value)
311 {
312 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
313 return set_value(lock, value);
314 }
315
328 template <typename T>
329 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
330 {
331 if (!lock.owns_lock())
332 {
333 return false;
334 }
335 // BEGIN (Handle export change): for backward compatibility
336 // TODO(Manuel) set value_ directly if old functionality is removed
337 if constexpr (std::is_same_v<T, double>)
338 {
339 // If the template is of type double, check if the value_ptr_ is not nullptr
340 THROW_ON_NULLPTR(value_ptr_);
341 *value_ptr_ = value;
342 }
343 else
344 {
345 if (!std::holds_alternative<T>(value_))
346 {
347 throw std::runtime_error(
348 fmt::format(
349 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
350 get_type_name<T>(), get_name(), data_type_.to_string()));
351 }
352 value_ = value;
353 }
354 return true;
355 // END
356 }
357
358 std::shared_mutex & get_mutex() const { return handle_mutex_; }
359
360 HandleDataType get_data_type() const { return data_type_; }
361
362private:
363 void copy(const Handle & other) noexcept
364 {
365 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
366 prefix_name_ = other.prefix_name_;
367 interface_name_ = other.interface_name_;
368 handle_name_ = other.handle_name_;
369 value_ = other.value_;
370 if (std::holds_alternative<std::monostate>(value_))
371 {
372 value_ptr_ = other.value_ptr_;
373 }
374 else
375 {
376 value_ptr_ = std::get_if<double>(&value_);
377 }
378 }
379
380 void swap(Handle & first, Handle & second) noexcept
381 {
382 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
383 std::swap(first.prefix_name_, second.prefix_name_);
384 std::swap(first.interface_name_, second.interface_name_);
385 std::swap(first.handle_name_, second.handle_name_);
386 std::swap(first.value_, second.value_);
387 std::swap(first.value_ptr_, second.value_ptr_);
388 }
389
390protected:
391 std::string prefix_name_;
392 std::string interface_name_;
393 std::string handle_name_;
394 HANDLE_DATATYPE value_ = std::monostate{};
395 HandleDataType data_type_ = HandleDataType::DOUBLE;
396 // BEGIN (Handle export change): for backward compatibility
397 // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
398 double * value_ptr_;
399 // END
400 mutable std::shared_mutex handle_mutex_;
401};
402
403class StateInterface : public Handle
404{
405public:
406 explicit StateInterface(const InterfaceDescription & interface_description)
407 : Handle(interface_description)
408 {
409 }
410
411 void registerIntrospection() const
412 {
413 if (value_ptr_ || std::holds_alternative<double>(value_))
414 {
415 std::function<double()> f = [this]()
416 { return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
417 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
418 }
419 }
420
421 void unregisterIntrospection() const
422 {
423 if (value_ptr_ || std::holds_alternative<double>(value_))
424 {
425 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
426 }
427 }
428
429 StateInterface(const StateInterface & other) = default;
430
431 StateInterface(StateInterface && other) = default;
432
433// Disable deprecated warnings
434#pragma GCC diagnostic push
435#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
436 using Handle::Handle;
437#pragma GCC diagnostic pop
438
439 using SharedPtr = std::shared_ptr<StateInterface>;
440 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
441};
442
444{
445public:
446 explicit CommandInterface(const InterfaceDescription & interface_description)
447 : Handle(interface_description)
448 {
449 }
451
456 CommandInterface(const CommandInterface & other) = delete;
457
458 CommandInterface(CommandInterface && other) = default;
459
460 void set_on_set_command_limiter(std::function<double(double, bool &)> on_set_command_limiter)
461 {
462 on_set_command_limiter_ = on_set_command_limiter;
463 }
464
466
470 template <typename T>
471 [[nodiscard]] bool set_limited_value(const T & value)
472 {
473 if constexpr (std::is_same_v<T, double>)
474 {
475 return set_value(on_set_command_limiter_(value, is_command_limited_));
476 }
477 else
478 {
479 return set_value(value);
480 }
481 }
482
483 const bool & is_limited() const { return is_command_limited_; }
484
485 void registerIntrospection() const
486 {
487 if (value_ptr_ || std::holds_alternative<double>(value_))
488 {
489 std::function<double()> f = [this]()
490 { return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
491 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
492 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
493 "command_interface." + get_name() + ".is_limited", &is_command_limited_);
494 }
495 }
496
497 void unregisterIntrospection() const
498 {
499 if (value_ptr_ || std::holds_alternative<double>(value_))
500 {
501 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
502 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
503 "command_interface." + get_name() + ".is_limited");
504 }
505 }
506
507// Disable deprecated warnings
508#pragma GCC diagnostic push
509#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
510 using Handle::Handle;
511#pragma GCC diagnostic pop
512
513 using SharedPtr = std::shared_ptr<CommandInterface>;
514
515private:
516 bool is_command_limited_ = false;
517 std::function<double(double, bool &)> on_set_command_limiter_ =
518 [](double value, bool & is_limited)
519 {
520 is_limited = false;
521 return value;
522 };
523};
524
525} // namespace hardware_interface
526
527#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Definition handle.hpp:444
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:471
CommandInterface(const CommandInterface &other)=delete
CommandInterface copy constructor is actively deleted.
A handle used to get and set a value on a given interface.
Definition handle.hpp:65
bool set_value(const T &value)
Set the value of the handle.
Definition handle.hpp:310
bool get_value(T &value) const
Get the value of the handle.
Definition handle.hpp:265
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:222
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:329
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:205
Definition handle.hpp:404
Definition actuator.hpp:22
double stod(const std::string &s)
Helper function to convert a std::string to double in a locale-independent way.
Definition lexical_casts.cpp:56
Definition hardware_info.hpp:198
InterfaceInfo interface_info
Definition hardware_info.hpp:214
std::string initial_value
(Optional) Initial value of the interface.
Definition hardware_info.hpp:42