55 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
58 const std::string & prefix_name,
const std::string & interface_name,
59 double * value_ptr =
nullptr)
60 : prefix_name_(prefix_name),
61 interface_name_(interface_name),
62 handle_name_(prefix_name_ +
"/" + interface_name_),
68 : prefix_name_(interface_description.get_prefix_name()),
69 interface_name_(interface_description.get_interface_name()),
70 handle_name_(interface_description.get_name())
72 data_type_ = interface_description.get_data_type();
75 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
77 value_ = std::numeric_limits<double>::quiet_NaN();
78 value_ptr_ = std::get_if<double>(&value_);
80 else if (data_type_ == hardware_interface::HandleDataType::BOOL)
87 throw std::runtime_error(
89 "' for interface : " + interface_description.get_name());
93 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
95 explicit Handle(
const std::string & interface_name)
96 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
100 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
102 explicit Handle(
const char * interface_name)
103 : interface_name_(interface_name), handle_name_(
"/" + interface_name_), value_ptr_(
nullptr)
118 Handle(
Handle && other)
noexcept { swap(*
this, other); }
129 inline operator bool()
const {
return value_ptr_ !=
nullptr; }
131 const std::string & get_name()
const {
return handle_name_; }
133 const std::string & get_interface_name()
const {
return interface_name_; }
136 "Replaced by get_name method, which is semantically more correct")]]
const std::string &
137 get_full_name()
const
142 const std::string & get_prefix_name()
const {
return prefix_name_; }
145 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
146 "removed by the ROS 2 Kilted Kaiju release.")]]
147 double get_value()
const
149 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
150 if (!lock.owns_lock())
152 return std::numeric_limits<double>::quiet_NaN();
156 THROW_ON_NULLPTR(value_ptr_);
171 template <
typename T =
double>
174 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
175 return get_optional<T>(lock);
188 template <
typename T =
double>
189 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
191 if (!lock.owns_lock())
197 if constexpr (std::is_same_v<T, double>)
200 THROW_ON_NULLPTR(value_ptr_);
205 return std::get<T>(value_);
207 catch (
const std::bad_variant_access & err)
209 throw std::runtime_error(
210 "Invalid data type : '" + get_type_name<T>() +
"' access for interface : " + get_name() +
211 " expected : '" + data_type_.to_string() +
"'");
189 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const {
…}
227 template <
typename T>
229 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
230 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]]
bool
233 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
234 if (!lock.owns_lock())
240 if constexpr (std::is_same_v<T, double>)
243 THROW_ON_NULLPTR(value_ptr_);
250 value = std::get<T>(value_);
252 catch (
const std::bad_variant_access & err)
254 throw std::runtime_error(
255 "Invalid data type : '" + get_type_name<T>() +
"' access for interface : " + get_name() +
256 " expected : '" + data_type_.to_string() +
"'");
274 template <
typename T>
277 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
293 template <
typename T>
294 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
296 if (!lock.owns_lock())
302 if constexpr (std::is_same_v<T, double>)
305 THROW_ON_NULLPTR(value_ptr_);
310 if (!std::holds_alternative<T>(value_))
312 throw std::runtime_error(
313 "Invalid data type : '" + get_type_name<T>() +
"' access for interface : " + get_name() +
314 " expected : '" + data_type_.to_string() +
"'");
294 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value) {
…}
322 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
324 HandleDataType get_data_type()
const {
return data_type_; }
327 void copy(
const Handle & other)
noexcept
329 std::scoped_lock lock(other.handle_mutex_, handle_mutex_);
330 prefix_name_ = other.prefix_name_;
331 interface_name_ = other.interface_name_;
332 handle_name_ = other.handle_name_;
333 value_ = other.value_;
334 if (std::holds_alternative<std::monostate>(value_))
336 value_ptr_ = other.value_ptr_;
340 value_ptr_ = std::get_if<double>(&value_);
344 void swap(Handle & first, Handle & second)
noexcept
346 std::scoped_lock lock(first.handle_mutex_, second.handle_mutex_);
347 std::swap(first.prefix_name_, second.prefix_name_);
348 std::swap(first.interface_name_, second.interface_name_);
349 std::swap(first.handle_name_, second.handle_name_);
350 std::swap(first.value_, second.value_);
351 std::swap(first.value_ptr_, second.value_ptr_);
355 std::string prefix_name_;
356 std::string interface_name_;
357 std::string handle_name_;
358 HANDLE_DATATYPE value_ = std::monostate{};
359 HandleDataType data_type_ = HandleDataType::DOUBLE;
364 mutable std::shared_mutex handle_mutex_;
371 :
Handle(interface_description)
375 void registerIntrospection()
const
377 if (value_ptr_ || std::holds_alternative<double>(value_))
379 std::function<double()> f = [
this]()
380 {
return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
381 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
"state_interface." + get_name(), f);
385 void unregisterIntrospection()
const
387 if (value_ptr_ || std::holds_alternative<double>(value_))
389 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"state_interface." + get_name());
397 using Handle::Handle;
399 using SharedPtr = std::shared_ptr<StateInterface>;
400 using ConstSharedPtr = std::shared_ptr<const StateInterface>;
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");
467 using Handle::Handle;
469 using SharedPtr = std::shared_ptr<CommandInterface>;
472 bool is_command_limited_ =
false;
473 std::function<double(
double,
bool &)> on_set_command_limiter_ =
474 [](
double value,
bool & is_limited)