ros2_control - rolling
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/macros.hpp"
35
36namespace
37{
38template <typename T>
39std::string get_type_name()
40{
41 int status = 0;
42 std::unique_ptr<char[], void (*)(void *)> res{
43 abi::__cxa_demangle(typeid(T).name(), nullptr, nullptr, &status), std::free};
44 return (status == 0) ? res.get() : typeid(T).name();
45}
46} // namespace
47
48namespace hardware_interface
49{
50
51using HANDLE_DATATYPE = std::variant<std::monostate, double, bool>;
52
54class Handle
55{
56public:
57 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
58 Handle(
59 const std::string & prefix_name, const std::string & interface_name,
60 double * value_ptr = nullptr)
61 : prefix_name_(prefix_name),
62 interface_name_(interface_name),
63 handle_name_(prefix_name_ + "/" + interface_name_),
64 value_ptr_(value_ptr)
65 {
66 }
67
68 explicit Handle(const InterfaceDescription & interface_description)
69 : prefix_name_(interface_description.get_prefix_name()),
70 interface_name_(interface_description.get_interface_name()),
71 handle_name_(interface_description.get_name())
72 {
73 data_type_ = interface_description.get_data_type();
74 // As soon as multiple datatypes are used in HANDLE_DATATYPE
75 // we need to initialize according the type passed in interface description
76 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
77 {
78 value_ = std::numeric_limits<double>::quiet_NaN();
79 value_ptr_ = std::get_if<double>(&value_);
80 }
81 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
82 {
83 value_ptr_ = nullptr;
84 value_ = false;
85 }
86 else
87 {
88 throw std::runtime_error(
89 fmt::format(
90 FMT_COMPILE("Invalid data type : '{}' for interface : {}"),
91 interface_description.interface_info.data_type, interface_description.get_name()));
92 }
93 }
94
95 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
96
97 explicit Handle(const std::string & interface_name)
98 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
99 {
100 }
101
102 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
103
104 explicit Handle(const char * interface_name)
105 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
106 {
107 }
108
109 Handle(const Handle & other) noexcept { copy(other); }
110
111 Handle & operator=(const Handle & other)
112 {
113 if (this != &other)
114 {
115 copy(other);
116 }
117 return *this;
118 }
119
120 Handle(Handle && other) noexcept { swap(*this, other); }
121
122 Handle & operator=(Handle && other)
123 {
124 swap(*this, other);
125 return *this;
126 }
127
128 virtual ~Handle() = default;
129
131 inline operator bool() const { return value_ptr_ != nullptr; }
132
133 const std::string & get_name() const { return handle_name_; }
134
135 const std::string & get_interface_name() const { return interface_name_; }
136
137 [[deprecated(
138 "Replaced by get_name method, which is semantically more correct")]] const std::string &
139 get_full_name() const
140 {
141 return get_name();
142 }
143
144 const std::string & get_prefix_name() const { return prefix_name_; }
145
146 [[deprecated(
147 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
148 "removed by the ROS 2 Kilted Kaiju release.")]]
149 double get_value() const
150 {
151 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
152 if (!lock.owns_lock())
153 {
154 return std::numeric_limits<double>::quiet_NaN();
155 }
156 // BEGIN (Handle export change): for backward compatibility
157 // TODO(Manuel) return value_ if old functionality is removed
158 THROW_ON_NULLPTR(value_ptr_);
159 return *value_ptr_;
160 // END
161 }
162
173 template <typename T = double>
174 [[nodiscard]] std::optional<T> get_optional() const
175 {
176 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
177 return get_optional<T>(lock);
178 }
190 template <typename T = double>
191 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
192 {
193 if (!lock.owns_lock())
194 {
195 return std::nullopt;
196 }
197 // BEGIN (Handle export change): for backward compatibility
198 // TODO(saikishor) return value_ if old functionality is removed
199 if constexpr (std::is_same_v<T, double>)
200 {
201 // If the template is of type double, check if the value_ptr_ is not nullptr
202 THROW_ON_NULLPTR(value_ptr_);
203 return *value_ptr_;
204 }
205 try
206 {
207 return std::get<T>(value_);
208 }
209 catch (const std::bad_variant_access & err)
210 {
211 throw std::runtime_error(
212 fmt::format(
213 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
214 get_type_name<T>(), get_name(), data_type_.to_string()));
215 }
216 // END
217 }
218
230 template <typename T>
231 [[deprecated(
232 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
233 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]] bool
234 get_value(T & value) const
235 {
236 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
237 if (!lock.owns_lock())
238 {
239 return false;
240 }
241 // BEGIN (Handle export change): for backward compatibility
242 // TODO(Manuel) return value_ if old functionality is removed
243 if constexpr (std::is_same_v<T, double>)
244 {
245 // If the template is of type double, check if the value_ptr_ is not nullptr
246 THROW_ON_NULLPTR(value_ptr_);
247 value = *value_ptr_;
248 }
249 else
250 {
251 try
252 {
253 value = std::get<T>(value_);
254 }
255 catch (const std::bad_variant_access & err)
256 {
257 throw std::runtime_error(
258 fmt::format(
259 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
260 get_type_name<T>(), get_name(), data_type_.to_string()));
261 }
262 }
263 return true;
264 // END
265 }
266
278 template <typename T>
279 [[nodiscard]] bool set_value(const T & value)
280 {
281 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
282 return set_value(lock, value);
283 }
284
297 template <typename T>
298 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
299 {
300 if (!lock.owns_lock())
301 {
302 return false;
303 }
304 // BEGIN (Handle export change): for backward compatibility
305 // TODO(Manuel) set value_ directly if old functionality is removed
306 if constexpr (std::is_same_v<T, double>)
307 {
308 // If the template is of type double, check if the value_ptr_ is not nullptr
309 THROW_ON_NULLPTR(value_ptr_);
310 *value_ptr_ = value;
311 }
312 else
313 {
314 if (!std::holds_alternative<T>(value_))
315 {
316 throw std::runtime_error(
317 fmt::format(
318 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
319 get_type_name<T>(), get_name(), data_type_.to_string()));
320 }
321 value_ = value;
322 }
323 return true;
324 // END
325 }
326
327 std::shared_mutex & get_mutex() const { return handle_mutex_; }
328
329 HandleDataType get_data_type() const { return data_type_; }
330
331private:
332 void copy(const Handle & other) noexcept
333 {
334 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
335 prefix_name_ = other.prefix_name_;
336 interface_name_ = other.interface_name_;
337 handle_name_ = other.handle_name_;
338 value_ = other.value_;
339 if (std::holds_alternative<std::monostate>(value_))
340 {
341 value_ptr_ = other.value_ptr_;
342 }
343 else
344 {
345 value_ptr_ = std::get_if<double>(&value_);
346 }
347 }
348
349 void swap(Handle & first, Handle & second) noexcept
350 {
351 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
352 std::swap(first.prefix_name_, second.prefix_name_);
353 std::swap(first.interface_name_, second.interface_name_);
354 std::swap(first.handle_name_, second.handle_name_);
355 std::swap(first.value_, second.value_);
356 std::swap(first.value_ptr_, second.value_ptr_);
357 }
358
359protected:
360 std::string prefix_name_;
361 std::string interface_name_;
362 std::string handle_name_;
363 HANDLE_DATATYPE value_ = std::monostate{};
364 HandleDataType data_type_ = HandleDataType::DOUBLE;
365 // BEGIN (Handle export change): for backward compatibility
366 // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
367 double * value_ptr_;
368 // END
369 mutable std::shared_mutex handle_mutex_;
370};
371
372class StateInterface : public Handle
373{
374public:
375 explicit StateInterface(const InterfaceDescription & interface_description)
376 : Handle(interface_description)
377 {
378 }
379
380 void registerIntrospection() const
381 {
382 if (value_ptr_ || std::holds_alternative<double>(value_))
383 {
384 std::function<double()> f = [this]()
385 { return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
386 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
387 }
388 }
389
390 void unregisterIntrospection() const
391 {
392 if (value_ptr_ || std::holds_alternative<double>(value_))
393 {
394 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
395 }
396 }
397
398 StateInterface(const StateInterface & other) = default;
399
400 StateInterface(StateInterface && other) = default;
401
402// Disable deprecated warnings
403#pragma GCC diagnostic push
404#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
405 using Handle::Handle;
406#pragma GCC diagnostic pop
407
408 using SharedPtr = std::shared_ptr<StateInterface>;
409 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
410};
411
413{
414public:
415 explicit CommandInterface(const InterfaceDescription & interface_description)
416 : Handle(interface_description)
417 {
418 }
420
425 CommandInterface(const CommandInterface & other) = delete;
426
427 CommandInterface(CommandInterface && other) = default;
428
429 void set_on_set_command_limiter(std::function<double(double, bool &)> on_set_command_limiter)
430 {
431 on_set_command_limiter_ = on_set_command_limiter;
432 }
433
435
439 template <typename T>
440 [[nodiscard]] bool set_limited_value(const T & value)
441 {
442 if constexpr (std::is_same_v<T, double>)
443 {
444 return set_value(on_set_command_limiter_(value, is_command_limited_));
445 }
446 else
447 {
448 return set_value(value);
449 }
450 }
451
452 const bool & is_limited() const { return is_command_limited_; }
453
454 void registerIntrospection() const
455 {
456 if (value_ptr_ || std::holds_alternative<double>(value_))
457 {
458 std::function<double()> f = [this]()
459 { return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
460 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
461 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
462 "command_interface." + get_name() + ".is_limited", &is_command_limited_);
463 }
464 }
465
466 void unregisterIntrospection() const
467 {
468 if (value_ptr_ || std::holds_alternative<double>(value_))
469 {
470 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
471 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
472 "command_interface." + get_name() + ".is_limited");
473 }
474 }
475
476// Disable deprecated warnings
477#pragma GCC diagnostic push
478#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
479 using Handle::Handle;
480#pragma GCC diagnostic pop
481
482 using SharedPtr = std::shared_ptr<CommandInterface>;
483
484private:
485 bool is_command_limited_ = false;
486 std::function<double(double, bool &)> on_set_command_limiter_ =
487 [](double value, bool & is_limited)
488 {
489 is_limited = false;
490 return value;
491 };
492};
493
494} // namespace hardware_interface
495
496#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Definition handle.hpp:413
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:440
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:55
bool set_value(const T &value)
Set the value of the handle.
Definition handle.hpp:279
bool get_value(T &value) const
Get the value of the handle.
Definition handle.hpp:234
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:191
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:298
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:174
Definition handle.hpp:373
Definition actuator.hpp:34
Definition hardware_info.hpp:198
InterfaceInfo interface_info
Definition hardware_info.hpp:214
std::string data_type
(Optional) The datatype of the interface, e.g. "bool", "int".
Definition hardware_info.hpp:44