diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt
index e10f7ec16f..a243a6ed77 100644
--- a/hardware_interface/CMakeLists.txt
+++ b/hardware_interface/CMakeLists.txt
@@ -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)
@@ -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
@@ -125,6 +134,12 @@ install(
DIRECTORY include/
DESTINATION include/hardware_interface
)
+
+install(
+ DIRECTORY schema
+ DESTINATION share/hardware_interface
+)
+
install(
TARGETS
mock_components
diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml
index 8c448a1b12..6d320cf037 100644
--- a/hardware_interface/package.xml
+++ b/hardware_interface/package.xml
@@ -31,6 +31,8 @@
rcutils
ament_cmake_gmock
+ ament_index_cpp
+ libxml2
ros2_control_test_assets
diff --git a/hardware_interface/schema/ros2_control.xsd b/hardware_interface/schema/ros2_control.xsd
new file mode 100644
index 0000000000..a9c237c090
--- /dev/null
+++ b/hardware_interface/schema/ros2_control.xsd
@@ -0,0 +1,105 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/hardware_interface/test/test_validate_xml_schema.cpp b/hardware_interface/test/test_validate_xml_schema.cpp
new file mode 100644
index 0000000000..66124195d2
--- /dev/null
+++ b/hardware_interface/test/test_validate_xml_schema.cpp
@@ -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
+#include
+#include
+#include
+
+#include
+
+#include
+
+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());
+}
diff --git a/ros2_control_test_assets/CMakeLists.txt b/ros2_control_test_assets/CMakeLists.txt
index d63fb52c86..9450ba9d35 100644
--- a/ros2_control_test_assets/CMakeLists.txt
+++ b/ros2_control_test_assets/CMakeLists.txt
@@ -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
diff --git a/ros2_control_test_assets/urdf/test_hardware_components.urdf b/ros2_control_test_assets/urdf/test_hardware_components.urdf
index c49c79bf55..611a7b4385 100644
--- a/ros2_control_test_assets/urdf/test_hardware_components.urdf
+++ b/ros2_control_test_assets/urdf/test_hardware_components.urdf
@@ -52,6 +52,7 @@
test_hardware_components/TestForceTorqueSensor
+ 0
@@ -68,12 +69,22 @@
test_hardware_components/TestTwoJointSystem
-
+
+ -1
+ 1
+
+
+
+ 0
+ 1
+
+
+
diff --git a/ros2_control_test_assets/urdf/test_hardware_components_with_error.urdf b/ros2_control_test_assets/urdf/test_hardware_components_with_error.urdf
new file mode 100644
index 0000000000..34b01aa5c1
--- /dev/null
+++ b/ros2_control_test_assets/urdf/test_hardware_components_with_error.urdf
@@ -0,0 +1,90 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ test_hardware_components/TestForceTorqueSensor
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ test_hardware_components/TestTwoJointSystem
+
+
+
+ -1
+ 1
+
+
+
+
+
+
+
+
+
+ 0
+ 1
+
+
+
+
+