diff --git a/launch_ros/package.xml b/launch_ros/package.xml
index 0df743b7..133b471c 100644
--- a/launch_ros/package.xml
+++ b/launch_ros/package.xml
@@ -17,18 +17,19 @@
Michel Hidalgo
William Woodall
- ament_index_python
- launch
- lifecycle_msgs
- osrf_pycommon
- rclpy
- python3-importlib-metadata
- python3-yaml
- composition_interfaces
+ ament_index_python
+ composition_interfaces
+ launch
+ lifecycle_msgs
+ osrf_pycommon
+ python3-importlib-metadata
+ python3-yaml
+ rclpy
ament_copyright
ament_flake8
ament_pep257
+ ament_xmllint
python3-pytest
diff --git a/launch_ros/test/test_xmllint.py b/launch_ros/test/test_xmllint.py
new file mode 100644
index 00000000..f46285e7
--- /dev/null
+++ b/launch_ros/test/test_xmllint.py
@@ -0,0 +1,23 @@
+# Copyright 2019 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_xmllint.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.xmllint
+def test_xmllint():
+ rc = main(argv=[])
+ assert rc == 0, 'Found errors'
diff --git a/launch_testing_ros/package.xml b/launch_testing_ros/package.xml
index 92defd22..847bf8bd 100644
--- a/launch_testing_ros/package.xml
+++ b/launch_testing_ros/package.xml
@@ -23,6 +23,7 @@
ament_copyright
ament_flake8
ament_pep257
+ ament_xmllint
python3-pytest
std_msgs
diff --git a/launch_testing_ros/test/test_xmllint.py b/launch_testing_ros/test/test_xmllint.py
new file mode 100644
index 00000000..f46285e7
--- /dev/null
+++ b/launch_testing_ros/test/test_xmllint.py
@@ -0,0 +1,23 @@
+# Copyright 2019 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_xmllint.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.xmllint
+def test_xmllint():
+ rc = main(argv=[])
+ assert rc == 0, 'Found errors'
diff --git a/ros2launch/package.xml b/ros2launch/package.xml
index ced0d234..f905dc17 100644
--- a/ros2launch/package.xml
+++ b/ros2launch/package.xml
@@ -19,11 +19,11 @@
Michel Hidalgo
William Woodall
- ament_index_python
- launch
- launch_ros
- ros2cli
- ros2pkg
+ ament_index_python
+ launch
+ launch_ros
+ ros2cli
+ ros2pkg
launch_xml
@@ -32,6 +32,7 @@
ament_copyright
ament_flake8
ament_pep257
+ ament_xmllint
python3-pytest
launch_frontend_packages
diff --git a/ros2launch/test/test_xmllint.py b/ros2launch/test/test_xmllint.py
new file mode 100644
index 00000000..f46285e7
--- /dev/null
+++ b/ros2launch/test/test_xmllint.py
@@ -0,0 +1,23 @@
+# Copyright 2019 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_xmllint.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.xmllint
+def test_xmllint():
+ rc = main(argv=[])
+ assert rc == 0, 'Found errors'
diff --git a/test_launch_ros/package.xml b/test_launch_ros/package.xml
index 9772e3da..f81881e9 100644
--- a/test_launch_ros/package.xml
+++ b/test_launch_ros/package.xml
@@ -20,6 +20,7 @@
ament_copyright
ament_flake8
ament_pep257
+ ament_xmllint
builtin_interfaces
composition
demo_nodes_py
diff --git a/test_launch_ros/test/test_xmllint.py b/test_launch_ros/test/test_xmllint.py
new file mode 100644
index 00000000..f46285e7
--- /dev/null
+++ b/test_launch_ros/test/test_xmllint.py
@@ -0,0 +1,23 @@
+# Copyright 2019 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_xmllint.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.xmllint
+def test_xmllint():
+ rc = main(argv=[])
+ assert rc == 0, 'Found errors'