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_),
86 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
90 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
92 value_ptr_ = std::get_if<double>(&value_);
94 catch (
const std::invalid_argument & err)
96 throw std::invalid_argument(
98 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
99 initial_value, handle_name_, data_type_.to_string()));
102 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
104 value_ptr_ =
nullptr;
109 throw std::runtime_error(
112 "Invalid data type: '{}' for interface: {}. Supported types are double and bool."),
113 data_type, handle_name_));
119 interface_description.get_prefix_name(), interface_description.get_interface_name(),
120 interface_description.get_data_type_string(),
125 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
127 explicit Handle(
const std::string & interface_name)
128 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
132 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
134 explicit Handle(
const char * interface_name)
135 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
150 Handle(
Handle && other)
noexcept { swap(*
this, other); }
161 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
163 const std::string & get_name()
const {
return handle_name_; }
165 const std::string & get_interface_name()
const {
return interface_name_; }
167 const std::string & get_prefix_name()
const {
return prefix_name_; }
179 template <
typename T =
double>
182 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
183 return get_optional<T>(lock);
196 template <
typename T =
double>
197 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
199 if (!lock.owns_lock())
205 if constexpr (std::is_same_v<T, double>)
209 case HandleDataType::DOUBLE:
210 THROW_ON_NULLPTR(value_ptr_);
212 case HandleDataType::BOOL:
219 rclcpp::get_logger(get_name()),
220 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
224 return static_cast<double>(std::get<bool>(value_));
226 throw std::runtime_error(
228 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
229 data_type_.to_string(), get_name()));
234 return std::get<T>(value_);
236 catch (
const std::bad_variant_access & err)
238 throw std::runtime_error(
240 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
241 get_type_name<T>(), get_name(), data_type_.to_string()));
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
265 std::shared_lock<std::shared_mutex> lock(handle_mutex_);
270 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
286 template <
typename T>
287 [[nodiscard]]
bool set_value(
const T & value,
bool wait_for_lock)
291 std::unique_lock<std::shared_mutex> lock(handle_mutex_);
296 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
312 template <
typename T>
315 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
331 template <
typename T>
332 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
334 if (!lock.owns_lock())
340 if constexpr (std::is_same_v<T, double>)
343 THROW_ON_NULLPTR(value_ptr_);
348 if (!std::holds_alternative<T>(value_))
350 throw std::runtime_error(
352 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
353 get_type_name<T>(), get_name(), data_type_.to_string()));
361 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
363 HandleDataType get_data_type()
const {
return data_type_; }
368 bool is_valid()
const
370 return (value_ptr_ !=
nullptr) || !std::holds_alternative<std::monostate>(value_);
383 template <
typename T>
384 [[nodiscard]]
bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value)
const
386 if (!lock.owns_lock())
392 if constexpr (std::is_same_v<T, double>)
396 case HandleDataType::DOUBLE:
397 THROW_ON_NULLPTR(value_ptr_);
400 case HandleDataType::BOOL:
407 rclcpp::get_logger(get_name()),
408 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
412 value =
static_cast<double>(std::get<bool>(value_));
415 throw std::runtime_error(
417 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
418 data_type_.to_string(), get_name()));
423 value = std::get<T>(value_);
426 catch (
const std::bad_variant_access & err)
428 throw std::runtime_error(
430 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
431 get_type_name<T>(), get_name(), data_type_.to_string()));
436 void copy(
const Handle & other)
noexcept
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_))
445 value_ptr_ = other.value_ptr_;
449 value_ptr_ = std::get_if<double>(&value_);
453 void swap(Handle & first, Handle & second)
noexcept
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_);
464 std::string prefix_name_;
465 std::string interface_name_;
466 std::string handle_name_;
468 HandleDataType data_type_ = HandleDataType::DOUBLE;
471 double * value_ptr_ =
nullptr;
473 mutable std::shared_mutex handle_mutex_;
479 mutable bool notified_ =
false;
544 :
Handle(interface_description)
557 void set_on_set_command_limiter(std::function<
double(
double,
bool &)> on_set_command_limiter)
559 on_set_command_limiter_ = on_set_command_limiter;
567 template <
typename T>
570 if constexpr (std::is_same_v<T, double>)
572 return set_value(on_set_command_limiter_(value, is_command_limited_));
580 const bool & is_limited()
const {
return is_command_limited_; }
582 void registerIntrospection()
const
587 rclcpp::get_logger(get_name()),
588 "Cannot register command introspection for command interface: %s without a valid value "
589 "pointer or initialized value.",
595 std::function<double()> f = [
this]()
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_);
612 void unregisterIntrospection()
const
616 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name());
617 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
618 "command_interface." + get_name() +
".is_limited");
623#pragma GCC diagnostic push
624#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
625 using Handle::Handle;
626#pragma GCC diagnostic pop
628 using SharedPtr = std::shared_ptr<CommandInterface>;
631 bool is_command_limited_ =
false;
632 std::function<double(
double,
bool &)> on_set_command_limiter_ =
633 [](
double value,
bool & is_limited)