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_),
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_),
82 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
86 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
88 value_ptr_ = std::get_if<double>(&value_);
90 catch (
const std::invalid_argument & err)
92 throw std::invalid_argument(
95 "Invalid initial value : '{}' parsed for interface : '{}' with type : '{}'"),
96 initial_value, handle_name_, data_type_.to_string()));
99 else if (data_type_ == hardware_interface::HandleDataType::FLOAT32)
103 value_ptr_ =
nullptr;
104 value_ = initial_value.empty()
105 ? std::numeric_limits<float>::quiet_NaN()
108 catch (
const std::invalid_argument & err)
110 throw std::invalid_argument(
112 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
113 initial_value, handle_name_, data_type_.to_string()));
116 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
120 value_ptr_ =
nullptr;
123 catch (
const std::invalid_argument & err)
125 throw std::invalid_argument(
127 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
128 initial_value, handle_name_, data_type_.to_string()));
131 else if (data_type_ == hardware_interface::HandleDataType::UINT8)
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));
140 catch (
const std::invalid_argument & err)
142 throw std::invalid_argument(
144 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
145 initial_value, handle_name_, data_type_.to_string()));
148 else if (data_type_ == hardware_interface::HandleDataType::INT8)
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));
157 catch (
const std::invalid_argument & err)
159 throw std::invalid_argument(
161 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
162 initial_value, handle_name_, data_type_.to_string()));
165 else if (data_type_ == hardware_interface::HandleDataType::UINT16)
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));
174 catch (
const std::invalid_argument & err)
176 throw std::invalid_argument(
178 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
179 initial_value, handle_name_, data_type_.to_string()));
182 else if (data_type_ == hardware_interface::HandleDataType::INT16)
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));
191 catch (
const std::invalid_argument & err)
193 throw std::invalid_argument(
195 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
196 initial_value, handle_name_, data_type_.to_string()));
199 else if (data_type_ == hardware_interface::HandleDataType::UINT32)
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));
208 catch (
const std::invalid_argument & err)
210 throw std::invalid_argument(
212 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
213 initial_value, handle_name_, data_type_.to_string()));
216 else if (data_type_ == hardware_interface::HandleDataType::INT32)
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));
225 catch (
const std::invalid_argument & err)
227 throw std::invalid_argument(
229 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
230 initial_value, handle_name_, data_type_.to_string()));
235 throw std::runtime_error(
237 FMT_COMPILE(
"Invalid data type: '{}' for interface: {}. Check supported types."),
238 data_type, handle_name_));
244 interface_description.get_prefix_name(), interface_description.get_interface_name(),
245 interface_description.get_data_type_string(),
250 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
252 explicit Handle(
const std::string & interface_name)
253 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
257 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
259 explicit Handle(
const char * interface_name)
260 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
275 Handle(
Handle && other)
noexcept { swap(*
this, other); }
286 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
288 const std::string & get_name()
const {
return handle_name_; }
290 const std::string & get_interface_name()
const {
return interface_name_; }
293 "Replaced by get_name method, which is semantically more correct")]]
const std::string &
294 get_full_name()
const
299 const std::string & get_prefix_name()
const {
return prefix_name_; }
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
306 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
307 if (!lock.owns_lock())
309 return std::numeric_limits<double>::quiet_NaN();
313 THROW_ON_NULLPTR(value_ptr_);
328 template <
typename T =
double>
331 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
332 return get_optional<T>(lock);
345 template <
typename T =
double>
346 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
348 if (!lock.owns_lock())
354 if constexpr (std::is_same_v<T, double>)
358 case HandleDataType::DOUBLE:
359 THROW_ON_NULLPTR(value_ptr_);
361 case HandleDataType::BOOL:
362 case HandleDataType::FLOAT32:
363 case HandleDataType::UINT8:
364 case HandleDataType::INT8:
365 case HandleDataType::UINT16:
366 case HandleDataType::INT16:
367 case HandleDataType::UINT32:
368 case HandleDataType::INT32:
369 throw std::runtime_error(
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()));
376 throw std::runtime_error(
378 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
379 data_type_.to_string(), get_name()));
384 return std::get<T>(value_);
386 catch (
const std::bad_variant_access & err)
388 throw std::runtime_error(
390 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
391 get_type_name<T>(), get_name(), data_type_.to_string()));
407 template <
typename T>
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
413 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
414 if (!lock.owns_lock())
420 if constexpr (std::is_same_v<T, double>)
423 THROW_ON_NULLPTR(value_ptr_);
430 value = std::get<T>(value_);
432 catch (
const std::bad_variant_access & err)
434 throw std::runtime_error(
436 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
437 get_type_name<T>(), get_name(), data_type_.to_string()));
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
463 std::shared_lock<std::shared_mutex> lock(handle_mutex_);
464 return get_value(lock, value);
468 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
469 return get_value(lock, value);
484 template <
typename T>
485 [[nodiscard]]
bool set_value(
const T & value,
bool wait_for_lock)
489 std::unique_lock<std::shared_mutex> lock(handle_mutex_);
494 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
510 template <
typename T>
513 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
529 template <
typename T>
530 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
532 if (!lock.owns_lock())
538 if constexpr (std::is_same_v<T, double>)
541 THROW_ON_NULLPTR(value_ptr_);
546 if (!std::holds_alternative<T>(value_))
548 throw std::runtime_error(
550 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
551 get_type_name<T>(), get_name(), data_type_.to_string()));
559 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
561 HandleDataType get_data_type()
const {
return data_type_; }
566 bool is_valid()
const
568 return (value_ptr_ !=
nullptr) || !std::holds_alternative<std::monostate>(value_);
581 template <
typename T>
582 [[nodiscard]]
bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value)
const
584 if (!lock.owns_lock())
590 if constexpr (std::is_same_v<T, double>)
594 case HandleDataType::DOUBLE:
595 THROW_ON_NULLPTR(value_ptr_);
598 case HandleDataType::BOOL:
599 case HandleDataType::FLOAT32:
600 case HandleDataType::UINT8:
601 case HandleDataType::INT8:
602 case HandleDataType::UINT16:
603 case HandleDataType::INT16:
604 case HandleDataType::UINT32:
605 case HandleDataType::INT32:
606 throw std::runtime_error(
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()));
613 throw std::runtime_error(
615 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
616 data_type_.to_string(), get_name()));
621 value = std::get<T>(value_);
624 catch (
const std::bad_variant_access & err)
626 throw std::runtime_error(
628 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
629 get_type_name<T>(), get_name(), data_type_.to_string()));
634 void copy(
const Handle & other)
noexcept
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_))
643 value_ptr_ = other.value_ptr_;
647 value_ptr_ = std::get_if<double>(&value_);
651 void swap(Handle & first, Handle & second)
noexcept
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_);
662 std::string prefix_name_;
663 std::string interface_name_;
664 std::string handle_name_;
666 HandleDataType data_type_ = HandleDataType::DOUBLE;
669 double * value_ptr_ =
nullptr;
671 mutable std::shared_mutex handle_mutex_;