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(
99 "Invalid initial value : '{}' parsed for interface : '{}' with type : '{}'"),
100 initial_value, handle_name_, data_type_.to_string()));
103 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
105 value_ptr_ =
nullptr;
106 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
110 throw std::runtime_error(
113 "Invalid data type : '{}' for interface : {}. Supported types are double and bool."),
114 data_type, handle_name_));
120 interface_description.get_prefix_name(), interface_description.get_interface_name(),
121 interface_description.get_data_type_string(),
126 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
128 explicit Handle(
const std::string & interface_name)
129 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
133 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
135 explicit Handle(
const char * interface_name)
136 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
151 Handle(
Handle && other)
noexcept { swap(*
this, other); }
162 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
164 const std::string & get_name()
const {
return handle_name_; }
166 const std::string & get_interface_name()
const {
return interface_name_; }
169 "Replaced by get_name method, which is semantically more correct")]]
const std::string &
170 get_full_name()
const
175 const std::string & get_prefix_name()
const {
return prefix_name_; }
178 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
179 "removed by the ROS 2 Kilted Kaiju release.")]]
180 double get_value()
const
182 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
183 if (!lock.owns_lock())
185 return std::numeric_limits<double>::quiet_NaN();
189 THROW_ON_NULLPTR(value_ptr_);
204 template <
typename T =
double>
207 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
208 return get_optional<T>(lock);
221 template <
typename T =
double>
222 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
224 if (!lock.owns_lock())
230 if constexpr (std::is_same_v<T, double>)
233 THROW_ON_NULLPTR(value_ptr_);
238 return std::get<T>(value_);
240 catch (
const std::bad_variant_access & err)
242 throw std::runtime_error(
244 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
245 get_type_name<T>(), get_name(), data_type_.to_string()));
261 template <
typename T>
263 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
264 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]]
bool
267 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
268 if (!lock.owns_lock())
274 if constexpr (std::is_same_v<T, double>)
277 THROW_ON_NULLPTR(value_ptr_);
284 value = std::get<T>(value_);
286 catch (
const std::bad_variant_access & err)
288 throw std::runtime_error(
290 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
291 get_type_name<T>(), get_name(), data_type_.to_string()));
309 template <
typename T>
312 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
328 template <
typename T>
329 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
331 if (!lock.owns_lock())
337 if constexpr (std::is_same_v<T, double>)
340 THROW_ON_NULLPTR(value_ptr_);
345 if (!std::holds_alternative<T>(value_))
347 throw std::runtime_error(
349 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
350 get_type_name<T>(), get_name(), data_type_.to_string()));
358 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
360 HandleDataType get_data_type()
const {
return data_type_; }
363 void copy(
const Handle & other)
noexcept
365 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
366 prefix_name_ = other.prefix_name_;
367 interface_name_ = other.interface_name_;
368 handle_name_ = other.handle_name_;
369 value_ = other.value_;
370 if (std::holds_alternative<std::monostate>(value_))
372 value_ptr_ = other.value_ptr_;
376 value_ptr_ = std::get_if<double>(&value_);
380 void swap(Handle & first, Handle & second)
noexcept
382 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
383 std::swap(first.prefix_name_, second.prefix_name_);
384 std::swap(first.interface_name_, second.interface_name_);
385 std::swap(first.handle_name_, second.handle_name_);
386 std::swap(first.value_, second.value_);
387 std::swap(first.value_ptr_, second.value_ptr_);
391 std::string prefix_name_;
392 std::string interface_name_;
393 std::string handle_name_;
394 HANDLE_DATATYPE value_ = std::monostate{};
395 HandleDataType data_type_ = HandleDataType::DOUBLE;
400 mutable std::shared_mutex handle_mutex_;
447 :
Handle(interface_description)
460 void set_on_set_command_limiter(std::function<
double(
double,
bool &)> on_set_command_limiter)
462 on_set_command_limiter_ = on_set_command_limiter;
470 template <
typename T>
473 if constexpr (std::is_same_v<T, double>)
475 return set_value(on_set_command_limiter_(value, is_command_limited_));
483 const bool & is_limited()
const {
return is_command_limited_; }
485 void registerIntrospection()
const
487 if (value_ptr_ || std::holds_alternative<double>(value_))
489 std::function<double()> f = [
this]()
490 {
return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
491 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name(), f);
492 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
493 "command_interface." + get_name() +
".is_limited", &is_command_limited_);
497 void unregisterIntrospection()
const
499 if (value_ptr_ || std::holds_alternative<double>(value_))
501 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name());
502 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
503 "command_interface." + get_name() +
".is_limited");
508#pragma GCC diagnostic push
509#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
510 using Handle::Handle;
511#pragma GCC diagnostic pop
513 using SharedPtr = std::shared_ptr<CommandInterface>;
516 bool is_command_limited_ =
false;
517 std::function<double(
double,
bool &)> on_set_command_limiter_ =
518 [](
double value,
bool & is_limited)