Skip to content

Commit

Permalink
Robustify tests and reuse methos for launch_testing
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jul 26, 2024
1 parent 3d9cce7 commit cde9d2a
Show file tree
Hide file tree
Showing 36 changed files with 296 additions and 421 deletions.
27 changes: 5 additions & 22 deletions example_1/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,9 @@
from launch_testing.actions import ReadyToTest

# import launch_testing.markers
from launch_testing_ros import WaitForTopics
from controller_manager.controller_manager_services import list_controllers
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from ros2_control_demo_testing.test_utils import check_controllers_running, check_if_js_published


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -78,34 +76,19 @@ def tearDown(self):
def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 2.0 and not found:
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"

def test_controller_running(self, proc_output):

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

start = time.time()
found = False
while time.time() - start < 10.0 and not found:
controllers = list_controllers(self.node, "controller_manager", 5.0).controller
assert controllers, "No controllers found!"
for c in controllers:
if c.name == cname and c.state == "active":
found = True
break
assert found, f"{cname} not found!"
check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
wait_for_topics = WaitForTopics([("/joint_states", JointState)], timeout=15.0)
assert wait_for_topics.wait(), "Topic '/joint_states' not found!"
msgs = wait_for_topics.received_messages("/joint_states")
msg = msgs[0]
assert len(msg.name) == 2, "Wrong number of joints in message"
assert set(msg.name) == {"joint1", "joint2"}, "Wrong joint names"
wait_for_topics.shutdown()
check_if_js_published("/joint_states", ["joint1", "joint2"])


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
Expand Down
2 changes: 1 addition & 1 deletion example_10/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,11 @@
<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
29 changes: 4 additions & 25 deletions example_10/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,9 @@
from launch_testing.actions import ReadyToTest

# import launch_testing.markers
from launch_testing_ros import WaitForTopics
from controller_manager.controller_manager_services import list_controllers
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from ros2_control_demo_testing.test_utils import check_controllers_running, check_if_js_published


# This function specifies the processes to be run for our test
Expand Down Expand Up @@ -78,38 +76,19 @@ def tearDown(self):
def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 2.0 and not found:
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"

def test_controller_running(self, proc_output):

cnames = ["forward_position_controller", "gpio_controller", "joint_state_broadcaster"]
found = {cname: False for cname in cnames} # Define 'found' as a dictionary

start = time.time()
while time.time() - start < 10.0 and not all(found.values()):
controllers = list_controllers(self.node, "controller_manager", 5.0).controller
assert controllers, "No controllers found!"
for c in controllers:
for cname in cnames:
if c.name == cname and c.state == "active":
found[cname] = True
break

assert all(
found.values()
), f"Controller(s) not found: {', '.join([cname for cname, is_found in found.items() if not is_found])}"
check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
wait_for_topics = WaitForTopics([("/joint_states", JointState)], timeout=15.0)
assert wait_for_topics.wait(), "Topic '/joint_states' not found!"
msgs = wait_for_topics.received_messages("/joint_states")
msg = msgs[0]
assert len(msg.name) == 2, "Wrong number of joints in message"
assert msg.name == ["joint1", "joint2"], "Wrong joint names"
wait_for_topics.shutdown()
check_if_js_published("/joint_states", ["joint1", "joint2"])


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
Expand Down
7 changes: 6 additions & 1 deletion example_11/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,12 @@
<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>
<build_type>ament_cmake</build_type>
Expand Down
36 changes: 11 additions & 25 deletions example_11/test/test_carlikebot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,9 @@
from launch_testing.actions import ReadyToTest

# import launch_testing.markers
from launch_testing_ros import WaitForTopics
from controller_manager.controller_manager_services import list_controllers
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from ros2_control_demo_testing.test_utils import check_controllers_running, check_if_js_published


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -78,37 +76,25 @@ def tearDown(self):
def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 2.0 and not found:
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"

def test_controller_running(self, proc_output):

cname = "bicycle_steering_controller"
cnames = ["bicycle_steering_controller", "joint_state_broadcaster"]

start = time.time()
found = False
while time.time() - start < 10.0 and not found:
controllers = list_controllers(self.node, "controller_manager", 5.0).controller
assert controllers, "No controllers found!"
for c in controllers:
if c.name == cname and c.state == "active":
found = True
break
assert found, f"{cname} not found!"
check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
wait_for_topics = WaitForTopics([("/joint_states", JointState)], timeout=15.0)
assert wait_for_topics.wait(), "Topic '/joint_states' not found!"
msgs = wait_for_topics.received_messages("/joint_states")
msg = msgs[0]
assert len(msg.name) == 2, "Wrong number of joints in message"
assert msg.name == [
"virtual_front_wheel_joint",
"virtual_rear_wheel_joint",
], "Wrong joint names"
wait_for_topics.shutdown()
check_if_js_published(
"/joint_states",
[
"virtual_front_wheel_joint",
"virtual_rear_wheel_joint",
],
)


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
Expand Down
2 changes: 1 addition & 1 deletion example_12/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,11 @@
<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
54 changes: 7 additions & 47 deletions example_12/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,9 @@
from launch_testing.actions import ReadyToTest

# import launch_testing.markers
from launch_testing_ros import WaitForTopics
from controller_manager.controller_manager_services import list_controllers
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from ros2_control_demo_testing.test_utils import check_controllers_running, check_if_js_published


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -79,7 +77,7 @@ def tearDown(self):
def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 2.0 and not found:
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
Expand All @@ -91,30 +89,11 @@ def test_controller_running(self, proc_output):
"joint2_position_controller",
"joint_state_broadcaster",
]
found = {cname: False for cname in cnames} # Define 'found' as a dictionary

start = time.time()
while time.time() - start < 10.0 and not all(found.values()):
controllers = list_controllers(self.node, "controller_manager", 5.0).controller
assert controllers, "No controllers found!"
for c in controllers:
for cname in cnames:
if c.name == cname and c.state == "active":
found[cname] = True
break

assert all(
found.values()
), f"Controller(s) not found: {', '.join([cname for cname, is_found in found.items() if not is_found])}"
check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
wait_for_topics = WaitForTopics([("/joint_states", JointState)], timeout=15.0)
assert wait_for_topics.wait(), "Topic '/joint_states' not found!"
msgs = wait_for_topics.received_messages("/joint_states")
msg = msgs[0]
assert len(msg.name) == 2, "Wrong number of joints in message"
assert msg.name == ["joint1", "joint2"], "Wrong joint names"
wait_for_topics.shutdown()
check_if_js_published("/joint_states", ["joint1", "joint2"])


# This is our second test fixture. Each method is a test case.
Expand All @@ -141,7 +120,7 @@ def tearDown(self):
def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 2.0 and not found:
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
Expand All @@ -155,30 +134,11 @@ def test_controller_running(self, proc_output):
"position_controller",
"forward_position_controller",
]
found = {cname: False for cname in cnames} # Define 'found' as a dictionary

start = time.time()
while time.time() - start < 10.0 and not all(found.values()):
controllers = list_controllers(self.node, "controller_manager", 5.0).controller
assert controllers, "No controllers found!"
for c in controllers:
for cname in cnames:
if c.name == cname and c.state == "active":
found[cname] = True
break

assert all(
found.values()
), f"Controller(s) not found: {', '.join([cname for cname, is_found in found.items() if not is_found])}"
check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
wait_for_topics = WaitForTopics([("/joint_states", JointState)], timeout=15.0)
assert wait_for_topics.wait(), "Topic '/joint_states' not found!"
msgs = wait_for_topics.received_messages("/joint_states")
msg = msgs[0]
assert len(msg.name) == 2, "Wrong number of joints in message"
assert msg.name == ["joint1", "joint2"], "Wrong joint names"
wait_for_topics.shutdown()
check_if_js_published("/joint_states", ["joint1", "joint2"])


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
Expand Down
2 changes: 1 addition & 1 deletion example_14/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,11 @@
<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
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,9 @@
from launch_testing.actions import ReadyToTest

# import launch_testing.markers
from launch_testing_ros import WaitForTopics
from controller_manager.controller_manager_services import list_controllers
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from ros2_control_demo_testing.test_utils import check_controllers_running, check_if_js_published


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -78,34 +76,22 @@ def tearDown(self):
def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 2.0 and not found:
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"

def test_controller_running(self, proc_output):

cname = "forward_velocity_controller"
cnames = [
"forward_velocity_controller",
"joint_state_broadcaster",
]

start = time.time()
found = False
while time.time() - start < 10.0 and not found:
controllers = list_controllers(self.node, "controller_manager", 5.0).controller
assert controllers, "No controllers found!"
for c in controllers:
if c.name == cname and c.state == "active":
found = True
break
assert found, f"{cname} not found!"
check_controllers_running(self.node, cnames)

def test_check_if_msgs_published(self):
wait_for_topics = WaitForTopics([("/joint_states", JointState)], timeout=15.0)
assert wait_for_topics.wait(), "Topic '/joint_states' not found!"
msgs = wait_for_topics.received_messages("/joint_states")
msg = msgs[0]
assert len(msg.name) == 2, "Wrong number of joints in message"
assert set(msg.name) == {"joint1", "joint2"}, "Wrong joint names"
wait_for_topics.shutdown()
check_if_js_published("/joint_states", ["joint1", "joint2"])


# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
Expand Down
1 change: 0 additions & 1 deletion example_15/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@ install(
)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_pytest REQUIRED)

ament_add_pytest_test(test_rrbot_namespace_launch test/test_rrbot_namespace_launch.py)
Expand Down
Loading

0 comments on commit cde9d2a

Please sign in to comment.