Skip to content

Commit 26cb421

Browse files
committed
Add conditioning to skip registering invalid cases
1 parent 65b7e0b commit 26cb421

File tree

1 file changed

+26
-3
lines changed
  • hardware_interface/include/hardware_interface

1 file changed

+26
-3
lines changed

hardware_interface/include/hardware_interface/handle.hpp

Lines changed: 26 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -310,6 +310,11 @@ class Handle
310310
/// Returns true if the handle data type can be casted to double.
311311
bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
312312

313+
bool is_valid() const
314+
{
315+
return (value_ptr_ != nullptr) || !std::holds_alternative<std::monostate>(value_);
316+
}
317+
313318
private:
314319
void copy(const Handle & other) noexcept
315320
{
@@ -346,7 +351,7 @@ class Handle
346351
HandleDataType data_type_ = HandleDataType::DOUBLE;
347352
// BEGIN (Handle export change): for backward compatibility
348353
// TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
349-
double * value_ptr_;
354+
double * value_ptr_ = nullptr;
350355
// END
351356
mutable std::shared_mutex handle_mutex_;
352357

@@ -367,6 +372,15 @@ class StateInterface : public Handle
367372

368373
void registerIntrospection() const
369374
{
375+
if (!is_valid())
376+
{
377+
RCLCPP_WARN(
378+
rclcpp::get_logger(get_name()),
379+
"Cannot register state introspection for state interface: %s without a valid value "
380+
"pointer or initialized value.",
381+
get_name().c_str());
382+
return;
383+
}
370384
if (value_ptr_ || data_type_.is_castable_to_double())
371385
{
372386
std::function<double()> f = [this]()
@@ -386,7 +400,7 @@ class StateInterface : public Handle
386400

387401
void unregisterIntrospection() const
388402
{
389-
if (value_ptr_ || data_type_.is_castable_to_double())
403+
if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
390404
{
391405
DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
392406
}
@@ -450,6 +464,15 @@ class CommandInterface : public Handle
450464

451465
void registerIntrospection() const
452466
{
467+
if (!is_valid())
468+
{
469+
RCLCPP_WARN(
470+
rclcpp::get_logger(get_name()),
471+
"Cannot register command introspection for command interface: %s without a valid value "
472+
"pointer or initialized value.",
473+
get_name().c_str());
474+
return;
475+
}
453476
if (value_ptr_ || data_type_.is_castable_to_double())
454477
{
455478
std::function<double()> f = [this]()
@@ -471,7 +494,7 @@ class CommandInterface : public Handle
471494

472495
void unregisterIntrospection() const
473496
{
474-
if (value_ptr_ || data_type_.is_castable_to_double())
497+
if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
475498
{
476499
DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
477500
DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(

0 commit comments

Comments
 (0)