Skip to content
11 changes: 8 additions & 3 deletions hardware_interface/include/hardware_interface/hardware_info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,16 +48,16 @@ struct ComponentInfo
{
/// Name of the component.
std::string name;
/// Type of the component: sensor or joint.
/// Type of the component: sensor, joint, or GPIO.
std::string type;
/**
* Name of the command interfaces that can be set, e.g. "position", "velocity", etc.
* Used by joints.
* Used by joints and GPIO.
*/
std::vector<InterfaceInfo> command_interfaces;
/**
* Name of the state interfaces that can be read, e.g. "position", "velocity", etc.
* Used by Joints and Sensors.
* Used by Joints, Sensors and GPIO.
*/
std::vector<InterfaceInfo> state_interfaces;
/// (Optional) Key-value pairs of component parameters, e.g. min/max values or serial number.
Expand All @@ -84,6 +84,11 @@ struct HardwareInfo
* Required for Sensor and optional for System Hardware.
*/
std::vector<ComponentInfo> sensors;
/**
* Map of GPIO provided by the hardware where the key is a descriptive name of the GPIO.
* Optional for any hardware components.
*/
std::vector<ComponentInfo> gpios;
/**
* Map of transmissions to calcualte ration between joints and physical actuators.
* Optional for Actuator and System Hardware.
Expand Down
3 changes: 3 additions & 0 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ constexpr const auto kClassTypeTag = "plugin";
constexpr const auto kParamTag = "param";
constexpr const auto kJointTag = "joint";
constexpr const auto kSensorTag = "sensor";
constexpr const auto kGPIOTag = "gpio";
constexpr const auto kTransmissionTag = "transmission";
constexpr const auto kCommandInterfaceTag = "command_interface";
constexpr const auto kStateInterfaceTag = "state_interface";
Expand Down Expand Up @@ -231,6 +232,8 @@ HardwareInfo parse_resource_from_xml(const tinyxml2::XMLElement * ros2_control_i
hardware.sensors.push_back(parse_component_from_xml(ros2_control_child_it) );
} else if (!std::string(kTransmissionTag).compare(ros2_control_child_it->Name())) {
hardware.transmissions.push_back(parse_component_from_xml(ros2_control_child_it) );
} else if (!std::string(kGPIOTag).compare(ros2_control_child_it->Name())) {
hardware.gpios.push_back(parse_component_from_xml(ros2_control_child_it) );
} else {
throw std::runtime_error("invalid tag name " + std::string(ros2_control_child_it->Name()));
}
Expand Down
42 changes: 42 additions & 0 deletions hardware_interface/test/test_component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -497,3 +497,45 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_only)
ASSERT_THAT(hardware_info.transmissions[0].parameters, SizeIs(1));
EXPECT_EQ(hardware_info.transmissions[0].parameters.at("joint_to_actuator"), "${1024/PI}");
}

TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_gpio)
{
std::string urdf_to_test =
std::string(ros2_control_test_assets::urdf_head) +
ros2_control_test_assets::valid_urdf_ros2_control_system_robot_with_gpio +
ros2_control_test_assets::urdf_tail;
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);
ASSERT_THAT(control_hardware, SizeIs(1));
auto hardware_info = control_hardware.front();

EXPECT_EQ(hardware_info.name, "RRBotSystemWithGPIO");
EXPECT_EQ(hardware_info.type, "system");
EXPECT_EQ(
hardware_info.hardware_class_type,
"ros2_control_demo_hardware/RRBotSystemWithGPIOHardware");

ASSERT_THAT(hardware_info.joints, SizeIs(2));

EXPECT_EQ(hardware_info.joints[0].name, "joint1");
EXPECT_EQ(hardware_info.joints[0].type, "joint");

EXPECT_EQ(hardware_info.joints[1].name, "joint2");
EXPECT_EQ(hardware_info.joints[1].type, "joint");

ASSERT_THAT(hardware_info.gpios, SizeIs(2));

EXPECT_EQ(hardware_info.gpios[0].name, "flange_analog_IOs");
EXPECT_EQ(hardware_info.gpios[0].type, "gpio");
EXPECT_THAT(hardware_info.gpios[0].state_interfaces, SizeIs(3));
EXPECT_THAT(hardware_info.gpios[0].command_interfaces, SizeIs(1));
EXPECT_THAT(hardware_info.gpios[0].state_interfaces[0].name, "analog_output1");
EXPECT_THAT(hardware_info.gpios[0].state_interfaces[1].name, "analog_input1");
EXPECT_THAT(hardware_info.gpios[0].state_interfaces[2].name, "analog_input2");

EXPECT_EQ(hardware_info.gpios[1].name, "flange_vacuum");
EXPECT_EQ(hardware_info.gpios[1].type, "gpio");
EXPECT_THAT(hardware_info.gpios[1].state_interfaces, SizeIs(1));
EXPECT_THAT(hardware_info.gpios[1].command_interfaces, SizeIs(1));
EXPECT_THAT(hardware_info.gpios[1].state_interfaces[0].name, "vacuum");
EXPECT_THAT(hardware_info.gpios[1].command_interfaces[0].name, "vacuum");
}
Original file line number Diff line number Diff line change
Expand Up @@ -332,6 +332,42 @@ const auto valid_urdf_ros2_control_actuator_only =
</ros2_control>
)";

// 10. Industrial Robots with integrated GPIO
const auto valid_urdf_ros2_control_system_robot_with_gpio =
R"(
<ros2_control name="RRBotSystemWithGPIO" type="system">
<hardware>
<plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<joint name="joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<joint name="joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<gpio name="flange_analog_IOs">
<command_interface name="analog_output1"/>
<state_interface name="analog_output1"/> <!-- Needed to know current state of the output -->
<state_interface name="analog_input1"/>
<state_interface name="analog_input2"/>
</gpio>
<gpio name="flange_vacuum">
<command_interface name="vacuum"/>
<state_interface name="vacuum"/> <!-- Needed to know current state of the input -->
</gpio>
</ros2_control>
)";

// Errors
const auto invalid_urdf_ros2_control_invalid_child =
R"(
Expand Down