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
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
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("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
99 initial_value, handle_name_, data_type_.to_string()));
100 }
101 }
102 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
103 {
104 value_ptr_ = nullptr;
105 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
106 }
107 else
108 {
109 throw std::runtime_error(
110 fmt::format(
111 FMT_COMPILE(
112 "Invalid data type: '{}' for interface: {}. Supported types are double and bool."),
113 data_type, handle_name_));
114 }
115 }
116
117 explicit Handle(const InterfaceDescription & interface_description)
118 : Handle(
119 interface_description.get_prefix_name(), interface_description.get_interface_name(),
120 interface_description.get_data_type_string(),
121 interface_description.interface_info.initial_value)
122 {
123 }
124
125 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
126
127 explicit Handle(const std::string & interface_name)
128 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
129 {
130 }
131
132 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
133
134 explicit Handle(const char * interface_name)
135 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
136 {
137 }
138
139 Handle(const Handle & other) noexcept { copy(other); }
140
141 Handle & operator=(const Handle & other)
142 {
143 if (this != &other)
144 {
145 copy(other);
146 }
147 return *this;
148 }
149
150 Handle(Handle && other) noexcept { swap(*this, other); }
151
152 Handle & operator=(Handle && other)
153 {
154 swap(*this, other);
155 return *this;
156 }
157
158 virtual ~Handle() = default;
159
161 inline operator bool() const { return value_ptr_ != nullptr; }
162
163 const std::string & get_name() const { return handle_name_; }
164
165 const std::string & get_interface_name() const { return interface_name_; }
166
167 const std::string & get_prefix_name() const { return prefix_name_; }
168
179 template <typename T = double>
180 [[nodiscard]] std::optional<T> get_optional() const
181 {
182 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
183 return get_optional<T>(lock);
184 }
196 template <typename T = double>
197 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
198 {
199 if (!lock.owns_lock())
200 {
201 return std::nullopt;
202 }
203 // BEGIN (Handle export change): for backward compatibility
204 // TODO(saikishor) return value_ if old functionality is removed
205 if constexpr (std::is_same_v<T, double>)
206 {
207 switch (data_type_)
208 {
209 case HandleDataType::DOUBLE:
210 THROW_ON_NULLPTR(value_ptr_);
211 return *value_ptr_;
212 case HandleDataType::BOOL:
213 // TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once
214 // https://github.com/ros2/rclcpp/issues/2587
215 // is fixed
216 if (!notified_)
217 {
218 RCLCPP_WARN(
219 rclcpp::get_logger(get_name()),
220 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
221 get_name().c_str());
222 notified_ = true;
223 }
224 return static_cast<double>(std::get<bool>(value_));
225 default:
226 throw std::runtime_error(
227 fmt::format(
228 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
229 data_type_.to_string(), get_name()));
230 }
231 }
232 try
233 {
234 return std::get<T>(value_);
235 }
236 catch (const std::bad_variant_access & err)
237 {
238 throw std::runtime_error(
239 fmt::format(
240 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
241 get_type_name<T>(), get_name(), data_type_.to_string()));
242 }
243 // END
244 }
245
258 template <
259 typename T, typename = std::enable_if_t<
260 !std::is_same_v<std::decay_t<T>, std::shared_lock<std::shared_mutex>>>>
261 [[nodiscard]] bool get_value(T & value, bool wait_for_lock) const
262 {
263 if (wait_for_lock)
264 {
265 std::shared_lock<std::shared_mutex> lock(handle_mutex_);
266 return get_value(lock, value);
267 }
268 else
269 {
270 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
271 return get_value(lock, value);
272 }
273 }
274
286 template <typename T>
287 [[nodiscard]] bool set_value(const T & value, bool wait_for_lock)
288 {
289 if (wait_for_lock)
290 {
291 std::unique_lock<std::shared_mutex> lock(handle_mutex_);
292 return set_value(lock, value);
293 }
294 else
295 {
296 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
297 return set_value(lock, value);
298 }
299 }
300
312 template <typename T>
313 [[nodiscard]] bool set_value(const T & value)
314 {
315 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
316 return set_value(lock, value);
317 }
318
331 template <typename T>
332 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
333 {
334 if (!lock.owns_lock())
335 {
336 return false;
337 }
338 // BEGIN (Handle export change): for backward compatibility
339 // TODO(Manuel) set value_ directly if old functionality is removed
340 if constexpr (std::is_same_v<T, double>)
341 {
342 // If the template is of type double, check if the value_ptr_ is not nullptr
343 THROW_ON_NULLPTR(value_ptr_);
344 *value_ptr_ = value;
345 }
346 else
347 {
348 if (!std::holds_alternative<T>(value_))
349 {
350 throw std::runtime_error(
351 fmt::format(
352 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
353 get_type_name<T>(), get_name(), data_type_.to_string()));
354 }
355 value_ = value;
356 }
357 return true;
358 // END
359 }
360
361 std::shared_mutex & get_mutex() const { return handle_mutex_; }
362
363 HandleDataType get_data_type() const { return data_type_; }
364
366 bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
367
368 bool is_valid() const
369 {
370 return (value_ptr_ != nullptr) || !std::holds_alternative<std::monostate>(value_);
371 }
372
373protected:
383 template <typename T>
384 [[nodiscard]] bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value) const
385 {
386 if (!lock.owns_lock())
387 {
388 return false;
389 }
390 // BEGIN (Handle export change): for backward compatibility
391 // TODO(saikishor) get value_ if old functionality is removed
392 if constexpr (std::is_same_v<T, double>)
393 {
394 switch (data_type_)
395 {
396 case HandleDataType::DOUBLE:
397 THROW_ON_NULLPTR(value_ptr_);
398 value = *value_ptr_;
399 return true;
400 case HandleDataType::BOOL:
401 // TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once
402 // https://github.com/ros2/rclcpp/issues/2587
403 // is fixed
404 if (!notified_)
405 {
406 RCLCPP_WARN(
407 rclcpp::get_logger(get_name()),
408 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
409 get_name().c_str());
410 notified_ = true;
411 }
412 value = static_cast<double>(std::get<bool>(value_));
413 return true;
414 default:
415 throw std::runtime_error(
416 fmt::format(
417 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
418 data_type_.to_string(), get_name()));
419 }
420 }
421 try
422 {
423 value = std::get<T>(value_);
424 return true;
425 }
426 catch (const std::bad_variant_access & err)
427 {
428 throw std::runtime_error(
429 fmt::format(
430 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
431 get_type_name<T>(), get_name(), data_type_.to_string()));
432 }
433 }
434
435private:
436 void copy(const Handle & other) noexcept
437 {
438 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
439 prefix_name_ = other.prefix_name_;
440 interface_name_ = other.interface_name_;
441 handle_name_ = other.handle_name_;
442 value_ = other.value_;
443 if (std::holds_alternative<std::monostate>(value_))
444 {
445 value_ptr_ = other.value_ptr_;
446 }
447 else
448 {
449 value_ptr_ = std::get_if<double>(&value_);
450 }
451 }
452
453 void swap(Handle & first, Handle & second) noexcept
454 {
455 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
456 std::swap(first.prefix_name_, second.prefix_name_);
457 std::swap(first.interface_name_, second.interface_name_);
458 std::swap(first.handle_name_, second.handle_name_);
459 std::swap(first.value_, second.value_);
460 std::swap(first.value_ptr_, second.value_ptr_);
461 }
462
463protected:
464 std::string prefix_name_;
465 std::string interface_name_;
466 std::string handle_name_;
467 HANDLE_DATATYPE value_ = std::monostate{};
468 HandleDataType data_type_ = HandleDataType::DOUBLE;
469 // BEGIN (Handle export change): for backward compatibility
470 // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
471 double * value_ptr_ = nullptr;
472 // END
473 mutable std::shared_mutex handle_mutex_;
474
475private:
476 // TODO(christophfroehlich): remove once
477 // https://github.com/ros2/rclcpp/issues/2587
478 // is fixed
479 mutable bool notified_ = false;
480};
481
482class StateInterface : public Handle
483{
484public:
485 explicit StateInterface(const InterfaceDescription & interface_description)
486 : Handle(interface_description)
487 {
488 }
489
490 void registerIntrospection() const
491 {
492 if (!is_valid())
493 {
494 RCLCPP_WARN(
495 rclcpp::get_logger(get_name()),
496 "Cannot register state introspection for state interface: %s without a valid value "
497 "pointer or initialized value.",
498 get_name().c_str());
499 return;
500 }
501 if (value_ptr_ || data_type_.is_castable_to_double())
502 {
503 std::function<double()> f = [this]()
504 {
505 if (value_ptr_)
506 {
507 return *value_ptr_;
508 }
509 else
510 {
511 return data_type_.cast_to_double(value_);
512 }
513 };
514 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
515 }
516 }
517
518 void unregisterIntrospection() const
519 {
520 if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
521 {
522 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
523 }
524 }
525
526 StateInterface(const StateInterface & other) = default;
527
528 StateInterface(StateInterface && other) = default;
529
530// Disable deprecated warnings
531#pragma GCC diagnostic push
532#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
533 using Handle::Handle;
534#pragma GCC diagnostic pop
535
536 using SharedPtr = std::shared_ptr<StateInterface>;
537 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
538};
539
541{
542public:
543 explicit CommandInterface(const InterfaceDescription & interface_description)
544 : Handle(interface_description)
545 {
546 }
548
553 CommandInterface(const CommandInterface & other) = delete;
554
555 CommandInterface(CommandInterface && other) = default;
556
557 void set_on_set_command_limiter(std::function<double(double, bool &)> on_set_command_limiter)
558 {
559 on_set_command_limiter_ = on_set_command_limiter;
560 }
561
563
567 template <typename T>
568 [[nodiscard]] bool set_limited_value(const T & value)
569 {
570 if constexpr (std::is_same_v<T, double>)
571 {
572 return set_value(on_set_command_limiter_(value, is_command_limited_));
573 }
574 else
575 {
576 return set_value(value);
577 }
578 }
579
580 const bool & is_limited() const { return is_command_limited_; }
581
582 void registerIntrospection() const
583 {
584 if (!is_valid())
585 {
586 RCLCPP_WARN(
587 rclcpp::get_logger(get_name()),
588 "Cannot register command introspection for command interface: %s without a valid value "
589 "pointer or initialized value.",
590 get_name().c_str());
591 return;
592 }
593 if (value_ptr_ || data_type_.is_castable_to_double())
594 {
595 std::function<double()> f = [this]()
596 {
597 if (value_ptr_)
598 {
599 return *value_ptr_;
600 }
601 else
602 {
603 return data_type_.cast_to_double(value_);
604 }
605 };
606 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
607 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
608 "command_interface." + get_name() + ".is_limited", &is_command_limited_);
609 }
610 }
611
612 void unregisterIntrospection() const
613 {
614 if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
615 {
616 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
617 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
618 "command_interface." + get_name() + ".is_limited");
619 }
620 }
621
622// Disable deprecated warnings
623#pragma GCC diagnostic push
624#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
625 using Handle::Handle;
626#pragma GCC diagnostic pop
627
628 using SharedPtr = std::shared_ptr<CommandInterface>;
629
630private:
631 bool is_command_limited_ = false;
632 std::function<double(double, bool &)> on_set_command_limiter_ =
633 [](double value, bool & is_limited)
634 {
635 is_limited = false;
636 return value;
637 };
638};
639
640} // namespace hardware_interface
641
642#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Definition handle.hpp:541
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:568
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:197
double cast_to_double(const HANDLE_DATATYPE &value) const
Cast the given value to double.
Definition hardware_info.hpp:217
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:313
bool get_value(std::shared_lock< std::shared_mutex > &lock, T &value) const
Get the value of the handle.
Definition handle.hpp:384
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:197
bool get_value(T &value, bool wait_for_lock) const
Get the value of the handle.
Definition handle.hpp:261
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:366
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:332
bool set_value(const T &value, bool wait_for_lock)
Set the value of the handle.
Definition handle.hpp:287
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:180
Definition handle.hpp:483
Definition actuator.hpp:22
std::variant< std::monostate, double, bool > HANDLE_DATATYPE
Definition hardware_info.hpp:140
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:242
InterfaceInfo interface_info
Definition hardware_info.hpp:258
std::string initial_value
(Optional) Initial value of the interface.
Definition hardware_info.hpp:45