Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 23 additions & 10 deletions hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <mutex>
#include <optional>
#include <shared_mutex>
#include <stdexcept>
#include <string>
#include <utility>
#include <variant>
Expand Down Expand Up @@ -97,8 +98,7 @@ class Handle
{
throw std::invalid_argument(
fmt::format(
FMT_COMPILE(
"Invalid initial value : '{}' parsed for interface : '{}' with type : '{}'"),
FMT_COMPILE("Invalid initial value: '{}' parsed for interface: '{}' with type: '{}'"),
initial_value, handle_name_, data_type_.to_string()));
}
}
Expand All @@ -112,7 +112,7 @@ class Handle
throw std::runtime_error(
fmt::format(
FMT_COMPILE(
"Invalid data type : '{}' for interface : {}. Supported types are double and bool."),
"Invalid data type: '{}' for interface: {}. Supported types are double and bool."),
data_type, handle_name_));
}
}
Expand Down Expand Up @@ -213,15 +213,22 @@ class Handle
THROW_ON_NULLPTR(value_ptr_);
return *value_ptr_;
case HandleDataType::BOOL:
RCLCPP_WARN_ONCE(
rclcpp::get_logger(get_name()),
"Casting bool to double for interface : %s. Better use get_optional<bool>().",
get_name().c_str());
// TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once
// https://github.com/ros2/rclcpp/issues/2587
// is fixed
if (!notified_)
{
RCLCPP_WARN(
rclcpp::get_logger(get_name()),
"Casting bool to double for interface: %s. Better use get_optional<bool>().",
get_name().c_str());
notified_ = true;
}
return static_cast<double>(std::get<bool>(value_));
default:
throw std::runtime_error(
fmt::format(
FMT_COMPILE("Data type : '{}' cannot be casted to double for interface : {}"),
FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"),
data_type_.to_string(), get_name()));
}
}
Expand All @@ -233,7 +240,7 @@ class Handle
{
throw std::runtime_error(
fmt::format(
FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
get_type_name<T>(), get_name(), data_type_.to_string()));
}
// END
Expand Down Expand Up @@ -290,7 +297,7 @@ class Handle
{
throw std::runtime_error(
fmt::format(
FMT_COMPILE("Invalid data type : '{}' access for interface : {} expected : '{}'"),
FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"),
get_type_name<T>(), get_name(), data_type_.to_string()));
}
value_ = value;
Expand Down Expand Up @@ -345,6 +352,12 @@ class Handle
double * value_ptr_;
// END
mutable std::shared_mutex handle_mutex_;

private:
// TODO(christophfroehlich): remove once
// https://github.com/ros2/rclcpp/issues/2587
// is fixed
mutable bool notified_ = false;
};

class StateInterface : public Handle
Expand Down
8 changes: 8 additions & 0 deletions hardware_interface/test/test_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,14 @@ TEST(TestHandle, interface_description_bool_data_type)
ASSERT_FALSE(handle.get_optional<bool>().value());
ASSERT_EQ(handle.get_optional(), 0.0);

info.name = "some_interface";
interface_descr = InterfaceDescription(itf_name, info);
StateInterface handle2{interface_descr};
EXPECT_EQ(handle2.get_name(), itf_name + "/" + "some_interface");
ASSERT_TRUE(handle2.set_value(false));
ASSERT_FALSE(handle2.get_optional<bool>().value());
ASSERT_EQ(handle2.get_optional(), 0.0);

// Test the assertions
ASSERT_THROW({ std::ignore = handle.set_value(-1.0); }, std::runtime_error);
ASSERT_THROW({ std::ignore = handle.set_value(0.0); }, std::runtime_error);
Expand Down
Loading