ros2_control - jazzy
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
31#include "hardware_interface/hardware_info.hpp"
32#include "hardware_interface/introspection.hpp"
33#include "hardware_interface/lexical_casts.hpp"
34#include "hardware_interface/macros.hpp"
35
36namespace
37{
38#ifndef _WIN32
39template <typename T>
40std::string get_type_name()
41{
42 int status = 0;
43 std::unique_ptr<char[], void (*)(void *)> res{
44 abi::__cxa_demangle(typeid(T).name(), nullptr, nullptr, &status), std::free};
45 return (status == 0) ? res.get() : typeid(T).name();
46}
47#else
48// not supported on Windows, use typeid directly
49template <typename T>
50std::string get_type_name()
51{
52 return typeid(T).name();
53}
54#endif
55} // namespace
56
57namespace hardware_interface
58{
59
61class Handle
62{
63public:
64 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
65 Handle(const std::string & prefix_name, const std::string & interface_name, double * value_ptr)
66 : prefix_name_(prefix_name),
67 interface_name_(interface_name),
68 handle_name_(prefix_name_ + "/" + interface_name_),
69 value_ptr_(value_ptr)
70 {
71 }
72
73 explicit Handle(
74 const std::string & prefix_name, const std::string & interface_name,
75 const std::string & data_type = "double", const std::string & initial_value = "")
76 : prefix_name_(prefix_name),
77 interface_name_(interface_name),
78 handle_name_(prefix_name_ + "/" + interface_name_),
79 data_type_(data_type)
80 {
81 // we need to initialize according the type passed in interface description
82 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
83 {
84 try
85 {
86 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
87 : hardware_interface::stod(initial_value);
88 value_ptr_ = std::get_if<double>(&value_);
89 }
90 catch (const std::invalid_argument & err)
91 {
92 throw std::invalid_argument(
93 fmt::format(
94 FMT_COMPILE(
95 "Invalid initial value : '{}' parsed for interface : '{}' with type : '{}'"),
96 initial_value, handle_name_, data_type_.to_string()));
97 }
98 }
99 else if (data_type_ == hardware_interface::HandleDataType::FLOAT32)
100 {
101 try
102 {
103 value_ptr_ = nullptr;
104 value_ = initial_value.empty()
105 ? std::numeric_limits<float>::quiet_NaN()
106 : static_cast<float>(hardware_interface::stof(initial_value));
107 }
108 catch (const std::invalid_argument & err)
109 {
110 throw std::invalid_argument(
111 fmt::format(
112 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
113 initial_value, handle_name_, data_type_.to_string()));
114 }
115 }
116 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
117 {
118 try
119 {
120 value_ptr_ = nullptr;
121 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
122 }
123 catch (const std::invalid_argument & err)
124 {
125 throw std::invalid_argument(
126 fmt::format(
127 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
128 initial_value, handle_name_, data_type_.to_string()));
129 }
130 }
131 else if (data_type_ == hardware_interface::HandleDataType::UINT8)
132 {
133 try
134 {
135 value_ptr_ = nullptr;
136 value_ = initial_value.empty()
137 ? static_cast<uint8_t>(std::numeric_limits<uint8_t>::max())
138 : static_cast<uint8_t>(hardware_interface::stoui8(initial_value));
139 }
140 catch (const std::invalid_argument & err)
141 {
142 throw std::invalid_argument(
143 fmt::format(
144 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
145 initial_value, handle_name_, data_type_.to_string()));
146 }
147 }
148 else if (data_type_ == hardware_interface::HandleDataType::INT8)
149 {
150 try
151 {
152 value_ptr_ = nullptr;
153 value_ = initial_value.empty()
154 ? static_cast<int8_t>(std::numeric_limits<int8_t>::max())
155 : static_cast<int8_t>(hardware_interface::stoi8(initial_value));
156 }
157 catch (const std::invalid_argument & err)
158 {
159 throw std::invalid_argument(
160 fmt::format(
161 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
162 initial_value, handle_name_, data_type_.to_string()));
163 }
164 }
165 else if (data_type_ == hardware_interface::HandleDataType::UINT16)
166 {
167 try
168 {
169 value_ptr_ = nullptr;
170 value_ = initial_value.empty()
171 ? static_cast<uint16_t>(std::numeric_limits<uint16_t>::max())
172 : static_cast<uint16_t>(hardware_interface::stoui16(initial_value));
173 }
174 catch (const std::invalid_argument & err)
175 {
176 throw std::invalid_argument(
177 fmt::format(
178 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
179 initial_value, handle_name_, data_type_.to_string()));
180 }
181 }
182 else if (data_type_ == hardware_interface::HandleDataType::INT16)
183 {
184 try
185 {
186 value_ptr_ = nullptr;
187 value_ = initial_value.empty()
188 ? static_cast<int16_t>(std::numeric_limits<int16_t>::max())
189 : static_cast<int16_t>(hardware_interface::stoi16(initial_value));
190 }
191 catch (const std::invalid_argument & err)
192 {
193 throw std::invalid_argument(
194 fmt::format(
195 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
196 initial_value, handle_name_, data_type_.to_string()));
197 }
198 }
199 else if (data_type_ == hardware_interface::HandleDataType::UINT32)
200 {
201 try
202 {
203 value_ptr_ = nullptr;
204 value_ = initial_value.empty()
205 ? static_cast<uint32_t>(std::numeric_limits<uint32_t>::max())
206 : static_cast<uint32_t>(hardware_interface::stoui32(initial_value));
207 }
208 catch (const std::invalid_argument & err)
209 {
210 throw std::invalid_argument(
211 fmt::format(
212 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
213 initial_value, handle_name_, data_type_.to_string()));
214 }
215 }
216 else if (data_type_ == hardware_interface::HandleDataType::INT32)
217 {
218 try
219 {
220 value_ptr_ = nullptr;
221 value_ = initial_value.empty()
222 ? static_cast<int32_t>(std::numeric_limits<int32_t>::max())
223 : static_cast<int32_t>(hardware_interface::stoi32(initial_value));
224 }
225 catch (const std::invalid_argument & err)
226 {
227 throw std::invalid_argument(
228 fmt::format(
229 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
230 initial_value, handle_name_, data_type_.to_string()));
231 }
232 }
233 else
234 {
235 throw std::runtime_error(
236 fmt::format(
237 FMT_COMPILE("Invalid data type: '{}' for interface: {}. Check supported types."),
238 data_type, handle_name_));
239 }
240 }
241
242 explicit Handle(const InterfaceDescription & interface_description)
243 : Handle(
244 interface_description.get_prefix_name(), interface_description.get_interface_name(),
245 interface_description.get_data_type_string(),
246 interface_description.interface_info.initial_value)
247 {
248 }
249
250 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
251
252 explicit Handle(const std::string & interface_name)
253 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
254 {
255 }
256
257 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
258
259 explicit Handle(const char * interface_name)
260 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
261 {
262 }
263
264 Handle(const Handle & other) noexcept { copy(other); }
265
266 Handle & operator=(const Handle & other)
267 {
268 if (this != &other)
269 {
270 copy(other);
271 }
272 return *this;
273 }
274
275 Handle(Handle && other) noexcept { swap(*this, other); }
276
277 Handle & operator=(Handle && other)
278 {
279 swap(*this, other);
280 return *this;
281 }
282
283 virtual ~Handle() = default;
284
286 inline operator bool() const { return value_ptr_ != nullptr; }
287
288 const std::string & get_name() const { return handle_name_; }
289
290 const std::string & get_interface_name() const { return interface_name_; }
291
292 [[deprecated(
293 "Replaced by get_name method, which is semantically more correct")]] const std::string &
294 get_full_name() const
295 {
296 return get_name();
297 }
298
299 const std::string & get_prefix_name() const { return prefix_name_; }
300
301 [[deprecated(
302 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
303 "removed by the ROS 2 Kilted Kaiju release.")]]
304 double get_value() const
305 {
306 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
307 if (!lock.owns_lock())
308 {
309 return std::numeric_limits<double>::quiet_NaN();
310 }
311 // BEGIN (Handle export change): for backward compatibility
312 // TODO(Manuel) return value_ if old functionality is removed
313 THROW_ON_NULLPTR(value_ptr_);
314 return *value_ptr_;
315 // END
316 }
317
328 template <typename T = double>
329 [[nodiscard]] std::optional<T> get_optional() const
330 {
331 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
332 return get_optional<T>(lock);
333 }
345 template <typename T = double>
346 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
347 {
348 if (!lock.owns_lock())
349 {
350 return std::nullopt;
351 }
352 // BEGIN (Handle export change): for backward compatibility
353 // TODO(saikishor) return value_ if old functionality is removed
354 if constexpr (std::is_same_v<T, double>)
355 {
356 switch (data_type_)
357 {
358 case HandleDataType::DOUBLE:
359 THROW_ON_NULLPTR(value_ptr_);
360 return *value_ptr_;
361 case HandleDataType::BOOL: // fallthrough
362 case HandleDataType::FLOAT32: // fallthrough
363 case HandleDataType::UINT8: // fallthrough
364 case HandleDataType::INT8: // fallthrough
365 case HandleDataType::UINT16: // fallthrough
366 case HandleDataType::INT16: // fallthrough
367 case HandleDataType::UINT32: // fallthrough
368 case HandleDataType::INT32: // fallthrough
369 throw std::runtime_error(
370 fmt::format(
371 FMT_COMPILE(
372 "Data type: '{}' will not be casted to double for interface: {}. Use "
373 "get_optional<{}>() instead."),
374 data_type_.to_string(), get_name(), data_type_.to_string()));
375 default:
376 throw std::runtime_error(
377 fmt::format(
378 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
379 data_type_.to_string(), get_name()));
380 }
381 }
382 try
383 {
384 return std::get<T>(value_);
385 }
386 catch (const std::bad_variant_access & err)
387 {
388 throw std::runtime_error(
389 fmt::format(
390 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
391 get_type_name<T>(), get_name(), data_type_.to_string()));
392 }
393 // END
394 }
395
407 template <typename T>
408 [[deprecated(
409 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
410 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]] bool
411 get_value(T & value) const
412 {
413 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
414 if (!lock.owns_lock())
415 {
416 return false;
417 }
418 // BEGIN (Handle export change): for backward compatibility
419 // TODO(Manuel) return value_ if old functionality is removed
420 if constexpr (std::is_same_v<T, double>)
421 {
422 // If the template is of type double, check if the value_ptr_ is not nullptr
423 THROW_ON_NULLPTR(value_ptr_);
424 value = *value_ptr_;
425 }
426 else
427 {
428 try
429 {
430 value = std::get<T>(value_);
431 }
432 catch (const std::bad_variant_access & err)
433 {
434 throw std::runtime_error(
435 fmt::format(
436 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
437 get_type_name<T>(), get_name(), data_type_.to_string()));
438 }
439 }
440 return true;
441 // END
442 }
443
456 template <
457 typename T, typename = std::enable_if_t<
458 !std::is_same_v<std::decay_t<T>, std::shared_lock<std::shared_mutex>>>>
459 [[nodiscard]] bool get_value(T & value, bool wait_for_lock) const
460 {
461 if (wait_for_lock)
462 {
463 std::shared_lock<std::shared_mutex> lock(handle_mutex_);
464 return get_value(lock, value);
465 }
466 else
467 {
468 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
469 return get_value(lock, value);
470 }
471 }
472
484 template <typename T>
485 [[nodiscard]] bool set_value(const T & value, bool wait_for_lock)
486 {
487 if (wait_for_lock)
488 {
489 std::unique_lock<std::shared_mutex> lock(handle_mutex_);
490 return set_value(lock, value);
491 }
492 else
493 {
494 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
495 return set_value(lock, value);
496 }
497 }
498
510 template <typename T>
511 [[nodiscard]] bool set_value(const T & value)
512 {
513 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
514 return set_value(lock, value);
515 }
516
529 template <typename T>
530 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
531 {
532 if (!lock.owns_lock())
533 {
534 return false;
535 }
536 // BEGIN (Handle export change): for backward compatibility
537 // TODO(Manuel) set value_ directly if old functionality is removed
538 if constexpr (std::is_same_v<T, double>)
539 {
540 // If the template is of type double, check if the value_ptr_ is not nullptr
541 THROW_ON_NULLPTR(value_ptr_);
542 *value_ptr_ = value;
543 }
544 else
545 {
546 if (!std::holds_alternative<T>(value_))
547 {
548 throw std::runtime_error(
549 fmt::format(
550 FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
551 get_type_name<T>(), get_name(), data_type_.to_string()));
552 }
553 value_ = value;
554 }
555 return true;
556 // END
557 }
558
559 std::shared_mutex & get_mutex() const { return handle_mutex_; }
560
561 HandleDataType get_data_type() const { return data_type_; }
562
564 bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
565
566 bool is_valid() const
567 {
568 return (value_ptr_ != nullptr) || !std::holds_alternative<std::monostate>(value_);
569 }
570
571protected:
581 template <typename T>
582 [[nodiscard]] bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value) const
583 {
584 if (!lock.owns_lock())
585 {
586 return false;
587 }
588 // BEGIN (Handle export change): for backward compatibility
589 // TODO(saikishor) get value_ if old functionality is removed
590 if constexpr (std::is_same_v<T, double>)
591 {
592 switch (data_type_)
593 {
594 case HandleDataType::DOUBLE:
595 THROW_ON_NULLPTR(value_ptr_);
596 value = *value_ptr_;
597 return true;
598 case HandleDataType::BOOL: // fallthrough
599 case HandleDataType::FLOAT32: // fallthrough
600 case HandleDataType::UINT8: // fallthrough
601 case HandleDataType::INT8: // fallthrough
602 case HandleDataType::UINT16: // fallthrough
603 case HandleDataType::INT16: // fallthrough
604 case HandleDataType::UINT32: // fallthrough
605 case HandleDataType::INT32: // fallthrough
606 throw std::runtime_error(
607 fmt::format(
608 FMT_COMPILE(
609 "Data type: '{}' will not be casted to double for interface: {}. Use "
610 "get_optional<{}>() instead."),
611 data_type_.to_string(), get_name(), data_type_.to_string()));
612 default:
613 throw std::runtime_error(
614 fmt::format(
615 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
616 data_type_.to_string(), get_name()));
617 }
618 }
619 try
620 {
621 value = std::get<T>(value_);
622 return true;
623 }
624 catch (const std::bad_variant_access & err)
625 {
626 throw std::runtime_error(
627 fmt::format(
628 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
629 get_type_name<T>(), get_name(), data_type_.to_string()));
630 }
631 }
632
633private:
634 void copy(const Handle & other) noexcept
635 {
636 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
637 prefix_name_ = other.prefix_name_;
638 interface_name_ = other.interface_name_;
639 handle_name_ = other.handle_name_;
640 value_ = other.value_;
641 if (std::holds_alternative<std::monostate>(value_))
642 {
643 value_ptr_ = other.value_ptr_;
644 }
645 else
646 {
647 value_ptr_ = std::get_if<double>(&value_);
648 }
649 }
650
651 void swap(Handle & first, Handle & second) noexcept
652 {
653 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
654 std::swap(first.prefix_name_, second.prefix_name_);
655 std::swap(first.interface_name_, second.interface_name_);
656 std::swap(first.handle_name_, second.handle_name_);
657 std::swap(first.value_, second.value_);
658 std::swap(first.value_ptr_, second.value_ptr_);
659 }
660
661protected:
662 std::string prefix_name_;
663 std::string interface_name_;
664 std::string handle_name_;
665 HANDLE_DATATYPE value_ = std::monostate{};
666 HandleDataType data_type_ = HandleDataType::DOUBLE;
667 // BEGIN (Handle export change): for backward compatibility
668 // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
669 double * value_ptr_ = nullptr;
670 // END
671 mutable std::shared_mutex handle_mutex_;
672};
673
674class StateInterface : public Handle
675{
676public:
677 explicit StateInterface(const InterfaceDescription & interface_description)
678 : Handle(interface_description)
679 {
680 }
681
682 void registerIntrospection() const
683 {
684 if (!is_valid())
685 {
686 RCLCPP_WARN(
687 rclcpp::get_logger(get_name()),
688 "Cannot register state introspection for state interface: %s without a valid value "
689 "pointer or initialized value.",
690 get_name().c_str());
691 return;
692 }
693 if (value_ptr_ || data_type_.is_castable_to_double())
694 {
695 std::function<double()> f = [this]()
696 {
697 if (value_ptr_)
698 {
699 return *value_ptr_;
700 }
701 else
702 {
703 return data_type_.cast_to_double(value_);
704 }
705 };
706 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
707 }
708 }
709
710 void unregisterIntrospection() const
711 {
712 if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
713 {
714 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
715 }
716 }
717
718 StateInterface(const StateInterface & other) = default;
719
720 StateInterface(StateInterface && other) = default;
721
722// Disable deprecated warnings
723#pragma GCC diagnostic push
724#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
725 using Handle::Handle;
726#pragma GCC diagnostic pop
727
728 using SharedPtr = std::shared_ptr<StateInterface>;
729 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
730};
731
733{
734public:
735 explicit CommandInterface(const InterfaceDescription & interface_description)
736 : Handle(interface_description)
737 {
738 }
740
745 CommandInterface(const CommandInterface & other) = delete;
746
747 CommandInterface(CommandInterface && other) = default;
748
749 void set_on_set_command_limiter(std::function<double(double, bool &)> on_set_command_limiter)
750 {
751 on_set_command_limiter_ = on_set_command_limiter;
752 }
753
755
759 template <typename T>
760 [[nodiscard]] bool set_limited_value(const T & value)
761 {
762 if constexpr (std::is_same_v<T, double>)
763 {
764 return set_value(on_set_command_limiter_(value, is_command_limited_));
765 }
766 else
767 {
768 return set_value(value);
769 }
770 }
771
772 const bool & is_limited() const { return is_command_limited_; }
773
774 void registerIntrospection() const
775 {
776 if (!is_valid())
777 {
778 RCLCPP_WARN(
779 rclcpp::get_logger(get_name()),
780 "Cannot register command introspection for command interface: %s without a valid value "
781 "pointer or initialized value.",
782 get_name().c_str());
783 return;
784 }
785 if (value_ptr_ || data_type_.is_castable_to_double())
786 {
787 std::function<double()> f = [this]()
788 {
789 if (value_ptr_)
790 {
791 return *value_ptr_;
792 }
793 else
794 {
795 return data_type_.cast_to_double(value_);
796 }
797 };
798 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
799 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
800 "command_interface." + get_name() + ".is_limited", &is_command_limited_);
801 }
802 }
803
804 void unregisterIntrospection() const
805 {
806 if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
807 {
808 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
809 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
810 "command_interface." + get_name() + ".is_limited");
811 }
812 }
813
814// Disable deprecated warnings
815#pragma GCC diagnostic push
816#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
817 using Handle::Handle;
818#pragma GCC diagnostic pop
819
820 using SharedPtr = std::shared_ptr<CommandInterface>;
821
822private:
823 bool is_command_limited_ = false;
824 std::function<double(double, bool &)> on_set_command_limiter_ =
825 [](double value, bool & is_limited)
826 {
827 is_limited = false;
828 return value;
829 };
830};
831
832} // namespace hardware_interface
833
834#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Definition handle.hpp:733
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:760
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:247
double cast_to_double(const HANDLE_DATATYPE &value) const
Cast the given value to double.
Definition hardware_info.hpp:273
A handle used to get and set a value on a given interface.
Definition handle.hpp:62
bool set_value(const T &value)
Set the value of the handle.
Definition handle.hpp:511
bool get_value(T &value) const
Get the value of the handle.
Definition handle.hpp:411
bool get_value(std::shared_lock< std::shared_mutex > &lock, T &value) const
Get the value of the handle.
Definition handle.hpp:582
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:346
bool get_value(T &value, bool wait_for_lock) const
Get the value of the handle.
Definition handle.hpp:459
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:564
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:530
bool set_value(const T &value, bool wait_for_lock)
Set the value of the handle.
Definition handle.hpp:485
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:329
Definition handle.hpp:675
Definition actuator.hpp:22
std::variant< std::monostate, double, float, bool, uint8_t, int8_t, uint16_t, int16_t, uint32_t, int32_t > HANDLE_DATATYPE
Definition hardware_info.hpp:141
float stof(const std::string &s)
Helper function to convert a std::string to float in a locale-independent way.
Definition lexical_casts.cpp:94
double stod(const std::string &s)
Helper function to convert a std::string to double in a locale-independent way.
Definition lexical_casts.cpp:85
bool parse_bool(const std::string &bool_string)
Parse a boolean value from a string.
Definition lexical_casts.cpp:112
Definition hardware_info.hpp:312
InterfaceInfo interface_info
Definition hardware_info.hpp:328
std::string initial_value
(Optional) Initial value of the interface.
Definition hardware_info.hpp:45