ros2_control - kilted
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
37#include "rclcpp/logging.hpp"
38
39namespace
40{
41#ifndef _WIN32
42template <typename T>
43std::string get_type_name()
44{
45 int status = 0;
46 std::unique_ptr<char[], void (*)(void *)> res{
47 abi::__cxa_demangle(typeid(T).name(), nullptr, nullptr, &status), std::free};
48 return (status == 0) ? res.get() : typeid(T).name();
49}
50#else
51// not supported on Windows, use typeid directly
52template <typename T>
53std::string get_type_name()
54{
55 return typeid(T).name();
56}
57#endif
58} // namespace
59
60namespace hardware_interface
61{
62
63using HANDLE_DATATYPE = std::variant<std::monostate, double, bool>;
64
66class Handle
67{
68public:
69 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
70 Handle(const std::string & prefix_name, const std::string & interface_name, double * value_ptr)
71 : prefix_name_(prefix_name),
72 interface_name_(interface_name),
73 handle_name_(prefix_name_ + "/" + interface_name_),
74 value_ptr_(value_ptr)
75 {
76 }
77
78 explicit Handle(
79 const std::string & prefix_name, const std::string & interface_name,
80 const std::string & data_type = "double", const std::string & initial_value = "")
81 : prefix_name_(prefix_name),
82 interface_name_(interface_name),
83 handle_name_(prefix_name_ + "/" + interface_name_),
84 data_type_(data_type)
85 {
86 // As soon as multiple datatypes are used in HANDLE_DATATYPE
87 // we need to initialize according the type passed in interface description
88 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
89 {
90 try
91 {
92 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
93 : hardware_interface::stod(initial_value);
94 value_ptr_ = std::get_if<double>(&value_);
95 }
96 catch (const std::invalid_argument & err)
97 {
98 throw std::invalid_argument(
99 fmt::format(
100 FMT_COMPILE(
101 "Invalid initial value : '{}' parsed for interface : '{}' with type : '{}'"),
102 initial_value, handle_name_, data_type_.to_string()));
103 }
104 }
105 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
106 {
107 value_ptr_ = nullptr;
108 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
109 }
110 else
111 {
112 throw std::runtime_error(
113 fmt::format(
114 FMT_COMPILE(
115 "Invalid data type : '{}' for interface : {}. Supported types are double and bool."),
116 data_type, handle_name_));
117 }
118 }
119
120 explicit Handle(const InterfaceDescription & interface_description)
121 : Handle(
122 interface_description.get_prefix_name(), interface_description.get_interface_name(),
123 interface_description.get_data_type_string(),
124 interface_description.interface_info.initial_value)
125 {
126 }
127
128 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
129
130 explicit Handle(const std::string & interface_name)
131 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
132 {
133 }
134
135 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
136
137 explicit Handle(const char * interface_name)
138 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
139 {
140 }
141
142 Handle(const Handle & other) noexcept { copy(other); }
143
144 Handle & operator=(const Handle & other)
145 {
146 if (this != &other)
147 {
148 copy(other);
149 }
150 return *this;
151 }
152
153 Handle(Handle && other) noexcept { swap(*this, other); }
154
155 Handle & operator=(Handle && other)
156 {
157 swap(*this, other);
158 return *this;
159 }
160
161 virtual ~Handle() = default;
162
164 inline operator bool() const { return value_ptr_ != nullptr; }
165
166 const std::string & get_name() const { return handle_name_; }
167
168 const std::string & get_interface_name() const { return interface_name_; }
169
170 const std::string & get_prefix_name() const { return prefix_name_; }
171
172 [[deprecated(
173 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
174 "removed by the ROS 2 Kilted Kaiju release.")]]
175 double get_value() const
176 {
177 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
178 if (!lock.owns_lock())
179 {
180 return std::numeric_limits<double>::quiet_NaN();
181 }
182 // BEGIN (Handle export change): for backward compatibility
183 // TODO(Manuel) return value_ if old functionality is removed
184 THROW_ON_NULLPTR(value_ptr_);
185 return *value_ptr_;
186 // END
187 }
188
199 template <typename T = double>
200 [[nodiscard]] std::optional<T> get_optional() const
201 {
202 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
203 return get_optional<T>(lock);
204 }
216 template <typename T = double>
217 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
218 {
219 if (!lock.owns_lock())
220 {
221 return std::nullopt;
222 }
223 // BEGIN (Handle export change): for backward compatibility
224 // TODO(saikishor) return value_ if old functionality is removed
225 if constexpr (std::is_same_v<T, double>)
226 {
227 switch (data_type_)
228 {
229 case HandleDataType::DOUBLE:
230 THROW_ON_NULLPTR(value_ptr_);
231 return *value_ptr_;
232 case HandleDataType::BOOL:
233 RCLCPP_WARN_ONCE(
234 rclcpp::get_logger(get_name()),
235 "Casting bool to double for interface : %s. Better use get_optional<bool>().",
236 get_name().c_str());
237 return static_cast<double>(std::get<bool>(value_));
238 default:
239 throw std::runtime_error(
240 fmt::format(
241 FMT_COMPILE("Data type : '{}' cannot be casted to double for interface : {}"),
242 data_type_.to_string(), get_name()));
243 }
244 }
245 try
246 {
247 return std::get<T>(value_);
248 }
249 catch (const std::bad_variant_access & err)
250 {
251 throw std::runtime_error(
252 fmt::format(
253 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
254 get_type_name<T>(), get_name(), data_type_.to_string()));
255 }
256 // END
257 }
258
270 template <typename T>
271 [[nodiscard]] bool set_value(const T & value)
272 {
273 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
274 return set_value(lock, value);
275 }
276
289 template <typename T>
290 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
291 {
292 if (!lock.owns_lock())
293 {
294 return false;
295 }
296 // BEGIN (Handle export change): for backward compatibility
297 // TODO(Manuel) set value_ directly if old functionality is removed
298 if constexpr (std::is_same_v<T, double>)
299 {
300 // If the template is of type double, check if the value_ptr_ is not nullptr
301 THROW_ON_NULLPTR(value_ptr_);
302 *value_ptr_ = value;
303 }
304 else
305 {
306 if (!std::holds_alternative<T>(value_))
307 {
308 throw std::runtime_error(
309 fmt::format(
310 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
311 get_type_name<T>(), get_name(), data_type_.to_string()));
312 }
313 value_ = value;
314 }
315 return true;
316 // END
317 }
318
319 std::shared_mutex & get_mutex() const { return handle_mutex_; }
320
321 HandleDataType get_data_type() const { return data_type_; }
322
324 bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
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// Disable deprecated warnings
398#pragma GCC diagnostic push
399#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
400 using Handle::Handle;
401#pragma GCC diagnostic pop
402
403 using SharedPtr = std::shared_ptr<StateInterface>;
404 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
405};
406
408{
409public:
410 explicit CommandInterface(const InterfaceDescription & interface_description)
411 : Handle(interface_description)
412 {
413 }
415
420 CommandInterface(const CommandInterface & other) = delete;
421
422 CommandInterface(CommandInterface && other) = default;
423
424 void set_on_set_command_limiter(std::function<double(double, bool &)> on_set_command_limiter)
425 {
426 on_set_command_limiter_ = on_set_command_limiter;
427 }
428
430
434 template <typename T>
435 [[nodiscard]] bool set_limited_value(const T & value)
436 {
437 if constexpr (std::is_same_v<T, double>)
438 {
439 return set_value(on_set_command_limiter_(value, is_command_limited_));
440 }
441 else
442 {
443 return set_value(value);
444 }
445 }
446
447 const bool & is_limited() const { return is_command_limited_; }
448
449 void registerIntrospection() const
450 {
451 if (value_ptr_ || std::holds_alternative<double>(value_))
452 {
453 std::function<double()> f = [this]()
454 { return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
455 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
456 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
457 "command_interface." + get_name() + ".is_limited", &is_command_limited_);
458 }
459 }
460
461 void unregisterIntrospection() const
462 {
463 if (value_ptr_ || std::holds_alternative<double>(value_))
464 {
465 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
466 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
467 "command_interface." + get_name() + ".is_limited");
468 }
469 }
470
471// Disable deprecated warnings
472#pragma GCC diagnostic push
473#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
474 using Handle::Handle;
475#pragma GCC diagnostic pop
476
477 using SharedPtr = std::shared_ptr<CommandInterface>;
478
479private:
480 bool is_command_limited_ = false;
481 std::function<double(double, bool &)> on_set_command_limiter_ =
482 [](double value, bool & is_limited)
483 {
484 is_limited = false;
485 return value;
486 };
487};
488
489} // namespace hardware_interface
490
491#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Definition handle.hpp:408
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:435
CommandInterface(const CommandInterface &other)=delete
CommandInterface copy constructor is actively deleted.
bool is_castable_to_double() const
Check if the HandleDataType can be casted to double.
Definition hardware_info.hpp:192
A handle used to get and set a value on a given interface.
Definition handle.hpp:67
bool set_value(const T &value)
Set the value of the handle.
Definition handle.hpp:271
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:217
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:324
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:290
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:200
Definition handle.hpp:368
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:216
InterfaceInfo interface_info
Definition hardware_info.hpp:232
std::string initial_value
(Optional) Initial value of the interface.
Definition hardware_info.hpp:42