Skip to content

Commit

Permalink
Use new get_value API for newly added tests and semantic components (
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Feb 19, 2025
1 parent 9394fd2 commit d126642
Show file tree
Hide file tree
Showing 2 changed files with 62 additions and 50 deletions.
28 changes: 20 additions & 8 deletions controller_interface/include/semantic_components/gps_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,10 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
*
* \return Status
*/
int8_t get_status() const { return static_cast<int8_t>(state_interfaces_[0].get().get_value()); }
int8_t get_status() const
{
return static_cast<int8_t>(state_interfaces_[0].get().template get_value<double>().value());
}

/**
* Return service used by GPS e.g. fix/no_fix
Expand All @@ -68,29 +71,38 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
*/
uint16_t get_service() const
{
return static_cast<uint16_t>(state_interfaces_[1].get().get_value());
return static_cast<uint16_t>(state_interfaces_[1].get().template get_value<double>().value());
}

/**
* Return latitude reported by a GPS
*
* \return Latitude.
*/
double get_latitude() const { return state_interfaces_[2].get().get_value(); }
double get_latitude() const
{
return state_interfaces_[2].get().template get_value<double>().value();
}

/**
* Return longitude reported by a GPS
*
* \return Longitude.
*/
double get_longitude() const { return state_interfaces_[3].get().get_value(); }
double get_longitude() const
{
return state_interfaces_[3].get().template get_value<double>().value();
}

/**
* Return altitude reported by a GPS
*
* \return Altitude.
*/
double get_altitude() const { return state_interfaces_[4].get().get_value(); }
double get_altitude() const
{
return state_interfaces_[4].get().template get_value<double>().value();
}

/**
* Return covariance reported by a GPS.
Expand All @@ -102,9 +114,9 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
const std::array<double, 9> & get_covariance()
{
covariance_[0] = state_interfaces_[5].get().get_value();
covariance_[4] = state_interfaces_[6].get().get_value();
covariance_[8] = state_interfaces_[7].get().get_value();
covariance_[0] = state_interfaces_[5].get().template get_value<double>().value();
covariance_[4] = state_interfaces_[6].get().template get_value<double>().value();
covariance_[8] = state_interfaces_[7].get().template get_value<double>().value();
return covariance_;
}

Expand Down
84 changes: 42 additions & 42 deletions hardware_interface/test/test_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ TEST(TestHandle, command_interface)
ASSERT_TRUE(interface.get_value<double>().has_value());
EXPECT_DOUBLE_EQ(interface.get_value<double>().value(), value);
EXPECT_DOUBLE_EQ(interface.get_value<double>().value(), value);
EXPECT_NO_THROW(bool status = interface.set_value(0.0));
EXPECT_NO_THROW({ interface.set_value(0.0); });
ASSERT_TRUE(interface.get_value<double>().has_value());
EXPECT_DOUBLE_EQ(interface.get_value<double>().value(), 0.0);
}
Expand Down Expand Up @@ -70,7 +70,7 @@ TEST(TestHandle, value_methods_work_on_non_nullptr)
CommandInterface handle{JOINT_NAME, FOO_INTERFACE, &value};
ASSERT_TRUE(handle.get_value<double>().has_value());
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
EXPECT_NO_THROW(bool status_set = handle.set_value(0.0));
EXPECT_NO_THROW({ handle.set_value(0.0); });
ASSERT_TRUE(handle.get_value<double>().has_value());
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), 0.0);
}
Expand Down Expand Up @@ -109,11 +109,11 @@ TEST(TestHandle, copy_constructor)
double value = 1.337;
hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value};
hardware_interface::Handle copy(handle);
EXPECT_DOUBLE_EQ(copy.get_value(), value);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_NO_THROW(copy.set_value(0.0));
EXPECT_DOUBLE_EQ(copy.get_value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value(), 0.0);
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), value);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
EXPECT_NO_THROW({ copy.set_value(0.0); });
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), 0.0);
}
{
double value = 1.337;
Expand All @@ -122,20 +122,20 @@ TEST(TestHandle, copy_constructor)
info.data_type = "double";
InterfaceDescription itf_descr{JOINT_NAME, info};
hardware_interface::Handle handle{itf_descr};
EXPECT_TRUE(std::isnan(handle.get_value()));
handle.set_value(value);
EXPECT_TRUE(std::isnan(handle.get_value<double>().value()));
ASSERT_TRUE(handle.set_value(value));
hardware_interface::Handle copy(handle);
EXPECT_EQ(copy.get_name(), handle.get_name());
EXPECT_EQ(copy.get_interface_name(), handle.get_interface_name());
EXPECT_EQ(copy.get_prefix_name(), handle.get_prefix_name());
EXPECT_DOUBLE_EQ(copy.get_value(), value);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_NO_THROW(copy.set_value(0.0));
EXPECT_DOUBLE_EQ(copy.get_value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_NO_THROW(copy.set_value(0.52));
EXPECT_DOUBLE_EQ(copy.get_value(), 0.52);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), value);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
EXPECT_NO_THROW({ copy.set_value(0.0); });
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
EXPECT_NO_THROW({ copy.set_value(0.52); });
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), 0.52);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
}
}

Expand All @@ -144,9 +144,9 @@ TEST(TesHandle, move_constructor)
double value = 1.337;
hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value};
hardware_interface::Handle moved{std::move(handle)};
EXPECT_DOUBLE_EQ(moved.get_value(), value);
EXPECT_NO_THROW(moved.set_value(0.0));
EXPECT_DOUBLE_EQ(moved.get_value(), 0.0);
EXPECT_DOUBLE_EQ(moved.get_value<double>().value(), value);
EXPECT_NO_THROW({ moved.set_value(0.0); });
EXPECT_DOUBLE_EQ(moved.get_value<double>().value(), 0.0);
}

TEST(TestHandle, copy_assignment)
Expand All @@ -156,14 +156,14 @@ TEST(TestHandle, copy_assignment)
double value_2 = 2.337;
hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value_1};
hardware_interface::Handle copy{JOINT_NAME, "random", &value_2};
EXPECT_DOUBLE_EQ(copy.get_value(), value_2);
EXPECT_DOUBLE_EQ(handle.get_value(), value_1);
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), value_2);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value_1);
copy = handle;
EXPECT_DOUBLE_EQ(copy.get_value(), value_1);
EXPECT_DOUBLE_EQ(handle.get_value(), value_1);
EXPECT_NO_THROW(copy.set_value(0.0));
EXPECT_DOUBLE_EQ(copy.get_value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value(), 0.0);
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), value_1);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value_1);
EXPECT_NO_THROW({ copy.set_value(0.0); });
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), 0.0);
EXPECT_DOUBLE_EQ(value_1, 0.0);
EXPECT_DOUBLE_EQ(value_2, 2.337);
}
Expand All @@ -175,20 +175,20 @@ TEST(TestHandle, copy_assignment)
info.data_type = "double";
InterfaceDescription itf_descr{JOINT_NAME, info};
hardware_interface::Handle handle{itf_descr};
EXPECT_TRUE(std::isnan(handle.get_value()));
handle.set_value(value);
EXPECT_TRUE(std::isnan(handle.get_value<double>().value()));
ASSERT_TRUE(handle.set_value(value));
hardware_interface::Handle copy = handle;
EXPECT_EQ(copy.get_name(), handle.get_name());
EXPECT_EQ(copy.get_interface_name(), handle.get_interface_name());
EXPECT_EQ(copy.get_prefix_name(), handle.get_prefix_name());
EXPECT_DOUBLE_EQ(copy.get_value(), value);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_NO_THROW(copy.set_value(0.0));
EXPECT_DOUBLE_EQ(copy.get_value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_NO_THROW(copy.set_value(0.52));
EXPECT_DOUBLE_EQ(copy.get_value(), 0.52);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), value);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
EXPECT_NO_THROW({ copy.set_value(0.0); });
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), 0.0);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
EXPECT_NO_THROW({ copy.set_value(0.52); });
EXPECT_DOUBLE_EQ(copy.get_value<double>().value(), 0.52);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
}
}

Expand All @@ -198,10 +198,10 @@ TEST(TestHandle, move_assignment)
double value_2 = 2.337;
hardware_interface::Handle handle{JOINT_NAME, FOO_INTERFACE, &value};
hardware_interface::Handle moved{JOINT_NAME, "random", &value_2};
EXPECT_DOUBLE_EQ(moved.get_value(), value_2);
EXPECT_DOUBLE_EQ(handle.get_value(), value);
EXPECT_DOUBLE_EQ(moved.get_value<double>().value(), value_2);
EXPECT_DOUBLE_EQ(handle.get_value<double>().value(), value);
moved = std::move(handle);
EXPECT_DOUBLE_EQ(moved.get_value(), value);
EXPECT_NO_THROW(moved.set_value(0.0));
EXPECT_DOUBLE_EQ(moved.get_value(), 0.0);
EXPECT_DOUBLE_EQ(moved.get_value<double>().value(), value);
EXPECT_NO_THROW({ moved.set_value(0.0); });
EXPECT_DOUBLE_EQ(moved.get_value<double>().value(), 0.0);
}

0 comments on commit d126642

Please sign in to comment.