Skip to content

Commit

Permalink
Fix description of new test and fix typo
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 4, 2024
1 parent d0affd8 commit c54242d
Show file tree
Hide file tree
Showing 6 changed files with 26 additions and 30 deletions.
4 changes: 2 additions & 2 deletions hardware_interface/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ class TestActuator : public ActuatorInterface
double max_velocity_command_ = 0.0;
};

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

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestActuator, hardware_interface::ActuatorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitilizableActuator, hardware_interface::ActuatorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitializableActuator, hardware_interface::ActuatorInterface)
12 changes: 6 additions & 6 deletions hardware_interface/test/test_components/test_components.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,21 @@
</description>
</class>

<class name="test_unitilizable_actuator" type="TestUnitilizableActuator" base_class_type="hardware_interface::ActuatorInterface">
<class name="test_unitializable_actuator" type="TestUnitializableActuator" base_class_type="hardware_interface::ActuatorInterface">
<description>
Test Unitilizable Actuator
Test Unitializable Actuator
</description>
</class>

<class name="test_unitilizable_sensor" type="TestUnitilizableSensor" base_class_type="hardware_interface::SensorInterface">
<class name="test_unitializable_sensor" type="TestUnitializableSensor" base_class_type="hardware_interface::SensorInterface">
<description>
Test Unitilizable Sensor
Test Unitializable Sensor
</description>
</class>

<class name="test_unitilizable_system" type="TestUnitilizableSystem" base_class_type="hardware_interface::SystemInterface">
<class name="test_unitializable_system" type="TestUnitializableSystem" base_class_type="hardware_interface::SystemInterface">
<description>
Test Unitilizable System
Test Unitializable System
</description>
</class>
</library>
4 changes: 2 additions & 2 deletions hardware_interface/test/test_components/test_sensor.cpp
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 TestUnitilizableSensor : public TestSensor
class TestUnitializableSensor : public TestSensor
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
Expand All @@ -66,4 +66,4 @@ class TestUnitilizableSensor : public TestSensor

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestSensor, hardware_interface::SensorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitilizableSensor, hardware_interface::SensorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitializableSensor, hardware_interface::SensorInterface)
4 changes: 2 additions & 2 deletions hardware_interface/test/test_components/test_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class TestSystem : public SystemInterface
double configuration_command_ = 0.0;
};

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

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestSystem, hardware_interface::SystemInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitilizableSystem, hardware_interface::SystemInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitializableSystem, hardware_interface::SystemInterface)
10 changes: 5 additions & 5 deletions hardware_interface/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,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_unitilizable_hardware_no_validation);
FRIEND_TEST(ResourceManagerTest, test_unitializable_hardware_no_validation);

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

Expand Down Expand Up @@ -155,22 +155,22 @@ TEST_F(ResourceManagerTest, post_initialization_with_urdf)
ASSERT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_robot_urdf));
}

TEST_F(ResourceManagerTest, test_unitilizable_hardware_validation)
TEST_F(ResourceManagerTest, test_unitializable_hardware_validation)
{
// 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_unitilizable_robot_urdf, true),
rm.load_urdf(ros2_control_test_assets::minimal_unitializable_robot_urdf, true),
std::runtime_error);
}

TEST_F(ResourceManagerTest, test_unitilizable_hardware_no_validation)
TEST_F(ResourceManagerTest, test_unitializable_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
TestableResourceManager rm;
EXPECT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, false));
EXPECT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_unitializable_robot_urdf, false));

// test actuator
EXPECT_FALSE(rm.state_interface_exists("joint1/position"));
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 unitilizable_hardware_resources =
const auto unitializable_hardware_resources =
R"(
<ros2_control name="TestUnitilizableActuatorHardware" type="actuator">
<ros2_control name="TestUnitializableActuatorHardware" type="actuator">
<hardware>
<plugin>test_unitilizable_actuator</plugin>
<plugin>test_unitializable_actuator</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position"/>
Expand All @@ -319,19 +319,19 @@ const auto unitilizable_hardware_resources =
<command_interface name="max_velocity" />
</joint>
</ros2_control>
<ros2_control name="TestUnitilizableSensorHardware" type="sensor">
<ros2_control name="TestUnitializableSensorHardware" type="sensor">
<hardware>
<plugin>test_unitilizable_sensor</plugin>
<plugin>test_unitializable_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="TestUnitilizableSystemHardware" type="system">
<ros2_control name="TestUnitializableSystemHardware" type="system">
<hardware>
<plugin>test_unitilizable_system</plugin>
<plugin>test_unitializable_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
Expand All @@ -348,10 +348,6 @@ const auto unitilizable_hardware_resources =
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="configuration">
<command_interface name="max_tcp_jerk"/>
<state_interface name="max_tcp_jerk"/>
</joint>
</ros2_control>
)";

Expand Down Expand Up @@ -1015,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_unitilizable_robot_urdf =
std::string(urdf_head) + std::string(unitilizable_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_robot_missing_state_keys_urdf =
std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
Expand Down

0 comments on commit c54242d

Please sign in to comment.