diff --git a/example_1/CMakeLists.txt b/example_1/CMakeLists.txt
index ef7ca3ecd..3ceb77a8c 100644
--- a/example_1/CMakeLists.txt
+++ b/example_1/CMakeLists.txt
@@ -56,6 +56,10 @@ install(
DIRECTORY bringup/launch bringup/config
DESTINATION share/ros2_control_demo_example_1
)
+install(
+ DIRECTORY test
+ DESTINATION share/ros2_control_demo_example_1
+)
install(TARGETS ros2_control_demo_example_1
EXPORT export_ros2_control_demo_example_1
ARCHIVE DESTINATION lib
@@ -64,9 +68,13 @@ install(TARGETS ros2_control_demo_example_1
)
if(BUILD_TESTING)
- find_package(ament_cmake_gtest REQUIRED)
+ find_package(ament_cmake_pytest REQUIRED)
+
+ ament_add_pytest_test(example_1_urdf_xacro test/test_urdf_xacro.py)
+ ament_add_pytest_test(view_example_1_launch test/test_view_robot_launch.py)
endif()
+
## EXPORTS
ament_export_targets(export_ros2_control_demo_example_1 HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
diff --git a/example_1/package.xml b/example_1/package.xml
index 8513ca3ee..141351687 100644
--- a/example_1/package.xml
+++ b/example_1/package.xml
@@ -33,7 +33,11 @@
rviz2
xacro
- ament_cmake_gtest
+ ament_cmake_pytest
+ launch_testing_ament_cmake
+ launch_testing_ros
+ liburdfdom-tools
+ xacro
ament_cmake
diff --git a/example_1/test/test_urdf_xacro.py b/example_1/test/test_urdf_xacro.py
new file mode 100644
index 000000000..03d9a5a3c
--- /dev/null
+++ b/example_1/test/test_urdf_xacro.py
@@ -0,0 +1,77 @@
+# Copyright (c) 2022 FZI Forschungszentrum Informatik
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+#
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+#
+# * Neither the name of the {copyright_holder} nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+# Author: Lukas Sackewitz
+
+import os
+import shutil
+import subprocess
+import tempfile
+
+from ament_index_python.packages import get_package_share_directory
+
+
+def test_urdf_xacro():
+ # General Arguments
+ description_package = "ros2_control_demo_example_1"
+ description_file = "rrbot.urdf.xacro"
+
+ description_file_path = os.path.join(
+ get_package_share_directory(description_package), "urdf", description_file
+ )
+
+ (_, tmp_urdf_output_file) = tempfile.mkstemp(suffix=".urdf")
+
+ # Compose `xacro` and `check_urdf` command
+ xacro_command = (
+ f"{shutil.which('xacro')}" f" {description_file_path}" f" > {tmp_urdf_output_file}"
+ )
+ check_urdf_command = f"{shutil.which('check_urdf')} {tmp_urdf_output_file}"
+
+ # Try to call processes but finally remove the temp file
+ try:
+ xacro_process = subprocess.run(
+ xacro_command, stdout=subprocess.PIPE, stderr=subprocess.PIPE, shell=True
+ )
+
+ assert xacro_process.returncode == 0, " --- XACRO command failed ---"
+
+ check_urdf_process = subprocess.run(
+ check_urdf_command, stdout=subprocess.PIPE, stderr=subprocess.PIPE, shell=True
+ )
+
+ assert (
+ check_urdf_process.returncode == 0
+ ), "\n --- URDF check failed! --- \nYour xacro does not unfold into a proper urdf robot description. Please check your xacro file."
+
+ finally:
+ os.remove(tmp_urdf_output_file)
+
+
+if __name__ == "__main__":
+ test_urdf_xacro()
diff --git a/example_1/test/test_view_robot_launch.py b/example_1/test/test_view_robot_launch.py
new file mode 100644
index 000000000..3fc5818b4
--- /dev/null
+++ b/example_1/test/test_view_robot_launch.py
@@ -0,0 +1,54 @@
+# Copyright (c) 2022 FZI Forschungszentrum Informatik
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+#
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+#
+# * Neither the name of the {copyright_holder} nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+# Author: Lukas Sackewitz
+
+import os
+import pytest
+
+from ament_index_python.packages import get_package_share_directory
+from launch import LaunchDescription
+from launch.actions import IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch_testing.actions import ReadyToTest
+
+
+# Executes the given launch file and checks if all nodes can be started
+@pytest.mark.rostest
+def generate_test_description():
+ launch_include = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(
+ get_package_share_directory("ros2_control_demo_example_1"),
+ "description/launch/view_robot.launch.py",
+ )
+ ),
+ launch_arguments={"gui": "true"}.items(),
+ )
+
+ return LaunchDescription([launch_include, ReadyToTest()])