Skip to content

Commit 25a9c63

Browse files
authored
Read data_type for all types of interfaces (#2235)
1 parent 151b22e commit 25a9c63

File tree

3 files changed

+106
-7
lines changed

3 files changed

+106
-7
lines changed

hardware_interface/src/component_parser.cpp

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -410,6 +410,9 @@ hardware_interface::InterfaceInfo parse_interfaces_from_xml(
410410
interface.parameters = parse_parameters_from_xml(params_it);
411411
}
412412

413+
interface.data_type = parse_data_type_attribute(interfaces_it);
414+
interface.size = static_cast<int>(parse_size_attribute(interfaces_it));
415+
413416
return interface;
414417
}
415418

@@ -503,10 +506,6 @@ ComponentInfo parse_complex_component_from_xml(const tinyxml2::XMLElement * comp
503506
while (command_interfaces_it)
504507
{
505508
component.command_interfaces.push_back(parse_interfaces_from_xml(command_interfaces_it));
506-
component.command_interfaces.back().data_type =
507-
parse_data_type_attribute(command_interfaces_it);
508-
component.command_interfaces.back().size =
509-
static_cast<int>(parse_size_attribute(command_interfaces_it));
510509
command_interfaces_it = command_interfaces_it->NextSiblingElement(kCommandInterfaceTag);
511510
}
512511

@@ -515,9 +514,6 @@ ComponentInfo parse_complex_component_from_xml(const tinyxml2::XMLElement * comp
515514
while (state_interfaces_it)
516515
{
517516
component.state_interfaces.push_back(parse_interfaces_from_xml(state_interfaces_it));
518-
component.state_interfaces.back().data_type = parse_data_type_attribute(state_interfaces_it);
519-
component.state_interfaces.back().size =
520-
static_cast<int>(parse_size_attribute(state_interfaces_it));
521517
state_interfaces_it = state_interfaces_it->NextSiblingElement(kStateInterfaceTag);
522518
}
523519

hardware_interface/test/test_component_parser.cpp

Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
#include "gmock/gmock.h"
1717
#include "hardware_interface/component_parser.hpp"
18+
#include "hardware_interface/handle.hpp"
1819
#include "hardware_interface/types/hardware_interface_type_values.hpp"
1920
#include "ros2_control_test_assets/components_urdfs.hpp"
2021
#include "ros2_control_test_assets/descriptions.hpp"
@@ -980,6 +981,82 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_with_size_and_d
980981
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].size, 1);
981982
}
982983

984+
TEST_F(
985+
TestComponentParser,
986+
successfully_parse_valid_urdf_system_with_bool_data_type_on_joint_sensor_and_gpio)
987+
{
988+
std::string urdf_to_test =
989+
std::string(ros2_control_test_assets::urdf_head) +
990+
ros2_control_test_assets::
991+
valid_urdf_ros2_control_system_robot_with_size_and_data_type_on_joint_sensor_and_gpio +
992+
ros2_control_test_assets::urdf_tail;
993+
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);
994+
ASSERT_THAT(control_hardware, SizeIs(1));
995+
auto hardware_info = control_hardware.front();
996+
997+
EXPECT_EQ(hardware_info.name, "RRBotSystemWithSizeAndDataType");
998+
EXPECT_EQ(hardware_info.type, "system");
999+
EXPECT_EQ(
1000+
hardware_info.hardware_plugin_name,
1001+
"ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType");
1002+
1003+
ASSERT_THAT(hardware_info.joints, SizeIs(1));
1004+
ASSERT_FALSE(hardware_info.is_async);
1005+
ASSERT_EQ(hardware_info.thread_priority, std::numeric_limits<int>::max());
1006+
EXPECT_EQ(hardware_info.joints[0].name, "joint1");
1007+
EXPECT_EQ(hardware_info.joints[0].type, "joint");
1008+
EXPECT_THAT(hardware_info.joints[0].command_interfaces, SizeIs(2));
1009+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].name, HW_IF_POSITION);
1010+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].data_type, "double");
1011+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].size, 1);
1012+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[1].name, "enable");
1013+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[1].data_type, "bool");
1014+
EXPECT_EQ(hardware_info.joints[0].command_interfaces[1].size, 1);
1015+
hardware_interface::InterfaceDescription bool_cmd_description(
1016+
hardware_info.joints[0].name, hardware_info.joints[0].command_interfaces[1]);
1017+
auto bool_cmd_itf = hardware_interface::CommandInterface(bool_cmd_description);
1018+
ASSERT_EQ(hardware_interface::HandleDataType::BOOL, bool_cmd_itf.get_data_type());
1019+
1020+
EXPECT_THAT(hardware_info.joints[0].state_interfaces, SizeIs(2));
1021+
EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].name, HW_IF_POSITION);
1022+
EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].data_type, "double");
1023+
EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].size, 1);
1024+
EXPECT_EQ(hardware_info.joints[0].state_interfaces[1].name, "status");
1025+
EXPECT_EQ(hardware_info.joints[0].state_interfaces[1].data_type, "bool");
1026+
EXPECT_EQ(hardware_info.joints[0].state_interfaces[1].size, 1);
1027+
hardware_interface::InterfaceDescription bool_state_description(
1028+
hardware_info.joints[0].name, hardware_info.joints[0].state_interfaces[1]);
1029+
auto bool_state_itf = hardware_interface::StateInterface(bool_state_description);
1030+
ASSERT_EQ(hardware_interface::HandleDataType::BOOL, bool_state_itf.get_data_type());
1031+
1032+
ASSERT_THAT(hardware_info.sensors, SizeIs(1));
1033+
EXPECT_EQ(hardware_info.sensors[0].name, "trigger");
1034+
EXPECT_EQ(hardware_info.sensors[0].type, "sensor");
1035+
EXPECT_THAT(hardware_info.sensors[0].state_interfaces, SizeIs(1));
1036+
EXPECT_EQ(hardware_info.sensors[0].state_interfaces[0].name, "safety");
1037+
EXPECT_EQ(hardware_info.sensors[0].state_interfaces[0].data_type, "bool");
1038+
EXPECT_EQ(hardware_info.sensors[0].state_interfaces[0].size, 1);
1039+
EXPECT_THAT(hardware_info.sensors[0].command_interfaces, SizeIs(1));
1040+
EXPECT_EQ(hardware_info.sensors[0].command_interfaces[0].name, "safety");
1041+
EXPECT_EQ(hardware_info.sensors[0].command_interfaces[0].data_type, "bool");
1042+
EXPECT_EQ(hardware_info.sensors[0].command_interfaces[0].size, 1);
1043+
1044+
ASSERT_THAT(hardware_info.gpios, SizeIs(1));
1045+
EXPECT_EQ(hardware_info.gpios[0].name, "flange_IOS");
1046+
EXPECT_EQ(hardware_info.gpios[0].type, "gpio");
1047+
EXPECT_THAT(hardware_info.gpios[0].command_interfaces, SizeIs(1));
1048+
EXPECT_EQ(hardware_info.gpios[0].command_interfaces[0].name, "digital_output");
1049+
EXPECT_EQ(hardware_info.gpios[0].command_interfaces[0].data_type, "bool");
1050+
EXPECT_EQ(hardware_info.gpios[0].command_interfaces[0].size, 2);
1051+
EXPECT_THAT(hardware_info.gpios[0].state_interfaces, SizeIs(2));
1052+
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[0].name, "analog_input");
1053+
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[0].data_type, "double");
1054+
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[0].size, 3);
1055+
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].name, "image");
1056+
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].data_type, "cv::Mat");
1057+
EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].size, 1);
1058+
}
1059+
9831060
TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_and_disabled_interfaces)
9841061
{
9851062
std::string urdf_to_test =

ros2_control_test_assets/include/ros2_control_test_assets/components_urdfs.hpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -735,6 +735,32 @@ const auto valid_urdf_ros2_control_parameter_empty =
735735
</ros2_control>
736736
)";
737737

738+
const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type_on_joint_sensor_and_gpio =
739+
R"(
740+
<ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
741+
<hardware>
742+
<plugin>ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType</plugin>
743+
<param name="example_param_write_for_sec">2</param>
744+
<param name="example_param_read_for_sec">2</param>
745+
</hardware>
746+
<joint name="joint1">
747+
<command_interface name="position"/>
748+
<state_interface name="position"/>
749+
<state_interface name="status" data_type="bool"/>
750+
<command_interface name="enable" data_type="bool"/>
751+
</joint>
752+
<sensor name="trigger">
753+
<command_interface name="safety" data_type="bool"/>
754+
<state_interface name="safety" data_type="bool"/>
755+
</sensor>
756+
<gpio name="flange_IOS">
757+
<command_interface name="digital_output" size="2" data_type="bool"/>
758+
<state_interface name="analog_input" size="3"/>
759+
<state_interface name="image" data_type="cv::Mat"/>
760+
</gpio>
761+
</ros2_control>
762+
)";
763+
738764
// Errors
739765
const auto invalid_urdf_ros2_control_invalid_child =
740766
R"(

0 commit comments

Comments
 (0)