Skip to content

Commit

Permalink
Fix tests
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Nov 28, 2024
1 parent 6a337d5 commit 3771540
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 17 deletions.
22 changes: 12 additions & 10 deletions rosbot_bringup/test/test_multirobot.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
import pytest
import rclpy
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.actions import IncludeLaunchDescription, TimerAction
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
Expand All @@ -31,7 +31,7 @@
def generate_test_description():
rosbot_bringup = FindPackageShare("rosbot_bringup")
actions = []
for robot_name in robot_names:
for i in range(len(robot_names)):
bringup_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
Expand All @@ -45,26 +45,28 @@ def generate_test_description():
launch_arguments={
"use_sim": "False",
"mecanum": "False",
"namespace": robot_name,
"namespace": robot_names[i],
}.items(),
)

actions.append(bringup_launch)
delayed_bringup = TimerAction(period=5.0*i, actions=[bringup_launch])
actions.append(delayed_bringup)

return LaunchDescription(actions)


@pytest.mark.launch(fixture=generate_test_description)
def test_multirobot_bringup_startup_success():
rclpy.init()
try:
for robot_name in robot_names:

for robot_name in robot_names:
rclpy.init()
try:
node = BringupTestNode("test_bringup", namespace=robot_name)
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
readings_data_test(node)
readings_data_test(node, robot_name)

finally:
rclpy.shutdown()
finally:
rclpy.shutdown()
8 changes: 1 addition & 7 deletions rosbot_bringup/test/test_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,12 +100,6 @@ def publish_fake_hardware_messages(self):


def wait_for_all_events(events, timeout):
"""
Wait for all specified events to be set within a given timeout.
:param events: List of Event objects to wait for.
:param timeout: Maximum time (in seconds) to wait.
:return: (bool, list) where the first value indicates success, and the second is a list of indices of events that were not set.
"""
start_time = time.time()
while time.time() - start_time < timeout:
if all(event.is_set() for event in events):
Expand All @@ -132,7 +126,7 @@ def readings_data_test(node, robot_name="ROSbot"):
"EKF Odometry",
]

msgs_received_flag, not_set_indices = wait_for_all_events(events, timeout=30.0)
msgs_received_flag, not_set_indices = wait_for_all_events(events, timeout=20.0)

if not msgs_received_flag:
not_set_event_names = [event_names[i] for i in not_set_indices]
Expand Down

0 comments on commit 3771540

Please sign in to comment.