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