Skip to content

Commit c67df7c

Browse files
fmauchbmagyardestogl
authored
Empty urdf tag humble (backport of #1017) (#1036)
* [URDF Parser] Allow empty urdf tag, e.g., parameter (#1017) * Do not explode with empty tag * Update tests to allow empty URDF parameter to hardware interface * Test checks that empty parameter tags work and actually checks the parsed urdf. * Patch test updates for humble API --------- Co-authored-by: Bence Magyar <[email protected]> Co-authored-by: Dr. Denis <[email protected]> (cherry picked from commit 7c07430)
1 parent f37408c commit c67df7c

File tree

3 files changed

+45
-28
lines changed

3 files changed

+45
-28
lines changed

hardware_interface/src/component_parser.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
// limitations under the License.
1414

1515
#include <tinyxml2.h>
16+
#include <charconv>
17+
#include <iostream>
1618
#include <regex>
1719
#include <stdexcept>
1820
#include <string>
@@ -65,7 +67,8 @@ std::string get_text_for_element(
6567
const auto get_text_output = element_it->GetText();
6668
if (!get_text_output)
6769
{
68-
throw std::runtime_error("text not specified in the " + tag_name + " tag");
70+
std::cerr << "text not specified in the " << tag_name << " tag" << std::endl;
71+
return "";
6972
}
7073
return get_text_output;
7174
}

hardware_interface/test/test_component_parser.cpp

Lines changed: 26 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -100,16 +100,6 @@ TEST_F(TestComponentParser, component_interface_type_empty_throws_error)
100100
ASSERT_THROW(parse_control_resources_from_urdf(broken_urdf_string), std::runtime_error);
101101
}
102102

103-
TEST_F(TestComponentParser, parameter_empty_throws_error)
104-
{
105-
const std::string broken_urdf_string =
106-
std::string(ros2_control_test_assets::urdf_head) +
107-
ros2_control_test_assets::invalid_urdf_ros2_control_parameter_empty +
108-
ros2_control_test_assets::urdf_tail;
109-
110-
ASSERT_THROW(parse_control_resources_from_urdf(broken_urdf_string), std::runtime_error);
111-
}
112-
113103
TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_one_interface)
114104
{
115105
std::string urdf_to_test =
@@ -598,6 +588,32 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_with_size_and_d
598588
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].size, 1);
599589
}
600590

591+
TEST_F(TestComponentParser, successfully_parse_parameter_empty)
592+
{
593+
const std::string urdf_to_test =
594+
std::string(ros2_control_test_assets::urdf_head) +
595+
ros2_control_test_assets::valid_urdf_ros2_control_parameter_empty +
596+
ros2_control_test_assets::urdf_tail;
597+
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);
598+
ASSERT_THAT(control_hardware, SizeIs(1));
599+
auto hardware_info = control_hardware.front();
600+
601+
EXPECT_EQ(hardware_info.name, "2DOF_System_Robot_Position_Only");
602+
EXPECT_EQ(hardware_info.type, "system");
603+
EXPECT_EQ(
604+
hardware_info.hardware_class_type,
605+
"ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only");
606+
607+
ASSERT_THAT(hardware_info.joints, SizeIs(1));
608+
609+
EXPECT_EQ(hardware_info.joints[0].name, "joint1");
610+
EXPECT_EQ(hardware_info.joints[0].type, "joint");
611+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].name, "position");
612+
613+
EXPECT_EQ(hardware_info.hardware_parameters.at("example_param_write_for_sec"), "");
614+
EXPECT_EQ(hardware_info.hardware_parameters.at("example_param_read_for_sec"), "2");
615+
}
616+
601617
TEST_F(TestComponentParser, negative_size_throws_error)
602618
{
603619
std::string urdf_to_test = std::string(ros2_control_test_assets::urdf_head) +

ros2_control_test_assets/include/ros2_control_test_assets/components_urdfs.hpp

Lines changed: 15 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -398,6 +398,21 @@ const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type =
398398
</ros2_control>
399399
)";
400400

401+
const auto valid_urdf_ros2_control_parameter_empty =
402+
R"(
403+
<ros2_control name="2DOF_System_Robot_Position_Only" type="system">
404+
<hardware>
405+
<plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
406+
<param name="example_param_write_for_sec"></param>
407+
<param name="example_param_read_for_sec">2</param>
408+
</hardware>
409+
<joint name="joint1">
410+
<command_interface name="position">
411+
</command_interface>
412+
</joint>
413+
</ros2_control>
414+
)";
415+
401416
// Errors
402417
const auto invalid_urdf_ros2_control_invalid_child =
403418
R"(
@@ -485,23 +500,6 @@ const auto invalid_urdf_ros2_control_component_interface_type_empty =
485500
</ros2_control>
486501
)";
487502

488-
const auto invalid_urdf_ros2_control_parameter_empty =
489-
R"(
490-
<ros2_control name="2DOF_System_Robot_Position_Only" type="system">
491-
<hardware>
492-
<plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
493-
<param name="example_param_write_for_sec"></param>
494-
<param name="example_param_read_for_sec">2</param>
495-
</hardware>
496-
<joint name="joint1">
497-
<command_interface name="position">
498-
<param name="min_position_value">-1</param>
499-
<param name="max_position_value">1</param>
500-
</command_interface>
501-
</joint>
502-
</ros2_control>
503-
)";
504-
505503
const auto invalid_urdf2_ros2_control_illegal_size =
506504
R"(
507505
<ros2_control name="RRBotSystemWithIllegalSize" type="system">

0 commit comments

Comments
 (0)