Skip to content

Commit

Permalink
Add launch tests to all examples (#540)
Browse files Browse the repository at this point in the history
* Add test for ex1

* Add test for ex2

* Add test for ex3

* Add test for ex4

* Add missing dependency

* Deactivate GUI

* Add test for ex5

* Add act stuff to gitignore

* Deactivate gui in tests

* Reduce update rate to avoid clogging the log

* Use set instead of list

* Add test for ex6

* Fix xacro macros and add gui launch argument

* Add test for example_7

* Add test for example_8

* Add test for example_9

* Add test for example_10

* Add test for example_11

* Add test for example_12

* Add test for example_14

* Update test for example_15

* Add test for example_15 multi_cm

* Add missing dependency

* Add missing dependency for ex4+ex5

* Robustify tests and reuse methos for launch_testing

* Fix dependencies

* Use a set to compare the joint names

* Reorder controller spawners

* Activate assertExitCodes tests

* Deactivate failing tests for example_15

* Increase timeout for example_10

* Add backward_ros everywhere

* Add error output and update includes

* Revert "Activate assertExitCodes tests"

This reverts commit fe28c67.

* Add missing import

* Update ros2_control_demo_testing/package.xml

Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>

* Reuse check_node_running

* Try to robustify example_14 tests

---------

Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>
  • Loading branch information
christophfroehlich and saikishor authored Jul 30, 2024
1 parent f92cc21 commit 0ba16d2
Show file tree
Hide file tree
Showing 77 changed files with 1,948 additions and 169 deletions.
8 changes: 2 additions & 6 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,6 +1,2 @@
.kdev4/


*~
*.kate-swp
*.kdev4
.ccache
.work
2 changes: 2 additions & 0 deletions example_1/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
)

# find dependencies
find_package(backward_ros REQUIRED)
find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
Expand Down Expand Up @@ -66,6 +67,7 @@ if(BUILD_TESTING)

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)
ament_add_pytest_test(run_example_1_launch test/test_rrbot_launch.py)
endif()


Expand Down
13 changes: 7 additions & 6 deletions example_1/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,20 +105,21 @@ def generate_launch_description():
)
)

# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
target_action=robot_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
joint_state_broadcaster_spawner,
robot_controller_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
]

return LaunchDescription(declared_arguments + nodes)
3 changes: 2 additions & 1 deletion example_1/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
<depend>hardware_interface</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
Expand All @@ -34,9 +35,9 @@
<exec_depend>xacro</exec_depend>

<test_depend>ament_cmake_pytest</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>launch_testing_ros</test_depend>
<test_depend>liburdfdom-tools</test_depend>
<test_depend>ros2_control_demo_testing</test_depend>
<test_depend>xacro</test_depend>

<export>
Expand Down
99 changes: 99 additions & 0 deletions example_1/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
# Copyright (c) 2024 AIT - Austrian Institute of Technology GmbH
#
# 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: Christoph Froehlich

import os
import pytest
import unittest

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

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# 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"),
"launch/rrbot.launch.py",
)
),
launch_arguments={"gui": "False"}.items(),
)

return LaunchDescription([launch_include, ReadyToTest()])


# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):

def setUp(self):
rclpy.init()
self.node = Node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

cnames = ["forward_position_controller", "joint_state_broadcaster"]

check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
check_if_js_published("/joint_states", ["joint1", "joint2"])


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
# @launch_testing.post_shutdown_test()
# # These tests are run after the processes in generate_test_description() have shutdown.
# class TestDescriptionCraneShutdown(unittest.TestCase):

# def test_exit_codes(self, proc_info):
# """Check if the processes exited normally."""
# launch_testing.asserts.assertExitCodes(proc_info)
2 changes: 2 additions & 0 deletions example_10/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
)

# find dependencies
find_package(backward_ros REQUIRED)
find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
Expand Down Expand Up @@ -77,6 +78,7 @@ if(BUILD_TESTING)

ament_add_pytest_test(example_10_urdf_xacro test/test_urdf_xacro.py)
ament_add_pytest_test(view_example_10_launch test/test_view_robot_launch.py)
ament_add_pytest_test(run_example_10_launch test/test_rrbot_launch.py)
endif()

## EXPORTS
Expand Down
21 changes: 14 additions & 7 deletions example_10/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,20 +93,27 @@ def generate_launch_description():
arguments=["gpio_controller", "-c", "/controller_manager"],
)

# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_gpio_after_robot_controller_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
target_action=robot_controller_spawner,
on_exit=[gpio_controller_spawner],
)
)
delay_joint_state_broadcaster_after_gpio_controller_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=gpio_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
joint_state_broadcaster_spawner,
gpio_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
robot_controller_spawner,
delay_gpio_after_robot_controller_spawner,
delay_joint_state_broadcaster_after_gpio_controller_spawner,
]

return LaunchDescription(declared_arguments + nodes)
4 changes: 2 additions & 2 deletions example_10/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
<depend>hardware_interface</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
Expand All @@ -32,11 +33,10 @@
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>launch_testing_ros</test_depend>
<test_depend>liburdfdom-tools</test_depend>
<test_depend>ros2_control_demo_testing</test_depend>
<test_depend>xacro</test_depend>

<export>
Expand Down
104 changes: 104 additions & 0 deletions example_10/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
# Copyright (c) 2024 AIT - Austrian Institute of Technology GmbH
#
# 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: Christoph Froehlich

import os
import pytest
import unittest

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

import launch_testing
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# This function specifies the processes to be run for our test
# The ReadyToTest action waits for 15 second by default for the processes to
# start, if processes take more time an error is thrown. We use decorator here
# to provide timeout duration of 20 second so that processes that take longer than
# 15 seconds can start up.
@pytest.mark.launch_test
@launch_testing.ready_to_test_action_timeout(20)
def generate_test_description():
launch_include = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(
get_package_share_directory("ros2_control_demo_example_10"),
"launch/rrbot.launch.py",
)
),
launch_arguments={"gui": "false"}.items(),
)

return LaunchDescription([launch_include, ReadyToTest()])


# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):

def setUp(self):
rclpy.init()
self.node = Node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

cnames = ["forward_position_controller", "gpio_controller", "joint_state_broadcaster"]

check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
check_if_js_published("/joint_states", ["joint1", "joint2"])


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
# @launch_testing.post_shutdown_test()
# # These tests are run after the processes in generate_test_description() have shutdown.
# class TestDescriptionCraneShutdown(unittest.TestCase):

# def test_exit_codes(self, proc_info):
# """Check if the processes exited normally."""
# launch_testing.asserts.assertExitCodes(proc_info)
2 changes: 2 additions & 0 deletions example_11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
)

# find dependencies
find_package(backward_ros REQUIRED)
find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
Expand Down Expand Up @@ -66,6 +67,7 @@ if(BUILD_TESTING)

ament_add_pytest_test(example_11_urdf_xacro test/test_urdf_xacro.py)
ament_add_pytest_test(view_example_11_launch test/test_view_robot_launch.py)
ament_add_pytest_test(run_example_11_launch test/test_carlikebot_launch.py)
endif()

## EXPORTS
Expand Down
13 changes: 7 additions & 6 deletions example_11/bringup/launch/carlikebot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,21 +125,22 @@ def generate_launch_description():
)
)

# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
# Delay start of joint_state_broadcaster after `robot_controller`
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_bicycle_controller_spawner],
target_action=robot_bicycle_controller_spawner,
on_exit=[joint_state_broadcaster_spawner],
)
)

nodes = [
control_node,
control_node_remapped,
robot_state_pub_bicycle_node,
joint_state_broadcaster_spawner,
robot_bicycle_controller_spawner,
delay_joint_state_broadcaster_after_robot_controller_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(declared_arguments + nodes)
Loading

0 comments on commit 0ba16d2

Please sign in to comment.