70 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
71 Handle(
const std::string & prefix_name,
const std::string & interface_name,
double * value_ptr)
72 : prefix_name_(prefix_name),
73 interface_name_(interface_name),
74 handle_name_(prefix_name_ +
"/" + interface_name_),
80 const std::string & prefix_name,
const std::string & interface_name,
81 const std::string & data_type =
"double",
const std::string & initial_value =
"")
82 : prefix_name_(prefix_name),
83 interface_name_(interface_name),
84 handle_name_(prefix_name_ +
"/" + interface_name_),
89 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
93 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
95 value_ptr_ = std::get_if<double>(&value_);
97 catch (
const std::invalid_argument & err)
99 throw std::invalid_argument(
101 FMT_COMPILE(
"Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
102 initial_value, handle_name_, data_type_.to_string()));
105 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
107 value_ptr_ =
nullptr;
112 throw std::runtime_error(
115 "Invalid data type: '{}' for interface: {}. Supported types are double and bool."),
116 data_type, handle_name_));
122 interface_description.get_prefix_name(), interface_description.get_interface_name(),
123 interface_description.get_data_type_string(),
128 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
130 explicit Handle(
const std::string & interface_name)
131 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
135 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
137 explicit Handle(
const char * interface_name)
138 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
153 Handle(
Handle && other)
noexcept { swap(*
this, other); }
164 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
166 const std::string & get_name()
const {
return handle_name_; }
168 const std::string & get_interface_name()
const {
return interface_name_; }
170 const std::string & get_prefix_name()
const {
return prefix_name_; }
182 template <
typename T =
double>
185 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
186 return get_optional<T>(lock);
199 template <
typename T =
double>
200 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
202 if (!lock.owns_lock())
208 if constexpr (std::is_same_v<T, double>)
212 case HandleDataType::DOUBLE:
213 THROW_ON_NULLPTR(value_ptr_);
215 case HandleDataType::BOOL:
222 rclcpp::get_logger(get_name()),
223 "Casting bool to double for interface: %s. Better use get_optional<bool>().",
227 return static_cast<double>(std::get<bool>(value_));
229 throw std::runtime_error(
231 FMT_COMPILE(
"Data type: '{}' cannot be casted to double for interface: {}"),
232 data_type_.to_string(), get_name()));
237 return std::get<T>(value_);
239 catch (
const std::bad_variant_access & err)
241 throw std::runtime_error(
243 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
244 get_type_name<T>(), get_name(), data_type_.to_string()));
260 template <
typename T>
263 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
279 template <
typename T>
280 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
282 if (!lock.owns_lock())
288 if constexpr (std::is_same_v<T, double>)
291 THROW_ON_NULLPTR(value_ptr_);
296 if (!std::holds_alternative<T>(value_))
298 throw std::runtime_error(
300 FMT_COMPILE(
"Invalid data type: '{}' access for interface: {} expected: '{}'"),
301 get_type_name<T>(), get_name(), data_type_.to_string()));
309 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
311 HandleDataType get_data_type()
const {
return data_type_; }
317 void copy(
const Handle & other)
noexcept
319 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
320 prefix_name_ = other.prefix_name_;
321 interface_name_ = other.interface_name_;
322 handle_name_ = other.handle_name_;
323 value_ = other.value_;
324 if (std::holds_alternative<std::monostate>(value_))
326 value_ptr_ = other.value_ptr_;
330 value_ptr_ = std::get_if<double>(&value_);
334 void swap(Handle & first, Handle & second)
noexcept
336 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
337 std::swap(first.prefix_name_, second.prefix_name_);
338 std::swap(first.interface_name_, second.interface_name_);
339 std::swap(first.handle_name_, second.handle_name_);
340 std::swap(first.value_, second.value_);
341 std::swap(first.value_ptr_, second.value_ptr_);
345 std::string prefix_name_;
346 std::string interface_name_;
347 std::string handle_name_;
348 HANDLE_DATATYPE value_ = std::monostate{};
349 HandleDataType data_type_ = HandleDataType::DOUBLE;
354 mutable std::shared_mutex handle_mutex_;
360 mutable bool notified_ =
false;
407 :
Handle(interface_description)
420 void set_on_set_command_limiter(std::function<
double(
double,
bool &)> on_set_command_limiter)
422 on_set_command_limiter_ = on_set_command_limiter;
430 template <
typename T>
433 if constexpr (std::is_same_v<T, double>)
435 return set_value(on_set_command_limiter_(value, is_command_limited_));
443 const bool & is_limited()
const {
return is_command_limited_; }
445 void registerIntrospection()
const
447 if (value_ptr_ || std::holds_alternative<double>(value_))
449 std::function<double()> f = [
this]()
450 {
return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
451 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name(), f);
452 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
453 "command_interface." + get_name() +
".is_limited", &is_command_limited_);
457 void unregisterIntrospection()
const
459 if (value_ptr_ || std::holds_alternative<double>(value_))
461 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name());
462 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
463 "command_interface." + get_name() +
".is_limited");
468#pragma GCC diagnostic push
469#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
470 using Handle::Handle;
471#pragma GCC diagnostic pop
473 using SharedPtr = std::shared_ptr<CommandInterface>;
476 bool is_command_limited_ =
false;
477 std::function<double(
double,
bool &)> on_set_command_limiter_ =
478 [](
double value,
bool & is_limited)