Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,8 @@ if(BUILD_TESTING)

find_package(ament_cmake_gmock REQUIRED)
find_package(ros2_control_test_assets REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(LibXml2)

ament_add_gmock(test_macros test/test_macros.cpp)
target_include_directories(test_macros PRIVATE include)
Expand Down Expand Up @@ -101,6 +103,13 @@ if(BUILD_TESTING)
ament_add_gmock(test_component_parser test/test_component_parser.cpp)
target_link_libraries(test_component_parser hardware_interface ros2_control_test_assets::ros2_control_test_assets)

# Test XML Schema Validator
ament_add_gmock(test_validate_xml_schema test/test_validate_xml_schema.cpp)
target_link_libraries(test_validate_xml_schema
ament_index_cpp::ament_index_cpp
LibXml2::LibXml2
)

add_library(test_hardware_components SHARED
test/test_hardware_components/test_single_joint_actuator.cpp
test/test_hardware_components/test_force_torque_sensor.cpp
Expand All @@ -125,6 +134,12 @@ install(
DIRECTORY include/
DESTINATION include/hardware_interface
)

install(
DIRECTORY schema
DESTINATION share/hardware_interface
)

install(
TARGETS
mock_components
Expand Down
2 changes: 2 additions & 0 deletions hardware_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
<exec_depend>rcutils</exec_depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_index_cpp</test_depend>
<test_depend>libxml2</test_depend>
<test_depend>ros2_control_test_assets</test_depend>

<export>
Expand Down
105 changes: 105 additions & 0 deletions hardware_interface/schema/ros2_control.xsd
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
<?xml version="1.0" encoding="UTF-8"?>
<xs:schema xmlns:xs="http://www.w3.org/2001/XMLSchema"
elementFormDefault="qualified">

<!-- Reusable types -->
<xs:complexType name="paramType">
<xs:simpleContent>
<xs:extension base="xs:string">
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:extension>
</xs:simpleContent>
</xs:complexType>

<xs:complexType name="interfaceType">
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:complexType>

<xs:complexType name="commandInterfaceType">
<xs:sequence>
<xs:element name="param" type="paramType" minOccurs="0" maxOccurs="unbounded"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:complexType>

<xs:complexType name="jointOrGpioType">
<xs:sequence>
<xs:element name="command_interface" type="commandInterfaceType" minOccurs="0" maxOccurs="unbounded"/>
<xs:element name="state_interface" type="interfaceType" minOccurs="0" maxOccurs="unbounded"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:complexType>



<!-- Root robot element -->
<xs:element name="robot">
<xs:complexType>
<xs:choice minOccurs="0" maxOccurs="unbounded">
<xs:element ref="link"/>
<xs:element ref="joint"/>
<xs:element ref="ros2_control"/>
<xs:element ref="transmission" minOccurs="0" maxOccurs="unbounded"/>
<xs:element ref="material" minOccurs="0" maxOccurs="unbounded"/>
<!-- Add more URDF elements here as needed -->
</xs:choice>
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:complexType>
</xs:element>


<!-- Minimal link and joint element definitions for validation -->
<xs:element name="link">
<xs:complexType mixed="true">
<xs:sequence minOccurs="0" maxOccurs="unbounded">
<xs:any processContents="lax" minOccurs="0" maxOccurs="unbounded"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:complexType>
</xs:element>

<xs:element name="joint">
<xs:complexType mixed="true">
<xs:sequence minOccurs="0" maxOccurs="unbounded">
<xs:any processContents="lax" minOccurs="0" maxOccurs="unbounded"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute name="type" type="xs:string" use="required"/>
</xs:complexType>
</xs:element>

<xs:element name="transmission" type="xs:anyType"/>
<xs:element name="material" type="xs:anyType"/>


<!-- ros2_control block -->
<xs:element name="ros2_control">
<xs:complexType>
<xs:sequence>
<xs:element name="hardware">
<xs:complexType>
<xs:sequence>
<xs:element name="plugin" type="xs:string"/>
<xs:element name="param" type="paramType" minOccurs="0" maxOccurs="unbounded"/>
</xs:sequence>
</xs:complexType>
</xs:element>
<xs:choice minOccurs="0" maxOccurs="unbounded">
<xs:element name="joint" type="jointOrGpioType" minOccurs="0" maxOccurs="unbounded"/>
<xs:element name="gpio" type="jointOrGpioType" minOccurs="0" maxOccurs="unbounded"/>
<xs:element name="sensor" minOccurs="0" maxOccurs="unbounded">
<xs:complexType>
<xs:sequence>
<xs:element name="state_interface" type="interfaceType" minOccurs="0" maxOccurs="unbounded"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
</xs:complexType>
</xs:element>
</xs:choice>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute name="type" type="xs:string" use="required"/>
</xs:complexType>
</xs:element>

</xs:schema>
120 changes: 120 additions & 0 deletions hardware_interface/test/test_validate_xml_schema.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
// Copyright 2025 ros2_control development team
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <libxml/parser.h>
#include <libxml/xmlschemas.h>

#include <string>

#include <ament_index_cpp/get_package_share_directory.hpp>

class XmlParser
{
public:
XmlParser(const std::string & xmlFilePath, const std::string & xsdFilePath)
: doc(nullptr), schema(nullptr), schemaCtx(nullptr)
{
this->xmlFile = xmlFilePath;
this->xsdFile = xsdFilePath;
}

~XmlParser()
{
if (doc)
{
xmlFreeDoc(doc);
}
if (schemaCtx)
{
xmlSchemaFreeParserCtxt(schemaCtx);
}
if (schema)
{
xmlSchemaFree(schema);
}
xmlCleanupParser();
}

bool parseAndValidate()
{
doc = xmlReadFile(xmlFile.c_str(), nullptr, 0);
if (!doc)
{
return false;
}

schemaCtx = xmlSchemaNewParserCtxt(xsdFile.c_str());
if (!schemaCtx)
{
return false;
}
schema = xmlSchemaParse(schemaCtx);
if (!schema)
{
return false;
}

xmlSchemaValidCtxtPtr validCtx = xmlSchemaNewValidCtxt(schema);
if (!validCtx)
{
return false;
}
int ret = xmlSchemaValidateDoc(validCtx, doc);
xmlSchemaFreeValidCtxt(validCtx);

return ret == 0;
}

private:
std::string xmlFile;
std::string xsdFile;
xmlDocPtr doc;
xmlSchemaPtr schema;
xmlSchemaParserCtxtPtr schemaCtx;
};

// Test fixture for XML schema validation
class XmlSchemaValidationTest : public ::testing::Test
{
protected:
std::string valid_xml;
std::string invalid_xml;
std::string xsd;

void SetUp() override
{
// Use ament_index_cpp to get the package share directory
std::string urdf_package_share_dir =
ament_index_cpp::get_package_share_directory("ros2_control_test_assets");
std::string xsd_package_share_dir =
ament_index_cpp::get_package_share_directory("hardware_interface");
valid_xml = urdf_package_share_dir + "/urdf/test_hardware_components.urdf";
invalid_xml = urdf_package_share_dir + "/urdf/test_hardware_components_with_error.urdf";
xsd = xsd_package_share_dir + "/schema/ros2_control.xsd";
}
};

TEST_F(XmlSchemaValidationTest, ValidXmlPasses)
{
XmlParser parser(valid_xml, xsd);
EXPECT_TRUE(parser.parseAndValidate());
}

TEST_F(XmlSchemaValidationTest, InvalidXmlFails)
{
XmlParser parser(invalid_xml, xsd);
EXPECT_FALSE(parser.parseAndValidate());
}
2 changes: 1 addition & 1 deletion ros2_control_test_assets/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ install(
DESTINATION include/ros2_control_test_assets
)
install(
FILES urdf/test_hardware_components.urdf
FILES urdf/test_hardware_components.urdf urdf/test_hardware_components_with_error.urdf
DESTINATION share/ros2_control_test_assets/urdf
)
install(TARGETS ros2_control_test_assets
Expand Down
13 changes: 12 additions & 1 deletion ros2_control_test_assets/urdf/test_hardware_components.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@
<ros2_control name="TestSensorComponent" type="sensor">
<hardware>
<plugin>test_hardware_components/TestForceTorqueSensor</plugin>
<param name="test_param">0</param>
</hardware>
<sensor name="ft_sensor">
<state_interface name="fx"/>
Expand All @@ -68,12 +69,22 @@
<plugin>test_hardware_components/TestTwoJointSystem</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position"/>
<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"/>
<state_interface name="position"/>
</joint>
<gpio name="flange_analog_IOs">
<command_interface name="analog_output1">
<param name="min">0</param>
<param name="max">1</param>
</command_interface>
<state_interface name="analog_input1"/>
</gpio>
</ros2_control>
</robot>
Loading
Loading