Skip to content

Commit 54d5e8e

Browse files
christophfroehlichmergify[bot]
authored andcommitted
Publish all castable data types to pal_statistics (#2633)
(cherry picked from commit fd12e90) # Conflicts: # hardware_interface/include/hardware_interface/handle.hpp # hardware_interface/include/hardware_interface/hardware_info.hpp
1 parent 1f75c84 commit 54d5e8e

File tree

4 files changed

+151
-11
lines changed

4 files changed

+151
-11
lines changed

hardware_interface/include/hardware_interface/handle.hpp

Lines changed: 54 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,6 @@
2727
#include <shared_mutex>
2828
#include <string>
2929
#include <utility>
30-
#include <variant>
3130

3231
#include "hardware_interface/hardware_info.hpp"
3332
#include "hardware_interface/introspection.hpp"
@@ -58,8 +57,6 @@ std::string get_type_name()
5857
namespace hardware_interface
5958
{
6059

61-
using HANDLE_DATATYPE = std::variant<std::monostate, double, bool>;
62-
6360
/// A handle used to get and set a value on a given interface.
6461
class Handle
6562
{
@@ -359,6 +356,17 @@ class Handle
359356

360357
HandleDataType get_data_type() const { return data_type_; }
361358

359+
<<<<<<< HEAD
360+
=======
361+
/// Returns true if the handle data type can be casted to double.
362+
bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
363+
364+
bool is_valid() const
365+
{
366+
return (value_ptr_ != nullptr) || !std::holds_alternative<std::monostate>(value_);
367+
}
368+
369+
>>>>>>> fd12e90 (Publish all castable data types to pal_statistics (#2633))
362370
private:
363371
void copy(const Handle & other) noexcept
364372
{
@@ -395,7 +403,7 @@ class Handle
395403
HandleDataType data_type_ = HandleDataType::DOUBLE;
396404
// BEGIN (Handle export change): for backward compatibility
397405
// TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
398-
double * value_ptr_;
406+
double * value_ptr_ = nullptr;
399407
// END
400408
mutable std::shared_mutex handle_mutex_;
401409
};
@@ -410,17 +418,35 @@ class StateInterface : public Handle
410418

411419
void registerIntrospection() const
412420
{
413-
if (value_ptr_ || std::holds_alternative<double>(value_))
421+
if (!is_valid())
422+
{
423+
RCLCPP_WARN(
424+
rclcpp::get_logger(get_name()),
425+
"Cannot register state introspection for state interface: %s without a valid value "
426+
"pointer or initialized value.",
427+
get_name().c_str());
428+
return;
429+
}
430+
if (value_ptr_ || data_type_.is_castable_to_double())
414431
{
415432
std::function<double()> f = [this]()
416-
{ return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
433+
{
434+
if (value_ptr_)
435+
{
436+
return *value_ptr_;
437+
}
438+
else
439+
{
440+
return data_type_.cast_to_double(value_);
441+
}
442+
};
417443
DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name(), f);
418444
}
419445
}
420446

421447
void unregisterIntrospection() const
422448
{
423-
if (value_ptr_ || std::holds_alternative<double>(value_))
449+
if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
424450
{
425451
DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("state_interface." + get_name());
426452
}
@@ -484,10 +510,28 @@ class CommandInterface : public Handle
484510

485511
void registerIntrospection() const
486512
{
487-
if (value_ptr_ || std::holds_alternative<double>(value_))
513+
if (!is_valid())
514+
{
515+
RCLCPP_WARN(
516+
rclcpp::get_logger(get_name()),
517+
"Cannot register command introspection for command interface: %s without a valid value "
518+
"pointer or initialized value.",
519+
get_name().c_str());
520+
return;
521+
}
522+
if (value_ptr_ || data_type_.is_castable_to_double())
488523
{
489524
std::function<double()> f = [this]()
490-
{ return value_ptr_ ? *value_ptr_ : std::get<double>(value_); };
525+
{
526+
if (value_ptr_)
527+
{
528+
return *value_ptr_;
529+
}
530+
else
531+
{
532+
return data_type_.cast_to_double(value_);
533+
}
534+
};
491535
DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name(), f);
492536
DEFAULT_REGISTER_ROS2_CONTROL_INTROSPECTION(
493537
"command_interface." + get_name() + ".is_limited", &is_command_limited_);
@@ -496,7 +540,7 @@ class CommandInterface : public Handle
496540

497541
void unregisterIntrospection() const
498542
{
499-
if (value_ptr_ || std::holds_alternative<double>(value_))
543+
if (is_valid() && (value_ptr_ || data_type_.is_castable_to_double()))
500544
{
501545
DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION("command_interface." + get_name());
502546
DEFAULT_UNREGISTER_ROS2_CONTROL_INTROSPECTION(

hardware_interface/include/hardware_interface/hardware_info.hpp

Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,11 @@
1515
#ifndef HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
1616
#define HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
1717

18+
#include <fmt/compile.h>
19+
1820
#include <string>
1921
#include <unordered_map>
22+
#include <variant>
2023
#include <vector>
2124

2225
#include "joint_limits/joint_limits.hpp"
@@ -133,6 +136,8 @@ struct TransmissionInfo
133136
/**
134137
* Hardware handles supported types
135138
*/
139+
140+
using HANDLE_DATATYPE = std::variant<std::monostate, double, bool>;
136141
class HandleDataType
137142
{
138143
public:
@@ -184,6 +189,48 @@ class HandleDataType
184189
}
185190
}
186191

192+
<<<<<<< HEAD
193+
=======
194+
/**
195+
* @brief Check if the HandleDataType can be casted to double.
196+
* @return True if the HandleDataType can be casted to double, false otherwise.
197+
* @note Once we add support for more data types, this function should be updated
198+
*/
199+
bool is_castable_to_double() const
200+
{
201+
switch (value_)
202+
{
203+
case DOUBLE:
204+
return true;
205+
case BOOL:
206+
return true; // bool can be converted to double
207+
default:
208+
return false; // unknown type cannot be converted
209+
}
210+
}
211+
212+
/**
213+
* @brief Cast the given value to double.
214+
* @param value The value to be casted.
215+
* @return The casted value.
216+
* @throw std::runtime_error if the HandleDataType cannot be casted to double.
217+
* @note Once we add support for more data types, this function should be updated
218+
*/
219+
double cast_to_double(const HANDLE_DATATYPE & value) const
220+
{
221+
switch (value_)
222+
{
223+
case DOUBLE:
224+
return std::get<double>(value);
225+
case BOOL:
226+
return static_cast<double>(std::get<bool>(value));
227+
default:
228+
throw std::runtime_error(
229+
fmt::format(FMT_COMPILE("Data type : '{}' cannot be casted to double."), to_string()));
230+
}
231+
}
232+
233+
>>>>>>> fd12e90 (Publish all castable data types to pal_statistics (#2633))
187234
HandleDataType from_string(const std::string & data_type) { return HandleDataType(data_type); }
188235

189236
private:

hardware_interface/test/test_handle.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -416,3 +416,51 @@ TEST(TestHandle, move_assignment)
416416
EXPECT_DOUBLE_EQ(moved.get_optional().value(), 0.0);
417417
}
418418
#pragma GCC diagnostic pop
419+
420+
class TestableHandle : public hardware_interface::Handle
421+
{
422+
FRIEND_TEST(TestHandle, handle_castable);
423+
// Use generation of interface names
424+
explicit TestableHandle(const InterfaceDescription & interface_description)
425+
: hardware_interface::Handle(interface_description)
426+
{
427+
}
428+
};
429+
430+
TEST(TestHandle, handle_castable)
431+
{
432+
hardware_interface::InterfaceInfo info;
433+
info.name = "position";
434+
const std::string JOINT_NAME_1 = "joint1";
435+
{
436+
info.data_type = "double";
437+
info.initial_value = "23.0";
438+
hardware_interface::InterfaceDescription interface_description{JOINT_NAME_1, info};
439+
TestableHandle handle{interface_description};
440+
441+
EXPECT_TRUE(handle.is_valid());
442+
EXPECT_TRUE(handle.is_castable_to_double());
443+
EXPECT_EQ(handle.data_type_.cast_to_double(handle.value_), 23.0);
444+
}
445+
{
446+
info.data_type = "bool";
447+
info.initial_value = "false";
448+
hardware_interface::InterfaceDescription interface_description{JOINT_NAME_1, info};
449+
TestableHandle handle{interface_description};
450+
451+
EXPECT_TRUE(handle.is_valid());
452+
EXPECT_TRUE(handle.is_castable_to_double());
453+
EXPECT_EQ(handle.data_type_.cast_to_double(handle.value_), 0.0);
454+
455+
handle.value_ = true;
456+
EXPECT_EQ(handle.data_type_.cast_to_double(handle.value_), 1.0);
457+
}
458+
{
459+
// handle with unsupported datatype can't be created right now
460+
// extend with more datatypes once supported in Handle
461+
hardware_interface::HandleDataType dt{"string"};
462+
EXPECT_FALSE(dt.is_castable_to_double());
463+
hardware_interface::HANDLE_DATATYPE value = std::monostate{};
464+
EXPECT_THROW(dt.cast_to_double(value), std::runtime_error);
465+
}
466+
}

hardware_interface_testing/test/test_components/test_actuator.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ class TestActuator : public ActuatorInterface
7575
&velocity_state_));
7676
state_interfaces.emplace_back(
7777
hardware_interface::StateInterface(
78-
get_hardware_info().joints[0].name, "some_unlisted_interface", nullptr));
78+
get_hardware_info().joints[0].name, "some_unlisted_interface", &unlisted_interface_));
7979

8080
return state_interfaces;
8181
}
@@ -187,6 +187,7 @@ class TestActuator : public ActuatorInterface
187187
double velocity_state_ = 0.0;
188188
double velocity_command_ = 0.0;
189189
double max_velocity_command_ = 0.0;
190+
double unlisted_interface_ = std::numeric_limits<double>::quiet_NaN();
190191
};
191192

192193
class TestUninitializableActuator : public TestActuator

0 commit comments

Comments
 (0)