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 <stdexcept>
29#include <string>
30#include <utility>
31#include <variant>
32
33#include "hardware_interface/hardware_info.hpp"
34#include "hardware_interface/introspection.hpp"
35#include "hardware_interface/lexical_casts.hpp"
36#include "hardware_interface/macros.hpp"
37
38#include "rclcpp/logging.hpp"
39
40namespace
41{
42#ifndef _WIN32
43template <typename T>
44std::string get_type_name()
45{
46 int status = 0;
47 std::unique_ptr<char[], void (*)(void *)> res{
48 abi::__cxa_demangle(typeid(T).name(), nullptr, nullptr, &status), std::free};
49 return (status == 0) ? res.get() : typeid(T).name();
50}
51#else
52// not supported on Windows, use typeid directly
53template <typename T>
54std::string get_type_name()
55{
56 return typeid(T).name();
57}
58#endif
59} // namespace
60
61namespace hardware_interface
62{
63
64using HANDLE_DATATYPE = std::variant<std::monostate, double, bool>;
65
67class Handle
68{
69public:
70 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
71 Handle(const std::string & prefix_name, const std::string & interface_name, double * value_ptr)
72 : prefix_name_(prefix_name),
73 interface_name_(interface_name),
74 handle_name_(prefix_name_ + "/" + interface_name_),
75 value_ptr_(value_ptr)
76 {
77 }
78
79 explicit Handle(
80 const std::string & prefix_name, const std::string & interface_name,
81 const std::string & data_type = "double", const std::string & initial_value = "")
82 : prefix_name_(prefix_name),
83 interface_name_(interface_name),
84 handle_name_(prefix_name_ + "/" + interface_name_),
85 data_type_(data_type)
86 {
87 // As soon as multiple datatypes are used in HANDLE_DATATYPE
88 // we need to initialize according the type passed in interface description
89 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
90 {
91 try
92 {
93 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
94 : hardware_interface::stod(initial_value);
95 value_ptr_ = std::get_if<double>(&value_);
96 }
97 catch (const std::invalid_argument & err)
98 {
99 throw std::invalid_argument(
100 fmt::format(
101 FMT_COMPILE("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
182 template <typename T = double>
183 [[nodiscard]] std::optional<T> get_optional() const
184 {
185 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
186 return get_optional<T>(lock);
187 }
199 template <typename T = double>
200 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
201 {
202 if (!lock.owns_lock())
203 {
204 return std::nullopt;
205 }
206 // BEGIN (Handle export change): for backward compatibility
207 // TODO(saikishor) return value_ if old functionality is removed
208 if constexpr (std::is_same_v<T, double>)
209 {
210 switch (data_type_)
211 {
212 case HandleDataType::DOUBLE:
213 THROW_ON_NULLPTR(value_ptr_);
214 return *value_ptr_;
215 case HandleDataType::BOOL:
216 // TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once
217 // https://github.com/ros2/rclcpp/issues/2587
218 // is fixed
219 if (!notified_)
220 {
221 RCLCPP_WARN(
222 rclcpp::get_logger(get_name()),
223 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
224 get_name().c_str());
225 notified_ = true;
226 }
227 return static_cast<double>(std::get<bool>(value_));
228 default:
229 throw std::runtime_error(
230 fmt::format(
231 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
232 data_type_.to_string(), get_name()));
233 }
234 }
235 try
236 {
237 return std::get<T>(value_);
238 }
239 catch (const std::bad_variant_access & err)
240 {
241 throw std::runtime_error(
242 fmt::format(
243 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
244 get_type_name<T>(), get_name(), data_type_.to_string()));
245 }
246 // END
247 }
248
260 template <typename T>
261 [[nodiscard]] bool set_value(const T & value)
262 {
263 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
264 return set_value(lock, value);
265 }
266
279 template <typename T>
280 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
281 {
282 if (!lock.owns_lock())
283 {
284 return false;
285 }
286 // BEGIN (Handle export change): for backward compatibility
287 // TODO(Manuel) set value_ directly if old functionality is removed
288 if constexpr (std::is_same_v<T, double>)
289 {
290 // If the template is of type double, check if the value_ptr_ is not nullptr
291 THROW_ON_NULLPTR(value_ptr_);
292 *value_ptr_ = value;
293 }
294 else
295 {
296 if (!std::holds_alternative<T>(value_))
297 {
298 throw std::runtime_error(
299 fmt::format(
300 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
301 get_type_name<T>(), get_name(), data_type_.to_string()));
302 }
303 value_ = value;
304 }
305 return true;
306 // END
307 }
308
309 std::shared_mutex & get_mutex() const { return handle_mutex_; }
310
311 HandleDataType get_data_type() const { return data_type_; }
312
314 bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
315
316private:
317 void copy(const Handle & other) noexcept
318 {
319 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
320 prefix_name_ = other.prefix_name_;
321 interface_name_ = other.interface_name_;
322 handle_name_ = other.handle_name_;
323 value_ = other.value_;
324 if (std::holds_alternative<std::monostate>(value_))
325 {
326 value_ptr_ = other.value_ptr_;
327 }
328 else
329 {
330 value_ptr_ = std::get_if<double>(&value_);
331 }
332 }
333
334 void swap(Handle & first, Handle & second) noexcept
335 {
336 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
337 std::swap(first.prefix_name_, second.prefix_name_);
338 std::swap(first.interface_name_, second.interface_name_);
339 std::swap(first.handle_name_, second.handle_name_);
340 std::swap(first.value_, second.value_);
341 std::swap(first.value_ptr_, second.value_ptr_);
342 }
343
344protected:
345 std::string prefix_name_;
346 std::string interface_name_;
347 std::string handle_name_;
348 HANDLE_DATATYPE value_ = std::monostate{};
349 HandleDataType data_type_ = HandleDataType::DOUBLE;
350 // BEGIN (Handle export change): for backward compatibility
351 // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
352 double * value_ptr_;
353 // END
354 mutable std::shared_mutex handle_mutex_;
355
356private:
357 // TODO(christophfroehlich): remove once
358 // https://github.com/ros2/rclcpp/issues/2587
359 // is fixed
360 mutable bool notified_ = false;
361};
362
363class StateInterface : public Handle
364{
365public:
366 explicit StateInterface(const InterfaceDescription & interface_description)
367 : Handle(interface_description)
368 {
369 }
370
371 void registerIntrospection() const
372 {
373 if (value_ptr_ || std::holds_alternative<double>(value_))
374 {
375 std::function<double()> f = [this]()
376 { return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
377 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
378 }
379 }
380
381 void unregisterIntrospection() const
382 {
383 if (value_ptr_ || std::holds_alternative<double>(value_))
384 {
385 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
386 }
387 }
388
389 StateInterface(const StateInterface & other) = default;
390
391 StateInterface(StateInterface && other) = default;
392
393// Disable deprecated warnings
394#pragma GCC diagnostic push
395#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
396 using Handle::Handle;
397#pragma GCC diagnostic pop
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// Disable deprecated warnings
468#pragma GCC diagnostic push
469#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
470 using Handle::Handle;
471#pragma GCC diagnostic pop
472
473 using SharedPtr = std::shared_ptr<CommandInterface>;
474
475private:
476 bool is_command_limited_ = false;
477 std::function<double(double, bool &)> on_set_command_limiter_ =
478 [](double value, bool & is_limited)
479 {
480 is_limited = false;
481 return value;
482 };
483};
484
485} // namespace hardware_interface
486
487#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.
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:68
bool set_value(const T &value)
Set the value of the handle.
Definition handle.hpp:261
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:200
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:314
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:280
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:183
Definition handle.hpp:364
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
bool parse_bool(const std::string &bool_string)
Parse a boolean value from a string.
Definition lexical_casts.cpp:74
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