69 [[deprecated(
"Use InterfaceDescription for initializing the Interface")]]
70 Handle(
const std::string & prefix_name,
const std::string & interface_name,
double * value_ptr)
71 : prefix_name_(prefix_name),
72 interface_name_(interface_name),
73 handle_name_(prefix_name_ +
"/" + interface_name_),
79 const std::string & prefix_name,
const std::string & interface_name,
80 const std::string & data_type =
"double",
const std::string & initial_value =
"")
81 : prefix_name_(prefix_name),
82 interface_name_(interface_name),
83 handle_name_(prefix_name_ +
"/" + interface_name_),
88 if (data_type_ == hardware_interface::HandleDataType::DOUBLE)
92 value_ = initial_value.empty() ? std::numeric_limits<double>::quiet_NaN()
94 value_ptr_ = std::get_if<double>(&value_);
96 catch (
const std::invalid_argument & err)
98 throw std::invalid_argument(
101 "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;
108 value_ = initial_value.empty() ? false : hardware_interface::parse_bool(initial_value);
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_; }
173 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
174 "removed by the ROS 2 Kilted Kaiju release.")]]
175 double get_value()
const
177 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
178 if (!lock.owns_lock())
180 return std::numeric_limits<double>::quiet_NaN();
184 THROW_ON_NULLPTR(value_ptr_);
199 template <
typename T =
double>
202 std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
203 return get_optional<T>(lock);
216 template <
typename T =
double>
217 [[nodiscard]] std::optional<T>
get_optional(std::shared_lock<std::shared_mutex> & lock)
const
219 if (!lock.owns_lock())
225 if constexpr (std::is_same_v<T, double>)
229 case HandleDataType::DOUBLE:
230 THROW_ON_NULLPTR(value_ptr_);
232 case HandleDataType::BOOL:
234 rclcpp::get_logger(get_name()),
235 "Casting bool to double for interface : %s. Better use get_optional<bool>().",
237 return static_cast<double>(std::get<bool>(value_));
239 throw std::runtime_error(
241 FMT_COMPILE(
"Data type : '{}' cannot be casted to double for interface : {}"),
242 data_type_.to_string(), get_name()));
247 return std::get<T>(value_);
249 catch (
const std::bad_variant_access & err)
251 throw std::runtime_error(
253 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
254 get_type_name<T>(), get_name(), data_type_.to_string()));
270 template <
typename T>
273 std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
289 template <
typename T>
290 [[nodiscard]]
bool set_value(std::unique_lock<std::shared_mutex> & lock,
const T & value)
292 if (!lock.owns_lock())
298 if constexpr (std::is_same_v<T, double>)
301 THROW_ON_NULLPTR(value_ptr_);
306 if (!std::holds_alternative<T>(value_))
308 throw std::runtime_error(
310 FMT_COMPILE(
"Invalid data type : '{}' access for interface : {} expected : '{}'"),
311 get_type_name<T>(), get_name(), data_type_.to_string()));
319 std::shared_mutex & get_mutex()
const {
return handle_mutex_; }
321 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_;
411 :
Handle(interface_description)
424 void set_on_set_command_limiter(std::function<
double(
double,
bool &)> on_set_command_limiter)
426 on_set_command_limiter_ = on_set_command_limiter;
434 template <
typename T>
437 if constexpr (std::is_same_v<T, double>)
439 return set_value(on_set_command_limiter_(value, is_command_limited_));
447 const bool & is_limited()
const {
return is_command_limited_; }
449 void registerIntrospection()
const
451 if (value_ptr_ || std::holds_alternative<double>(value_))
453 std::function<double()> f = [
this]()
454 {
return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
455 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name(), f);
456 DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
457 "command_interface." + get_name() +
".is_limited", &is_command_limited_);
461 void unregisterIntrospection()
const
463 if (value_ptr_ || std::holds_alternative<double>(value_))
465 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
"command_interface." + get_name());
466 DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(
467 "command_interface." + get_name() +
".is_limited");
472#pragma GCC diagnostic push
473#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
474 using Handle::Handle;
475#pragma GCC diagnostic pop
477 using SharedPtr = std::shared_ptr<CommandInterface>;
480 bool is_command_limited_ =
false;
481 std::function<double(
double,
bool &)> on_set_command_limiter_ =
482 [](
double value,
bool & is_limited)