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_),
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_),
85 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
89 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
91 value_ptr_ = std::get_if<double>(&value_);
93 catch (
const std::invalid_argument & err)
95 throw std::invalid_argument(
97 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
98 initial_value, handle_name_, data_type_.to_string()));
101 else if (data_type_ == hardware_interface::HandleDataType::FLOAT32)
105 value_ptr_ =
nullptr;
106 value_ = initial_value.empty()
107 ? std::numeric_limits<float>::quiet_NaN()
110 catch (
const std::invalid_argument & err)
112 throw std::invalid_argument(
114 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
115 initial_value, handle_name_, data_type_.to_string()));
118 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
122 value_ptr_ =
nullptr;
125 catch (
const std::invalid_argument & err)
127 throw std::invalid_argument(
129 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
130 initial_value, handle_name_, data_type_.to_string()));
133 else if (data_type_ == hardware_interface::HandleDataType::UINT8)
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));
142 catch (
const std::invalid_argument & err)
144 throw std::invalid_argument(
146 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
147 initial_value, handle_name_, data_type_.to_string()));
150 else if (data_type_ == hardware_interface::HandleDataType::INT8)
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));
159 catch (
const std::invalid_argument & err)
161 throw std::invalid_argument(
163 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
164 initial_value, handle_name_, data_type_.to_string()));
167 else if (data_type_ == hardware_interface::HandleDataType::UINT16)
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));
176 catch (
const std::invalid_argument & err)
178 throw std::invalid_argument(
180 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
181 initial_value, handle_name_, data_type_.to_string()));
184 else if (data_type_ == hardware_interface::HandleDataType::INT16)
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));
193 catch (
const std::invalid_argument & err)
195 throw std::invalid_argument(
197 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
198 initial_value, handle_name_, data_type_.to_string()));
201 else if (data_type_ == hardware_interface::HandleDataType::UINT32)
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));
210 catch (
const std::invalid_argument & err)
212 throw std::invalid_argument(
214 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
215 initial_value, handle_name_, data_type_.to_string()));
218 else if (data_type_ == hardware_interface::HandleDataType::INT32)
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));
227 catch (
const std::invalid_argument & err)
229 throw std::invalid_argument(
231 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
232 initial_value, handle_name_, data_type_.to_string()));
237 throw std::runtime_error(
239 FMT_COMPILE(
"Invalid data type: '{}' for interface: {}. Check supported types."),
240 data_type, handle_name_));
246 interface_description.get_prefix_name(), interface_description.get_interface_name(),
247 interface_description.get_data_type_string(),
252 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
254 explicit Handle(
const std::string & interface_name)
255 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
259 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
261 explicit Handle(
const char * interface_name)
262 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
277 Handle(
Handle && other)
noexcept { swap(*
this, other); }
288 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
290 const std::string & get_name()
const {
return handle_name_; }
292 const std::string & get_interface_name()
const {
return interface_name_; }
294 const std::string & get_prefix_name()
const {
return prefix_name_; }
306 template <
typename T =
double>
309 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
310 return get_optional<T>(lock);
323 template <
typename T =
double>
324 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
326 if (!lock.owns_lock())
332 if constexpr (std::is_same_v<T, double>)
336 case HandleDataType::DOUBLE:
337 THROW_ON_NULLPTR(value_ptr_);
339 case HandleDataType::BOOL:
346 rclcpp::get_logger(get_name()),
"%s",
349 "Casting bool to double for interface '{}'. Better use get_optional<bool>()."),
354 return static_cast<double>(std::get<bool>(value_));
355 case HandleDataType::FLOAT32:
356 case HandleDataType::UINT8:
357 case HandleDataType::INT8:
358 case HandleDataType::UINT16:
359 case HandleDataType::INT16:
360 case HandleDataType::UINT32:
361 case HandleDataType::INT32:
362 throw std::runtime_error(
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()));
369 throw std::runtime_error(
371 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
372 data_type_.to_string(), get_name()));
377 return std::get<T>(value_);
379 catch (
const std::bad_variant_access & err)
381 throw std::runtime_error(
383 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
384 get_type_name<T>(), get_name(), data_type_.to_string()));
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
408 std::shared_lock<std::shared_mutex> lock(handle_mutex_);
413 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
429 template <
typename T>
430 [[nodiscard]]
bool set_value(
const T & value,
bool wait_for_lock)
434 std::unique_lock<std::shared_mutex> lock(handle_mutex_);
439 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
455 template <
typename T>
458 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
474 template <
typename T>
475 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
477 if (!lock.owns_lock())
483 if constexpr (std::is_same_v<T, double>)
486 THROW_ON_NULLPTR(value_ptr_);
491 if (!std::holds_alternative<T>(value_))
493 throw std::runtime_error(
495 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
496 get_type_name<T>(), get_name(), data_type_.to_string()));
504 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
506 HandleDataType get_data_type()
const {
return data_type_; }
511 bool is_valid()
const
513 return (value_ptr_ !=
nullptr) || !std::holds_alternative<std::monostate>(value_);
526 template <
typename T>
527 [[nodiscard]]
bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value)
const
529 if (!lock.owns_lock())
535 if constexpr (std::is_same_v<T, double>)
539 case HandleDataType::DOUBLE:
540 THROW_ON_NULLPTR(value_ptr_);
543 case HandleDataType::BOOL:
550 rclcpp::get_logger(get_name()),
551 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
555 value =
static_cast<double>(std::get<bool>(value_));
557 case HandleDataType::FLOAT32:
558 case HandleDataType::UINT8:
559 case HandleDataType::INT8:
560 case HandleDataType::UINT16:
561 case HandleDataType::INT16:
562 case HandleDataType::UINT32:
563 case HandleDataType::INT32:
564 throw std::runtime_error(
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()));
571 throw std::runtime_error(
573 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
574 data_type_.to_string(), get_name()));
579 value = std::get<T>(value_);
582 catch (
const std::bad_variant_access & err)
584 throw std::runtime_error(
586 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
587 get_type_name<T>(), get_name(), data_type_.to_string()));
592 void copy(
const Handle & other)
noexcept
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_))
601 value_ptr_ = other.value_ptr_;
605 value_ptr_ = std::get_if<double>(&value_);
609 void swap(Handle & first, Handle & second)
noexcept
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_);
620 std::string prefix_name_;
621 std::string interface_name_;
622 std::string handle_name_;
624 HandleDataType data_type_ = HandleDataType::DOUBLE;
627 double * value_ptr_ =
nullptr;
629 mutable std::shared_mutex handle_mutex_;
635 mutable bool notified_ =
false;