Skip to content

Commit

Permalink
Add testing for the component parser of the read and write rate
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jun 16, 2024
1 parent 6a3d92d commit 0c5e78d
Show file tree
Hide file tree
Showing 3 changed files with 95 additions and 5 deletions.
25 changes: 20 additions & 5 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,14 +233,29 @@ std::string parse_data_type_attribute(const tinyxml2::XMLElement * elem)
unsigned int parse_rw_rate_attribute(const tinyxml2::XMLElement * elem)
{
const tinyxml2::XMLAttribute * attr = elem->FindAttribute(kReadWriteRateAttribute);
const auto rw_rate = attr ? std::stoi(attr->Value()) : 0;
if (rw_rate < 0)
try
{
const auto rw_rate = attr ? std::stoi(attr->Value()) : 0;
if (rw_rate < 0)
{
throw std::runtime_error(
"Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." + "Got \"" +
std::to_string(rw_rate) + "\", but expected a positive integer.");
}
return static_cast<unsigned int>(rw_rate);
}
catch (const std::invalid_argument & e)
{
throw std::runtime_error(
"Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." +
" Invalid value : \"" + attr->Value() + "\", expected a positive integer.");
}
catch (const std::out_of_range & e)
{
throw std::runtime_error(
"Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." + "Got \"" +
std::to_string(rw_rate) + "\", but expected a positive integer.");
"Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." +
" Out of range value : \"" + attr->Value() + "\", expected a positive valid integer.");
}
return static_cast<unsigned int>(rw_rate);
}

/// Parse is_async attribute
Expand Down
30 changes: 30 additions & 0 deletions hardware_interface/test/test_component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1358,6 +1358,36 @@ TEST_F(TestComponentParser, gripper_mimic_deprecated_valid_config)
EXPECT_EQ(hw_info[0].mimic_joints[0].joint_index, 1);
}

TEST_F(TestComponentParser, negative_rw_rates_throws_error)
{
const auto urdf_to_test =
std::string(ros2_control_test_assets::gripper_urdf_head) +
std::string(ros2_control_test_assets::hardware_resources_with_negative_rw_rates) +
std::string(ros2_control_test_assets::urdf_tail);
std::vector<hardware_interface::HardwareInfo> hw_info;
ASSERT_THROW(parse_control_resources_from_urdf(urdf_to_test), std::runtime_error);
}

TEST_F(TestComponentParser, invalid_rw_rates_throws_error)
{
const auto urdf_to_test =
std::string(ros2_control_test_assets::gripper_urdf_head) +
std::string(ros2_control_test_assets::hardware_resources_invalid_with_text_in_rw_rates) +
std::string(ros2_control_test_assets::urdf_tail);
std::vector<hardware_interface::HardwareInfo> hw_info;
ASSERT_THROW(parse_control_resources_from_urdf(urdf_to_test), std::runtime_error);
}

TEST_F(TestComponentParser, invalid_rw_rates_out_of_range)
{
const auto urdf_to_test =
std::string(ros2_control_test_assets::gripper_urdf_head) +
std::string(ros2_control_test_assets::hardware_resources_invalid_out_of_range_in_rw_rates) +
std::string(ros2_control_test_assets::urdf_tail);
std::vector<hardware_interface::HardwareInfo> hw_info;
ASSERT_THROW(parse_control_resources_from_urdf(urdf_to_test), std::runtime_error);
}

TEST_F(TestComponentParser, gripper_mimic_deprecated_unknown_joint_throws_error)
{
const auto urdf_to_test =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -709,6 +709,51 @@ const auto hardware_resources_with_different_rw_rates =
</ros2_control>
)";

const auto hardware_resources_with_negative_rw_rates =
R"(
<ros2_control name="TestActuatorHardware" type="actuator" rw_rate="-50">
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="right_finger_joint">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="max_velocity" />
</joint>
</ros2_control>
)";

const auto hardware_resources_invalid_with_text_in_rw_rates =
R"(
<ros2_control name="TestActuatorHardware" type="actuator" rw_rate="d 50">
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="right_finger_joint">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="max_velocity" />
</joint>
</ros2_control>
)";

const auto hardware_resources_invalid_out_of_range_in_rw_rates =
R"(
<ros2_control name="TestActuatorHardware" type="actuator" rw_rate="12345678901">
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="right_finger_joint">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="max_velocity" />
</joint>
</ros2_control>
)";

const auto uninitializable_hardware_resources =
R"(
<ros2_control name="TestUninitializableActuatorHardware" type="actuator">
Expand Down

0 comments on commit 0c5e78d

Please sign in to comment.