Skip to content

Commit 9371d59

Browse files
authored
add changes to cast the other data types to double (#2360)
1 parent d376254 commit 9371d59

File tree

5 files changed

+56
-5
lines changed

5 files changed

+56
-5
lines changed

hardware_interface/include/hardware_interface/handle.hpp

Lines changed: 22 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@
3434
#include "hardware_interface/lexical_casts.hpp"
3535
#include "hardware_interface/macros.hpp"
3636

37+
#include "rclcpp/logging.hpp"
38+
3739
namespace
3840
{
3941
#ifndef _WIN32
@@ -222,9 +224,23 @@ class Handle
222224
// TODO(saikishor) return value_ if old functionality is removed
223225
if constexpr (std::is_same_v<T, double>)
224226
{
225-
// If the template is of type double, check if the value_ptr_ is not nullptr
226-
THROW_ON_NULLPTR(value_ptr_);
227-
return *value_ptr_;
227+
switch (data_type_)
228+
{
229+
case HandleDataType::DOUBLE:
230+
THROW_ON_NULLPTR(value_ptr_);
231+
return *value_ptr_;
232+
case HandleDataType::BOOL:
233+
RCLCPP_WARN_ONCE(
234+
rclcpp::get_logger(get_name()),
235+
"Casting bool to double for interface : %s. Better use get_optional<bool>().",
236+
get_name().c_str());
237+
return static_cast<double>(std::get<bool>(value_));
238+
default:
239+
throw std::runtime_error(
240+
fmt::format(
241+
FMT_COMPILE("Data type : '{}' cannot be casted to double for interface : {}"),
242+
data_type_.to_string(), get_name()));
243+
}
228244
}
229245
try
230246
{
@@ -304,6 +320,9 @@ class Handle
304320

305321
HandleDataType get_data_type() const { return data_type_; }
306322

323+
/// Returns true if the handle data type can be casted to double.
324+
bool is_castable_to_double() const { return data_type_.is_castable_to_double(); }
325+
307326
private:
308327
void copy(const Handle & other) noexcept
309328
{

hardware_interface/include/hardware_interface/hardware_info.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -184,6 +184,24 @@ class HandleDataType
184184
}
185185
}
186186

187+
/**
188+
* @brief Check if the HandleDataType can be casted to double.
189+
* @return True if the HandleDataType can be casted to double, false otherwise.
190+
* @note Once we add support for more data types, this function should be updated
191+
*/
192+
bool is_castable_to_double() const
193+
{
194+
switch (value_)
195+
{
196+
case DOUBLE:
197+
return true;
198+
case BOOL:
199+
return true; // bool can be converted to double
200+
default:
201+
return false; // unknown type cannot be converted
202+
}
203+
}
204+
187205
HandleDataType from_string(const std::string & data_type) { return HandleDataType(data_type); }
188206

189207
private:

hardware_interface/include/hardware_interface/loaned_command_interface.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,12 @@ class LoanedCommandInterface
178178
*/
179179
HandleDataType get_data_type() const { return command_interface_.get_data_type(); }
180180

181+
/**
182+
* @brief Check if the state interface can be casted to double.
183+
* @return True if the state interface can be casted to double, false otherwise.
184+
*/
185+
bool is_castable_to_double() const { return command_interface_.is_castable_to_double(); }
186+
181187
protected:
182188
CommandInterface & command_interface_;
183189
Deleter deleter_;

hardware_interface/include/hardware_interface/loaned_state_interface.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,12 @@ class LoanedStateInterface
138138
*/
139139
HandleDataType get_data_type() const { return state_interface_.get_data_type(); }
140140

141+
/**
142+
* @brief Check if the state interface can be casted to double.
143+
* @return True if the state interface can be casted to double, false otherwise.
144+
*/
145+
bool is_castable_to_double() const { return state_interface_.is_castable_to_double(); }
146+
141147
protected:
142148
const StateInterface & state_interface_;
143149
Deleter deleter_;

hardware_interface/test/test_handle.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -225,13 +225,14 @@ TEST(TestHandle, interface_description_bool_data_type)
225225
ASSERT_FALSE(handle.get_optional<bool>().value()) << "Default value should be false";
226226
ASSERT_TRUE(handle.set_value(true));
227227
ASSERT_TRUE(handle.get_optional<bool>().value());
228+
ASSERT_EQ(handle.get_optional(), 1.0);
228229
ASSERT_TRUE(handle.set_value(false));
229230
ASSERT_FALSE(handle.get_optional<bool>().value());
231+
ASSERT_EQ(handle.get_optional(), 0.0);
230232

231233
// Test the assertions
232234
ASSERT_THROW({ std::ignore = handle.set_value(-1.0); }, std::runtime_error);
233235
ASSERT_THROW({ std::ignore = handle.set_value(0.0); }, std::runtime_error);
234-
ASSERT_THROW({ std::ignore = handle.get_optional<double>(); }, std::runtime_error);
235236
}
236237

237238
TEST(TestHandle, handle_constructor_double_data_type)
@@ -274,13 +275,14 @@ TEST(TestHandle, handle_constructor_bool_data_type)
274275
<< "Default value should be true as it is initialized";
275276
ASSERT_TRUE(handle.set_value(false));
276277
ASSERT_FALSE(handle.get_optional<bool>().value());
278+
ASSERT_EQ(handle.get_optional(), 0.0);
277279
ASSERT_TRUE(handle.set_value(true));
278280
ASSERT_TRUE(handle.get_optional<bool>().value());
281+
ASSERT_EQ(handle.get_optional(), 1.0);
279282

280283
// Test the assertions
281284
ASSERT_THROW({ std::ignore = handle.set_value(-1.0); }, std::runtime_error);
282285
ASSERT_THROW({ std::ignore = handle.set_value(0.0); }, std::runtime_error);
283-
ASSERT_THROW({ std::ignore = handle.get_optional<double>(); }, std::runtime_error);
284286
}
285287

286288
TEST(TestHandle, interface_description_unknown_data_type)

0 commit comments

Comments
 (0)