Skip to content

Commit

Permalink
Fix uninitialize typos and use SizeIs for vector size comparisons
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored and christophfroehlich committed Mar 27, 2024
1 parent 9112088 commit 6a95524
Show file tree
Hide file tree
Showing 7 changed files with 63 additions and 50 deletions.
25 changes: 15 additions & 10 deletions hardware_interface_testing/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,11 @@ class TestActuator : public ActuatorInterface
* // can only control one joint
* if (info_.joints.size() != 1) {return CallbackReturn::ERROR;}
* // can only control in position
* if (info_.joints[0].command_interfaces.size() != 1) {return CallbackReturn::ERROR;}
* if (info_.joints[0].command_interfaces.size() != 1) {return
* CallbackReturn::ERROR;}
* // can only give feedback state for position and velocity
* if (info_.joints[0].state_interfaces.size() != 2) {return CallbackReturn::ERROR;}
* if (info_.joints[0].state_interfaces.size() != 2) {return
* CallbackReturn::ERROR;}
*/

return CallbackReturn::SUCCESS;
Expand Down Expand Up @@ -95,7 +97,8 @@ class TestActuator : public ActuatorInterface
// simulate error on read
if (velocity_command_ == test_constants::READ_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
// reset value to get out from error on the next call - simplifies CM
// tests
velocity_command_ = 0.0;
return return_type::ERROR;
}
Expand All @@ -104,10 +107,11 @@ class TestActuator : public ActuatorInterface
{
return return_type::DEACTIVATE;
}
// The next line is for the testing purposes. We need value to be changed to be sure that
// the feedback from hardware to controllers in the chain is working as it should.
// This makes value checks clearer and confirms there is no "state = command" line or some
// other mixture of interfaces somewhere in the test stack.
// The next line is for the testing purposes. We need value to be changed to
// be sure that the feedback from hardware to controllers in the chain is
// working as it should. This makes value checks clearer and confirms there
// is no "state = command" line or some other mixture of interfaces
// somewhere in the test stack.
velocity_state_ = velocity_command_ / 2;
return return_type::OK;
}
Expand All @@ -117,7 +121,8 @@ class TestActuator : public ActuatorInterface
// simulate error on write
if (velocity_command_ == test_constants::WRITE_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
// reset value to get out from error on the next call - simplifies CM
// tests
velocity_command_ = 0.0;
return return_type::ERROR;
}
Expand All @@ -136,7 +141,7 @@ class TestActuator : public ActuatorInterface
double max_velocity_command_ = 0.0;
};

class TestUnitializableActuator : public TestActuator
class TestUninitializableActuator : public TestActuator
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
Expand All @@ -147,4 +152,4 @@ class TestUnitializableActuator : public TestActuator

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestActuator, hardware_interface::ActuatorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitializableActuator, hardware_interface::ActuatorInterface)
PLUGINLIB_EXPORT_CLASS(TestUninitializableActuator, hardware_interface::ActuatorInterface)
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,21 @@
</description>
</class>

<class name="test_unitializable_actuator" type="TestUnitializableActuator" base_class_type="hardware_interface::ActuatorInterface">
<class name="test_uninitializable_actuator" type="TestUninitializableActuator" base_class_type="hardware_interface::ActuatorInterface">
<description>
Test Unitializable Actuator
Test Uninitializable Actuator
</description>
</class>

<class name="test_unitializable_sensor" type="TestUnitializableSensor" base_class_type="hardware_interface::SensorInterface">
<class name="test_uninitializable_sensor" type="TestUninitializableSensor" base_class_type="hardware_interface::SensorInterface">
<description>
Test Unitializable Sensor
Test Uninitializable Sensor
</description>
</class>

<class name="test_unitializable_system" type="TestUnitializableSystem" base_class_type="hardware_interface::SystemInterface">
<class name="test_uninitializable_system" type="TestUninitializableSystem" base_class_type="hardware_interface::SystemInterface">
<description>
Test Unitializable System
Test Uninitializable System
</description>
</class>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class TestSensor : public SensorInterface
double velocity_state_ = 0.0;
};

class TestUnitializableSensor : public TestSensor
class TestUninitializableSensor : public TestSensor
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
Expand All @@ -66,4 +66,4 @@ class TestUnitializableSensor : public TestSensor

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestSensor, hardware_interface::SensorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitializableSensor, hardware_interface::SensorInterface)
PLUGINLIB_EXPORT_CLASS(TestUninitializableSensor, hardware_interface::SensorInterface)
10 changes: 6 additions & 4 deletions hardware_interface_testing/test/test_components/test_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,8 @@ class TestSystem : public SystemInterface
// simulate error on read
if (velocity_command_[0] == test_constants::READ_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
// reset value to get out from error on the next call - simplifies CM
// tests
velocity_command_[0] = 0.0;
return return_type::ERROR;
}
Expand All @@ -95,7 +96,8 @@ class TestSystem : public SystemInterface
// simulate error on write
if (velocity_command_[0] == test_constants::WRITE_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
// reset value to get out from error on the next call - simplifies CM
// tests
velocity_command_[0] = 0.0;
return return_type::ERROR;
}
Expand All @@ -117,7 +119,7 @@ class TestSystem : public SystemInterface
double configuration_command_ = 0.0;
};

class TestUnitializableSystem : public TestSystem
class TestUninitializableSystem : public TestSystem
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
Expand All @@ -128,4 +130,4 @@ class TestUnitializableSystem : public TestSystem

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestSystem, hardware_interface::SystemInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitializableSystem, hardware_interface::SystemInterface)
PLUGINLIB_EXPORT_CLASS(TestUninitializableSystem, hardware_interface::SystemInterface)
42 changes: 24 additions & 18 deletions hardware_interface_testing/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ using ros2_control_test_assets::TEST_SYSTEM_HARDWARE_NAME;
using ros2_control_test_assets::TEST_SYSTEM_HARDWARE_PLUGIN_NAME;
using ros2_control_test_assets::TEST_SYSTEM_HARDWARE_STATE_INTERFACES;
using ros2_control_test_assets::TEST_SYSTEM_HARDWARE_TYPE;
using testing::SizeIs;

auto configure_components =
[](TestableResourceManager & rm, const std::vector<std::string> & components = {})
Expand Down Expand Up @@ -101,22 +102,23 @@ TEST_F(ResourceManagerTest, post_initialization_with_urdf)
ASSERT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_robot_urdf));
}

TEST_F(ResourceManagerTest, test_unitializable_hardware_validation)
TEST_F(ResourceManagerTest, test_uninitializable_hardware_validation)
{
// If the the hardware can not be initialized and load_urdf tried to validate the interfaces a
// runtime exception is thrown
// If the the hardware can not be initialized and load_urdf tried to validate
// the interfaces a runtime exception is thrown
TestableResourceManager rm;
ASSERT_THROW(
rm.load_urdf(ros2_control_test_assets::minimal_unitializable_robot_urdf, true),
rm.load_urdf(ros2_control_test_assets::minimal_uninitializable_robot_urdf, true),
std::runtime_error);
}

TEST_F(ResourceManagerTest, test_unitializable_hardware_no_validation)
TEST_F(ResourceManagerTest, test_uninitializable_hardware_no_validation)
{
// If the the hardware can not be initialized and load_urdf didn't try to validate the interfaces,
// the interface should not show up
// If the the hardware can not be initialized and load_urdf didn't try to
// validate the interfaces, the interface should not show up
TestableResourceManager rm;
EXPECT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_unitializable_robot_urdf, false));
EXPECT_NO_THROW(
rm.load_urdf(ros2_control_test_assets::minimal_uninitializable_robot_urdf, false));

// test actuator
EXPECT_FALSE(rm.state_interface_exists("joint1/position"));
Expand Down Expand Up @@ -150,15 +152,15 @@ TEST_F(ResourceManagerTest, initialization_with_urdf_manual_validation)
EXPECT_EQ(1u, rm.system_components_size());

auto state_interface_keys = rm.state_interface_keys();
ASSERT_EQ(11u, state_interface_keys.size());
ASSERT_THAT(state_interface_keys, SizeIs(11));
EXPECT_TRUE(rm.state_interface_exists("joint1/position"));
EXPECT_TRUE(rm.state_interface_exists("joint1/velocity"));
EXPECT_TRUE(rm.state_interface_exists("sensor1/velocity"));
EXPECT_TRUE(rm.state_interface_exists("joint2/position"));
EXPECT_TRUE(rm.state_interface_exists("joint3/position"));

auto command_interface_keys = rm.command_interface_keys();
ASSERT_EQ(6u, command_interface_keys.size());
ASSERT_THAT(command_interface_keys, SizeIs(6));
EXPECT_TRUE(rm.command_interface_exists("joint1/position"));
EXPECT_TRUE(rm.command_interface_exists("joint2/velocity"));
EXPECT_TRUE(rm.command_interface_exists("joint3/velocity"));
Expand Down Expand Up @@ -351,8 +353,8 @@ TEST_F(ResourceManagerTest, post_initialization_add_components)
EXPECT_EQ(1u, rm.sensor_components_size());
EXPECT_EQ(1u, rm.system_components_size());

ASSERT_EQ(11u, rm.state_interface_keys().size());
ASSERT_EQ(6u, rm.command_interface_keys().size());
ASSERT_THAT(rm.state_interface_keys(), SizeIs(11));
ASSERT_THAT(rm.command_interface_keys(), SizeIs(6));

hardware_interface::HardwareInfo external_component_hw_info;
external_component_hw_info.name = "ExternalComponent";
Expand All @@ -361,9 +363,9 @@ TEST_F(ResourceManagerTest, post_initialization_add_components)
rm.import_component(std::make_unique<ExternalComponent>(), external_component_hw_info);
EXPECT_EQ(2u, rm.actuator_components_size());

ASSERT_EQ(12u, rm.state_interface_keys().size());
ASSERT_THAT(rm.state_interface_keys(), SizeIs(12));
EXPECT_TRUE(rm.state_interface_exists("external_joint/external_state_interface"));
ASSERT_EQ(7u, rm.command_interface_keys().size());
ASSERT_THAT(rm.command_interface_keys(), SizeIs(7));
EXPECT_TRUE(rm.command_interface_exists("external_joint/external_command_interface"));

auto status_map = rm.get_components_status();
Expand Down Expand Up @@ -874,7 +876,8 @@ TEST_F(ResourceManagerTest, resource_availability_and_claiming_in_lifecycle)
std::bind(&TestableResourceManager::command_interface_is_claimed, &rm, _1), expected_result);
};

// All resources start as UNCONFIGURED - All interfaces are imported but not available
// All resources start as UNCONFIGURED - All interfaces are imported but not
// available
{
check_interfaces(
TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES,
Expand Down Expand Up @@ -954,7 +957,8 @@ TEST_F(ResourceManagerTest, resource_availability_and_claiming_in_lifecycle)
TEST_SYSTEM_HARDWARE_STATE_INTERFACES, TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES, false);
}

// When actuator is activated all state- and command- interfaces become available
// When actuator is activated all state- and command- interfaces become
// available
activate_components(rm, {TEST_ACTUATOR_HARDWARE_NAME});
{
check_interfaces(
Expand Down Expand Up @@ -1430,7 +1434,8 @@ class ResourceManagerTestReadWriteError : public ResourceManagerTest
check_if_interface_available(true, true);
}

// read failure for both, TEST_ACTUATOR_HARDWARE_NAME and TEST_SYSTEM_HARDWARE_NAME
// read failure for both, TEST_ACTUATOR_HARDWARE_NAME and
// TEST_SYSTEM_HARDWARE_NAME
claimed_itfs[0].set_value(fail_value);
claimed_itfs[1].set_value(fail_value);
{
Expand Down Expand Up @@ -1547,7 +1552,8 @@ class ResourceManagerTestReadWriteError : public ResourceManagerTest
check_if_interface_available(true, true);
}

// deactivate both, TEST_ACTUATOR_HARDWARE_NAME and TEST_SYSTEM_HARDWARE_NAME
// deactivate both, TEST_ACTUATOR_HARDWARE_NAME and
// TEST_SYSTEM_HARDWARE_NAME
claimed_itfs[0].set_value(deactivate_value);
claimed_itfs[1].set_value(deactivate_value);
{
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface_testing/test/test_resource_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class TestableResourceManager : public hardware_interface::ResourceManager
FRIEND_TEST(ResourceManagerTest, post_initialization_add_components);
FRIEND_TEST(ResourceManagerTest, managing_controllers_reference_interfaces);
FRIEND_TEST(ResourceManagerTest, resource_availability_and_claiming_in_lifecycle);
FRIEND_TEST(ResourceManagerTest, test_unitializable_hardware_no_validation);
FRIEND_TEST(ResourceManagerTest, test_uninitializable_hardware_no_validation);

TestableResourceManager() : hardware_interface::ResourceManager() {}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -306,11 +306,11 @@ const auto hardware_resources =
</ros2_control>
)";

const auto unitializable_hardware_resources =
const auto uninitializable_hardware_resources =
R"(
<ros2_control name="TestUnitializableActuatorHardware" type="actuator">
<ros2_control name="TestUninitializableActuatorHardware" type="actuator">
<hardware>
<plugin>test_unitializable_actuator</plugin>
<plugin>test_uninitializable_actuator</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position"/>
Expand All @@ -319,19 +319,19 @@ const auto unitializable_hardware_resources =
<command_interface name="max_velocity" />
</joint>
</ros2_control>
<ros2_control name="TestUnitializableSensorHardware" type="sensor">
<ros2_control name="TestUninitializableSensorHardware" type="sensor">
<hardware>
<plugin>test_unitializable_sensor</plugin>
<plugin>test_uninitializable_sensor</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<sensor name="sensor1">
<state_interface name="velocity"/>
</sensor>
</ros2_control>
<ros2_control name="TestUnitializableSystemHardware" type="system">
<ros2_control name="TestUninitializableSystemHardware" type="system">
<hardware>
<plugin>test_unitializable_system</plugin>
<plugin>test_uninitializable_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
Expand Down Expand Up @@ -1011,8 +1011,8 @@ const auto gripper_hardware_resources_mimic_false_command_if =

const auto minimal_robot_urdf =
std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
const auto minimal_unitializable_robot_urdf =
std::string(urdf_head) + std::string(unitializable_hardware_resources) + std::string(urdf_tail);
const auto minimal_uninitializable_robot_urdf =
std::string(urdf_head) + std::string(uninitializable_hardware_resources) + std::string(urdf_tail);

const auto minimal_robot_missing_state_keys_urdf =
std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
Expand Down

0 comments on commit 6a95524

Please sign in to comment.