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 <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 // we need to initialize according the type passed in interface description
85 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
86 {
87 try
88 {
89 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
90 : hardware_interface::stod(initial_value);
91 value_ptr_ = std::get_if<double>(&value_);
92 }
93 catch (const std::invalid_argument & err)
94 {
95 throw std::invalid_argument(
96 fmt::format(
97 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
98 initial_value, handle_name_, data_type_.to_string()));
99 }
100 }
101 else if (data_type_ == hardware_interface::HandleDataType::FLOAT32)
102 {
103 try
104 {
105 value_ptr_ = nullptr;
106 value_ = initial_value.empty()
107 ? std::numeric_limits<float>::quiet_NaN()
108 : static_cast<float>(hardware_interface::stof(initial_value));
109 }
110 catch (const std::invalid_argument & err)
111 {
112 throw std::invalid_argument(
113 fmt::format(
114 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
115 initial_value, handle_name_, data_type_.to_string()));
116 }
117 }
118 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
119 {
120 try
121 {
122 value_ptr_ = nullptr;
123 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
124 }
125 catch (const std::invalid_argument & err)
126 {
127 throw std::invalid_argument(
128 fmt::format(
129 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
130 initial_value, handle_name_, data_type_.to_string()));
131 }
132 }
133 else if (data_type_ == hardware_interface::HandleDataType::UINT8)
134 {
135 try
136 {
137 value_ptr_ = nullptr;
138 value_ = initial_value.empty()
139 ? static_cast<uint8_t>(std::numeric_limits<uint8_t>::max())
140 : static_cast<uint8_t>(hardware_interface::stoui8(initial_value));
141 }
142 catch (const std::invalid_argument & err)
143 {
144 throw std::invalid_argument(
145 fmt::format(
146 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
147 initial_value, handle_name_, data_type_.to_string()));
148 }
149 }
150 else if (data_type_ == hardware_interface::HandleDataType::INT8)
151 {
152 try
153 {
154 value_ptr_ = nullptr;
155 value_ = initial_value.empty()
156 ? static_cast<int8_t>(std::numeric_limits<int8_t>::max())
157 : static_cast<int8_t>(hardware_interface::stoi8(initial_value));
158 }
159 catch (const std::invalid_argument & err)
160 {
161 throw std::invalid_argument(
162 fmt::format(
163 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
164 initial_value, handle_name_, data_type_.to_string()));
165 }
166 }
167 else if (data_type_ == hardware_interface::HandleDataType::UINT16)
168 {
169 try
170 {
171 value_ptr_ = nullptr;
172 value_ = initial_value.empty()
173 ? static_cast<uint16_t>(std::numeric_limits<uint16_t>::max())
174 : static_cast<uint16_t>(hardware_interface::stoui16(initial_value));
175 }
176 catch (const std::invalid_argument & err)
177 {
178 throw std::invalid_argument(
179 fmt::format(
180 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
181 initial_value, handle_name_, data_type_.to_string()));
182 }
183 }
184 else if (data_type_ == hardware_interface::HandleDataType::INT16)
185 {
186 try
187 {
188 value_ptr_ = nullptr;
189 value_ = initial_value.empty()
190 ? static_cast<int16_t>(std::numeric_limits<int16_t>::max())
191 : static_cast<int16_t>(hardware_interface::stoi16(initial_value));
192 }
193 catch (const std::invalid_argument & err)
194 {
195 throw std::invalid_argument(
196 fmt::format(
197 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
198 initial_value, handle_name_, data_type_.to_string()));
199 }
200 }
201 else if (data_type_ == hardware_interface::HandleDataType::UINT32)
202 {
203 try
204 {
205 value_ptr_ = nullptr;
206 value_ = initial_value.empty()
207 ? static_cast<uint32_t>(std::numeric_limits<uint32_t>::max())
208 : static_cast<uint32_t>(hardware_interface::stoui32(initial_value));
209 }
210 catch (const std::invalid_argument & err)
211 {
212 throw std::invalid_argument(
213 fmt::format(
214 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
215 initial_value, handle_name_, data_type_.to_string()));
216 }
217 }
218 else if (data_type_ == hardware_interface::HandleDataType::INT32)
219 {
220 try
221 {
222 value_ptr_ = nullptr;
223 value_ = initial_value.empty()
224 ? static_cast<int32_t>(std::numeric_limits<int32_t>::max())
225 : static_cast<int32_t>(hardware_interface::stoi32(initial_value));
226 }
227 catch (const std::invalid_argument & err)
228 {
229 throw std::invalid_argument(
230 fmt::format(
231 FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
232 initial_value, handle_name_, data_type_.to_string()));
233 }
234 }
235 else
236 {
237 throw std::runtime_error(
238 fmt::format(
239 FMT_COMPILE("Invalid data type: '{}' for interface: {}. Check supported types."),
240 data_type, handle_name_));
241 }
242 }
243
244 explicit Handle(const InterfaceDescription & interface_description)
245 : Handle(
246 interface_description.get_prefix_name(), interface_description.get_interface_name(),
247 interface_description.get_data_type_string(),
248 interface_description.interface_info.initial_value)
249 {
250 }
251
252 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
253
254 explicit Handle(const std::string & interface_name)
255 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
256 {
257 }
258
259 [[deprecated("Use InterfaceDescription for initializing the Interface")]]
260
261 explicit Handle(const char * interface_name)
262 : interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
263 {
264 }
265
266 Handle(const Handle & other) noexcept { copy(other); }
267
268 Handle & operator=(const Handle & other)
269 {
270 if (this != &other)
271 {
272 copy(other);
273 }
274 return *this;
275 }
276
277 Handle(Handle && other) noexcept { swap(*this, other); }
278
279 Handle & operator=(Handle && other)
280 {
281 swap(*this, other);
282 return *this;
283 }
284
285 virtual ~Handle() = default;
286
288 inline operator bool() const { return value_ptr_ != nullptr; }
289
290 const std::string & get_name() const { return handle_name_; }
291
292 const std::string & get_interface_name() const { return interface_name_; }
293
294 const std::string & get_prefix_name() const { return prefix_name_; }
295
306 template <typename T = double>
307 [[nodiscard]] std::optional<T> get_optional() const
308 {
309 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
310 return get_optional<T>(lock);
311 }
323 template <typename T = double>
324 [[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
325 {
326 if (!lock.owns_lock())
327 {
328 return std::nullopt;
329 }
330 // BEGIN (Handle export change): for backward compatibility
331 // TODO(saikishor) return value_ if old functionality is removed
332 if constexpr (std::is_same_v<T, double>)
333 {
334 switch (data_type_)
335 {
336 case HandleDataType::DOUBLE:
337 THROW_ON_NULLPTR(value_ptr_);
338 return *value_ptr_;
339 case HandleDataType::BOOL:
340 // TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once
341 // https://github.com/ros2/rclcpp/issues/2587
342 // is fixed
343 if (!notified_)
344 {
345 RCLCPP_WARN(
346 rclcpp::get_logger(get_name()), "%s",
347 fmt::format(
348 FMT_COMPILE(
349 "Casting bool to double for interface '{}'. Better use get_optional<bool>()."),
350 get_name())
351 .c_str());
352 notified_ = true;
353 }
354 return static_cast<double>(std::get<bool>(value_));
355 case HandleDataType::FLOAT32: // fallthrough
356 case HandleDataType::UINT8: // fallthrough
357 case HandleDataType::INT8: // fallthrough
358 case HandleDataType::UINT16: // fallthrough
359 case HandleDataType::INT16: // fallthrough
360 case HandleDataType::UINT32: // fallthrough
361 case HandleDataType::INT32: // fallthrough
362 throw std::runtime_error(
363 fmt::format(
364 FMT_COMPILE(
365 "Data type: '{}' will not be casted to double for interface: {}. Use "
366 "get_optional<{}>() instead."),
367 data_type_.to_string(), get_name(), data_type_.to_string()));
368 default:
369 throw std::runtime_error(
370 fmt::format(
371 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
372 data_type_.to_string(), get_name()));
373 }
374 }
375 try
376 {
377 return std::get<T>(value_);
378 }
379 catch (const std::bad_variant_access & err)
380 {
381 throw std::runtime_error(
382 fmt::format(
383 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
384 get_type_name<T>(), get_name(), data_type_.to_string()));
385 }
386 // END
387 }
388
401 template <
402 typename T, typename = std::enable_if_t<
403 !std::is_same_v<std::decay_t<T>, std::shared_lock<std::shared_mutex>>>>
404 [[nodiscard]] bool get_value(T & value, bool wait_for_lock) const
405 {
406 if (wait_for_lock)
407 {
408 std::shared_lock<std::shared_mutex> lock(handle_mutex_);
409 return get_value(lock, value);
410 }
411 else
412 {
413 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
414 return get_value(lock, value);
415 }
416 }
417
429 template <typename T>
430 [[nodiscard]] bool set_value(const T & value, bool wait_for_lock)
431 {
432 if (wait_for_lock)
433 {
434 std::unique_lock<std::shared_mutex> lock(handle_mutex_);
435 return set_value(lock, value);
436 }
437 else
438 {
439 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
440 return set_value(lock, value);
441 }
442 }
443
455 template <typename T>
456 [[nodiscard]] bool set_value(const T & value)
457 {
458 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
459 return set_value(lock, value);
460 }
461
474 template <typename T>
475 [[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
476 {
477 if (!lock.owns_lock())
478 {
479 return false;
480 }
481 // BEGIN (Handle export change): for backward compatibility
482 // TODO(Manuel) set value_ directly if old functionality is removed
483 if constexpr (std::is_same_v<T, double>)
484 {
485 // If the template is of type double, check if the value_ptr_ is not nullptr
486 THROW_ON_NULLPTR(value_ptr_);
487 *value_ptr_ = value;
488 }
489 else
490 {
491 if (!std::holds_alternative<T>(value_))
492 {
493 throw std::runtime_error(
494 fmt::format(
495 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
496 get_type_name<T>(), get_name(), data_type_.to_string()));
497 }
498 value_ = value;
499 }
500 return true;
501 // END
502 }
503
504 std::shared_mutex & get_mutex() const { return handle_mutex_; }
505
506 HandleDataType get_data_type() const { return data_type_; }
507
509 bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
510
511 bool is_valid() const
512 {
513 return (value_ptr_ != nullptr) || !std::holds_alternative<std::monostate>(value_);
514 }
515
516protected:
526 template <typename T>
527 [[nodiscard]] bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value) const
528 {
529 if (!lock.owns_lock())
530 {
531 return false;
532 }
533 // BEGIN (Handle export change): for backward compatibility
534 // TODO(saikishor) get value_ if old functionality is removed
535 if constexpr (std::is_same_v<T, double>)
536 {
537 switch (data_type_)
538 {
539 case HandleDataType::DOUBLE:
540 THROW_ON_NULLPTR(value_ptr_);
541 value = *value_ptr_;
542 return true;
543 case HandleDataType::BOOL:
544 // TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once
545 // https://github.com/ros2/rclcpp/issues/2587
546 // is fixed
547 if (!notified_)
548 {
549 RCLCPP_WARN(
550 rclcpp::get_logger(get_name()),
551 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
552 get_name().c_str());
553 notified_ = true;
554 }
555 value = static_cast<double>(std::get<bool>(value_));
556 return true;
557 case HandleDataType::FLOAT32: // fallthrough
558 case HandleDataType::UINT8: // fallthrough
559 case HandleDataType::INT8: // fallthrough
560 case HandleDataType::UINT16: // fallthrough
561 case HandleDataType::INT16: // fallthrough
562 case HandleDataType::UINT32: // fallthrough
563 case HandleDataType::INT32: // fallthrough
564 throw std::runtime_error(
565 fmt::format(
566 FMT_COMPILE(
567 "Data type: '{}' will not be casted to double for interface: {}. Use "
568 "get_optional<{}>() instead."),
569 data_type_.to_string(), get_name(), data_type_.to_string()));
570 default:
571 throw std::runtime_error(
572 fmt::format(
573 FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
574 data_type_.to_string(), get_name()));
575 }
576 }
577 try
578 {
579 value = std::get<T>(value_);
580 return true;
581 }
582 catch (const std::bad_variant_access & err)
583 {
584 throw std::runtime_error(
585 fmt::format(
586 FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
587 get_type_name<T>(), get_name(), data_type_.to_string()));
588 }
589 }
590
591private:
592 void copy(const Handle & other) noexcept
593 {
594 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
595 prefix_name_ = other.prefix_name_;
596 interface_name_ = other.interface_name_;
597 handle_name_ = other.handle_name_;
598 value_ = other.value_;
599 if (std::holds_alternative<std::monostate>(value_))
600 {
601 value_ptr_ = other.value_ptr_;
602 }
603 else
604 {
605 value_ptr_ = std::get_if<double>(&value_);
606 }
607 }
608
609 void swap(Handle & first, Handle & second) noexcept
610 {
611 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
612 std::swap(first.prefix_name_, second.prefix_name_);
613 std::swap(first.interface_name_, second.interface_name_);
614 std::swap(first.handle_name_, second.handle_name_);
615 std::swap(first.value_, second.value_);
616 std::swap(first.value_ptr_, second.value_ptr_);
617 }
618
619protected:
620 std::string prefix_name_;
621 std::string interface_name_;
622 std::string handle_name_;
623 HANDLE_DATATYPE value_ = std::monostate{};
624 HandleDataType data_type_ = HandleDataType::DOUBLE;
625 // BEGIN (Handle export change): for backward compatibility
626 // TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
627 double * value_ptr_ = nullptr;
628 // END
629 mutable std::shared_mutex handle_mutex_;
630
631private:
632 // TODO(christophfroehlich): remove once
633 // https://github.com/ros2/rclcpp/issues/2587
634 // is fixed
635 mutable bool notified_ = false;
636};
637
638class StateInterface : public Handle
639{
640public:
641 explicit StateInterface(const InterfaceDescription & interface_description)
642 : Handle(interface_description)
643 {
644 }
645
646 void registerIntrospection() const
647 {
648 if (!is_valid())
649 {
650 RCLCPP_WARN(
651 rclcpp::get_logger(get_name()),
652 "Cannot register state introspection for state interface: %s without a valid value "
653 "pointer or initialized value.",
654 get_name().c_str());
655 return;
656 }
657 if (value_ptr_ || data_type_.is_castable_to_double())
658 {
659 std::function<double()> f = [this]()
660 {
661 if (value_ptr_)
662 {
663 return *value_ptr_;
664 }
665 else
666 {
667 return data_type_.cast_to_double(value_);
668 }
669 };
670 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
671 }
672 }
673
674 void unregisterIntrospection() const
675 {
676 if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
677 {
678 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
679 }
680 }
681
682 StateInterface(const StateInterface & other) = default;
683
684 StateInterface(StateInterface && other) = default;
685
686// Disable deprecated warnings
687#pragma GCC diagnostic push
688#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
689 using Handle::Handle;
690#pragma GCC diagnostic pop
691
692 using SharedPtr = std::shared_ptr<StateInterface>;
693 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
694};
695
697{
698public:
699 explicit CommandInterface(const InterfaceDescription & interface_description)
700 : Handle(interface_description)
701 {
702 }
704
709 CommandInterface(const CommandInterface & other) = delete;
710
711 CommandInterface(CommandInterface && other) = default;
712
713 void set_on_set_command_limiter(std::function<double(double, bool &)> on_set_command_limiter)
714 {
715 on_set_command_limiter_ = on_set_command_limiter;
716 }
717
719
723 template <typename T>
724 [[nodiscard]] bool set_limited_value(const T & value)
725 {
726 if constexpr (std::is_same_v<T, double>)
727 {
728 return set_value(on_set_command_limiter_(value, is_command_limited_));
729 }
730 else
731 {
732 return set_value(value);
733 }
734 }
735
736 const bool & is_limited() const { return is_command_limited_; }
737
738 void registerIntrospection() const
739 {
740 if (!is_valid())
741 {
742 RCLCPP_WARN(
743 rclcpp::get_logger(get_name()),
744 "Cannot register command introspection for command interface: %s without a valid value "
745 "pointer or initialized value.",
746 get_name().c_str());
747 return;
748 }
749 if (value_ptr_ || data_type_.is_castable_to_double())
750 {
751 std::function<double()> f = [this]()
752 {
753 if (value_ptr_)
754 {
755 return *value_ptr_;
756 }
757 else
758 {
759 return data_type_.cast_to_double(value_);
760 }
761 };
762 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
763 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
764 "command_interface." + get_name() + ".is_limited", &is_command_limited_);
765 }
766 }
767
768 void unregisterIntrospection() const
769 {
770 if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
771 {
772 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
773 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
774 "command_interface." + get_name() + ".is_limited");
775 }
776 }
777
778// Disable deprecated warnings
779#pragma GCC diagnostic push
780#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
781 using Handle::Handle;
782#pragma GCC diagnostic pop
783
784 using SharedPtr = std::shared_ptr<CommandInterface>;
785
786private:
787 bool is_command_limited_ = false;
788 std::function<double(double, bool &)> on_set_command_limiter_ =
789 [](double value, bool & is_limited)
790 {
791 is_limited = false;
792 return value;
793 };
794};
795
796} // namespace hardware_interface
797
798#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Definition handle.hpp:697
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:724
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:65
bool set_value(const T &value)
Set the value of the handle.
Definition handle.hpp:456
bool get_value(std::shared_lock< std::shared_mutex > &lock, T &value) const
Get the value of the handle.
Definition handle.hpp:527
std::optional< T > get_optional(std::shared_lock< std::shared_mutex > &lock) const
Get the value of the handle.
Definition handle.hpp:324
bool get_value(T &value, bool wait_for_lock) const
Get the value of the handle.
Definition handle.hpp:404
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:509
bool set_value(std::unique_lock< std::shared_mutex > &lock, const T &value)
Set the value of the handle.
Definition handle.hpp:475
bool set_value(const T &value, bool wait_for_lock)
Set the value of the handle.
Definition handle.hpp:430
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:307
Definition handle.hpp:639
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