57 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
59 const std::string & prefix_name,
const std::string & interface_name,
60 double * value_ptr =
nullptr)
61 : prefix_name_(prefix_name),
62 interface_name_(interface_name),
63 handle_name_(prefix_name_ +
"/" + interface_name_),
69 : prefix_name_(interface_description.get_prefix_name()),
70 interface_name_(interface_description.get_interface_name()),
71 handle_name_(interface_description.get_name())
73 data_type_ = interface_description.get_data_type();
76 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
78 value_ = std::numeric_limits<double>::quiet_NaN();
79 value_ptr_ = std::get_if<double>(&value_);
81 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
88 throw std::runtime_error(
90 FMT_COMPILE(
"Invalid data type : '{}' for interface : {}"),
95 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
97 explicit Handle(
const std::string & interface_name)
98 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
102 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
104 explicit Handle(
const char * interface_name)
105 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
120 Handle(
Handle && other)
noexcept { swap(*
this, other); }
131 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
133 const std::string & get_name()
const {
return handle_name_; }
135 const std::string & get_interface_name()
const {
return interface_name_; }
138 "Replaced by get_name method, which is semantically more correct")]]
const std::string &
139 get_full_name()
const
144 const std::string & get_prefix_name()
const {
return prefix_name_; }
147 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
148 "removed by the ROS 2 Kilted Kaiju release.")]]
149 double get_value()
const
151 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
152 if (!lock.owns_lock())
154 return std::numeric_limits<double>::quiet_NaN();
158 THROW_ON_NULLPTR(value_ptr_);
173 template <
typename T =
double>
176 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
177 return get_optional<T>(lock);
190 template <
typename T =
double>
191 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
193 if (!lock.owns_lock())
199 if constexpr (std::is_same_v<T, double>)
202 THROW_ON_NULLPTR(value_ptr_);
207 return std::get<T>(value_);
209 catch (
const std::bad_variant_access & err)
211 throw std::runtime_error(
213 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
214 get_type_name<T>(), get_name(), data_type_.to_string()));
230 template <
typename T>
232 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
233 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]]
bool
236 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
237 if (!lock.owns_lock())
243 if constexpr (std::is_same_v<T, double>)
246 THROW_ON_NULLPTR(value_ptr_);
253 value = std::get<T>(value_);
255 catch (
const std::bad_variant_access & err)
257 throw std::runtime_error(
259 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
260 get_type_name<T>(), get_name(), data_type_.to_string()));
278 template <
typename T>
281 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
297 template <
typename T>
298 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
300 if (!lock.owns_lock())
306 if constexpr (std::is_same_v<T, double>)
309 THROW_ON_NULLPTR(value_ptr_);
314 if (!std::holds_alternative<T>(value_))
316 throw std::runtime_error(
318 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
319 get_type_name<T>(), get_name(), data_type_.to_string()));
327 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
329 HandleDataType get_data_type()
const {
return data_type_; }
332 void copy(
const Handle & other)
noexcept
334 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
335 prefix_name_ = other.prefix_name_;
336 interface_name_ = other.interface_name_;
337 handle_name_ = other.handle_name_;
338 value_ = other.value_;
339 if (std::holds_alternative<std::monostate>(value_))
341 value_ptr_ = other.value_ptr_;
345 value_ptr_ = std::get_if<double>(&value_);
349 void swap(Handle & first, Handle & second)
noexcept
351 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
352 std::swap(first.prefix_name_, second.prefix_name_);
353 std::swap(first.interface_name_, second.interface_name_);
354 std::swap(first.handle_name_, second.handle_name_);
355 std::swap(first.value_, second.value_);
356 std::swap(first.value_ptr_, second.value_ptr_);
360 std::string prefix_name_;
361 std::string interface_name_;
362 std::string handle_name_;
363 HANDLE_DATATYPE value_ = std::monostate{};
364 HandleDataType data_type_ = HandleDataType::DOUBLE;
369 mutable std::shared_mutex handle_mutex_;
376 :
Handle(interface_description)
380 void registerIntrospection()
const
382 if (value_ptr_ || std::holds_alternative<double>(value_))
384 std::function<double()> f = [
this]()
385 {
return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
386 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
"state_interface." + get_name(), f);
390 void unregisterIntrospection()
const
392 if (value_ptr_ || std::holds_alternative<double>(value_))
394 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"state_interface." + get_name());
403#pragma GCC diagnostic push
404#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
405 using Handle::Handle;
406#pragma GCC diagnostic pop
408 using SharedPtr = std::shared_ptr<StateInterface>;
409 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
416 :
Handle(interface_description)
429 void set_on_set_command_limiter(std::function<
double(
double,
bool &)> on_set_command_limiter)
431 on_set_command_limiter_ = on_set_command_limiter;
439 template <
typename T>
442 if constexpr (std::is_same_v<T, double>)
444 return set_value(on_set_command_limiter_(value, is_command_limited_));
452 const bool & is_limited()
const {
return is_command_limited_; }
454 void registerIntrospection()
const
456 if (value_ptr_ || std::holds_alternative<double>(value_))
458 std::function<double()> f = [
this]()
459 {
return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
460 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name(), f);
461 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
462 "command_interface." + get_name() +
".is_limited", &is_command_limited_);
466 void unregisterIntrospection()
const
468 if (value_ptr_ || std::holds_alternative<double>(value_))
470 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name());
471 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
472 "command_interface." + get_name() +
".is_limited");
477#pragma GCC diagnostic push
478#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
479 using Handle::Handle;
480#pragma GCC diagnostic pop
482 using SharedPtr = std::shared_ptr<CommandInterface>;
485 bool is_command_limited_ =
false;
486 std::function<double(
double,
bool &)> on_set_command_limiter_ =
487 [](
double value,
bool & is_limited)