Skip to content

Commit

Permalink
Increase test coverage for deprecated config structure
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 29, 2023
1 parent 21a68c1 commit 9584729
Show file tree
Hide file tree
Showing 3 changed files with 74 additions and 4 deletions.
9 changes: 5 additions & 4 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -355,8 +355,8 @@ ComponentInfo parse_component_from_xml(const tinyxml2::XMLElement * component_it
if (component.is_mimic && command_interfaces_it)
{
throw std::runtime_error(
"Component " + std::string(component.name) +
" has mimic attribute set to true: Mimic joints cannot have command interfaces.");
"Component '" + std::string(component.name) +
"' has mimic attribute set to true: Mimic joints cannot have command interfaces.");
}
while (command_interfaces_it)
{
Expand Down Expand Up @@ -665,6 +665,7 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
const auto & joint = hw_info.joints.at(i);

// Search for mimic joints defined in ros2_control tag (deprecated)
// TODO(christophfroehlich) delete deprecated config with ROS-J
if (joint.parameters.find("mimic") != joint.parameters.cend())
{
std::cerr << "Warning: Mimic joints defined in ros2_control tag are deprecated. "
Expand Down Expand Up @@ -715,7 +716,7 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
[&name](const auto & j) { return j.name == name; });
if (it == hw_info.joints.end())
{
throw std::runtime_error("Joint `" + name + "` not found in hw_info.joints");
throw std::runtime_error("Joint '" + name + "' not found in hw_info.joints");
}
return std::distance(hw_info.joints.begin(), it);
};
Expand All @@ -729,7 +730,7 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
}
else
{
throw std::runtime_error("Joint `" + joint.name + "` has no mimic information in URDF");
throw std::runtime_error("Joint '" + joint.name + "' has no mimic information in URDF");
}
}
}
Expand Down
29 changes: 29 additions & 0 deletions hardware_interface/test/test_component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -691,6 +691,35 @@ TEST_F(TestComponentParser, mimic_true_valid_config)
EXPECT_EQ(hw_info[0].mimic_joints[0].joint_index, 1);
}

// TODO(christophfroehlich) delete deprecated config test
TEST_F(TestComponentParser, mimic_deprecated_valid_config)
{
const auto urdf_to_test =
std::string(ros2_control_test_assets::gripper_urdf_head) +
std::string(ros2_control_test_assets::gripper_hardware_resources_mimic_deprecated) +
std::string(ros2_control_test_assets::urdf_tail);
std::vector<hardware_interface::HardwareInfo> hw_info;
ASSERT_NO_THROW(hw_info = parse_control_resources_from_urdf(urdf_to_test));
ASSERT_THAT(hw_info, SizeIs(1));
ASSERT_THAT(hw_info[0].mimic_joints, SizeIs(1));
EXPECT_DOUBLE_EQ(hw_info[0].mimic_joints[0].multiplier, 1.0);
EXPECT_DOUBLE_EQ(hw_info[0].mimic_joints[0].offset, 0.0);
EXPECT_EQ(hw_info[0].mimic_joints[0].mimicked_joint_index, 0);
EXPECT_EQ(hw_info[0].mimic_joints[0].joint_index, 1);
}

TEST_F(TestComponentParser, mimic_deprecated_unknown_joint_throws_error)
{
const auto urdf_to_test =
std::string(ros2_control_test_assets::gripper_urdf_head) +
std::string(
ros2_control_test_assets::gripper_hardware_resources_mimic_deprecated_unknown_joint) +
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);
}
// end delete deprecated config test

TEST_F(TestComponentParser, mimic_with_unknown_joint_throws_error)
{
const auto urdf_to_test =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -873,6 +873,46 @@ const auto gripper_hardware_resources_mimic_true_no_command_if =
</ros2_control>
)";

// TODO(christophfroehlich) delete deprecated config test
const auto gripper_hardware_resources_mimic_deprecated =
R"(
<ros2_control name="TestGripper" type="system">
<joint name="right_finger_joint">
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_finger_joint">
<param name="mimic">right_finger_joint</param>
<param name="multiplier">1</param>
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
)";

const auto gripper_hardware_resources_mimic_deprecated_unknown_joint =
R"(
<ros2_control name="TestGripper" type="system">
<joint name="right_finger_joint">
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_finger_joint">
<param name="mimic">middle_finger_joint</param>
<param name="multiplier">1</param>
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
)";
// end delete deprecated config test

const auto gripper_hardware_resources_mimic_true_command_if =
R"(
<ros2_control name="TestGripper" type="system">
Expand Down

0 comments on commit 9584729

Please sign in to comment.