1919from action_msgs .msg import GoalStatus
2020from geometry_msgs .msg import TransformStamped , Twist , TwistStamped
2121from launch import LaunchDescription
22+ # from launch.actions import SetEnvironmentVariable
2223from launch_ros .actions import Node
2324import launch_testing
25+ import launch_testing .actions
26+ import launch_testing .asserts
27+ import launch_testing .markers
28+ import launch_testing .util
2429from nav2_msgs .action import DockRobot , NavigateToPose , UndockRobot
2530import pytest
2631import rclpy
27- from rclpy .action import ActionClient , ActionServer
32+ from rclpy .action .client import ActionClient
33+ from rclpy .action .server import ActionServer
2834from sensor_msgs .msg import BatteryState
2935from tf2_ros import TransformBroadcaster
3036
3137
3238# This test can be run standalone with:
3339# python3 -u -m pytest test_docking_server.py -s
3440
41+ # If python3-flaky is installed, you can run the test multiple times to
42+ # try to identify flaky ness.
43+ # python3 -u -m pytest --force-flaky --min-passes 3 --max-runs 5 -s -v test_docking_server.py
44+
3545@pytest .mark .rostest
46+ # @pytest.mark.flaky
47+ # @pytest.mark.flaky(max_runs=5, min_passes=3)
3648def generate_test_description ():
3749
3850 return LaunchDescription ([
51+ # SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
52+ # SetEnvironmentVariable('RCUTILS_LOGGING_USE_STDOUT', '1'),
3953 Node (
4054 package = 'opennav_docking' ,
4155 executable = 'opennav_docking' ,
@@ -74,21 +88,26 @@ class TestDockingServer(unittest.TestCase):
7488 @classmethod
7589 def setUpClass (cls ):
7690 rclpy .init ()
77- # Latest odom -> base_link
78- cls .x = 0.0
79- cls .y = 0.0
80- cls .theta = 0.0
81- # Track charge state
82- cls .is_charging = False
83- # Latest command velocity
84- cls .command = Twist ()
85- cls .node = rclpy .create_node ('test_docking_server' )
8691
8792 @classmethod
8893 def tearDownClass (cls ):
89- cls .node .destroy_node ()
9094 rclpy .shutdown ()
9195
96+ def setUp (self ):
97+ # Create a ROS node for tests
98+ # Latest odom -> base_link
99+ self .x = 0.0
100+ self .y = 0.0
101+ self .theta = 0.0
102+ # Track charge state
103+ self .is_charging = False
104+ # Latest command velocity
105+ self .command = Twist ()
106+ self .node = rclpy .create_node ('test_docking_server' )
107+
108+ def tearDown (self ):
109+ self .node .destroy_node ()
110+
92111 def command_velocity_callback (self , msg ):
93112 self .node .get_logger ().info ('Command: %f %f' % (msg .twist .linear .x , msg .twist .angular .z ))
94113 self .command = msg .twist
@@ -175,24 +194,32 @@ def test_docking_server(self):
175194 'navigate_to_pose' ,
176195 self .nav_execute_callback )
177196
178- # Spin once so that TF is published
179- rclpy .spin_once (self .node , timeout_sec = 0.1 )
197+ # Publish transform
198+ self .publish ()
199+
200+ # Run for 1 seconds to allow tf to propogate
201+ for _ in range (10 ):
202+ rclpy .spin_once (self .node , timeout_sec = 0.1 )
203+ time .sleep (0.1 )
180204
181205 # Test docking action
182206 self .action_result = []
183- self .dock_action_client .wait_for_server (timeout_sec = 5.0 )
207+ assert self .dock_action_client .wait_for_server (timeout_sec = 5.0 ), \
208+ 'dock_robot service not available'
209+
184210 goal = DockRobot .Goal ()
185211 goal .use_dock_id = True
186212 goal .dock_id = 'test_dock'
187213 future = self .dock_action_client .send_goal_async (
188214 goal , feedback_callback = self .action_feedback_callback )
189215 rclpy .spin_until_future_complete (self .node , future )
190216 self .goal_handle = future .result ()
191- assert self .goal_handle .accepted
217+ assert self .goal_handle is not None , 'goal_handle should not be None'
218+ assert self .goal_handle .accepted , 'goal_handle not accepted'
192219 result_future_original = self .goal_handle .get_result_async ()
193220
194221 # Run for 2 seconds
195- for i in range (20 ):
222+ for _ in range (20 ):
196223 rclpy .spin_once (self .node , timeout_sec = 0.1 )
197224 time .sleep (0.1 )
198225
@@ -201,7 +228,8 @@ def test_docking_server(self):
201228 goal , feedback_callback = self .action_feedback_callback )
202229 rclpy .spin_until_future_complete (self .node , future )
203230 self .goal_handle = future .result ()
204- assert self .goal_handle .accepted
231+ assert self .goal_handle is not None , 'goal_handle should not be None'
232+ assert self .goal_handle .accepted , 'goal_handle not accepted'
205233 result_future = self .goal_handle .get_result_async ()
206234 rclpy .spin_until_future_complete (self .node , result_future )
207235 self .action_result .append (result_future .result ())
@@ -216,7 +244,7 @@ def test_docking_server(self):
216244 self .node .get_logger ().info ('Goal preempted' )
217245
218246 # Run for 0.5 seconds
219- for i in range (5 ):
247+ for _ in range (5 ):
220248 rclpy .spin_once (self .node , timeout_sec = 0.1 )
221249 time .sleep (0.1 )
222250
@@ -230,7 +258,8 @@ def test_docking_server(self):
230258 goal , feedback_callback = self .action_feedback_callback )
231259 rclpy .spin_until_future_complete (self .node , future )
232260 self .goal_handle = future .result ()
233- assert self .goal_handle .accepted
261+ assert self .goal_handle is not None , 'goal_handle should not be None'
262+ assert self .goal_handle .accepted , 'goal_handle not accepted'
234263 result_future = self .goal_handle .get_result_async ()
235264 rclpy .spin_until_future_complete (self .node , result_future )
236265 self .action_result .append (result_future .result ())
@@ -247,10 +276,19 @@ def test_docking_server(self):
247276 future = self .undock_action_client .send_goal_async (goal )
248277 rclpy .spin_until_future_complete (self .node , future )
249278 self .goal_handle = future .result ()
250- assert self .goal_handle .accepted
279+ assert self .goal_handle is not None , 'goal_handle should not be None'
280+ assert self .goal_handle .accepted , 'goal_handle not accepted'
251281 result_future = self .goal_handle .get_result_async ()
252282 rclpy .spin_until_future_complete (self .node , result_future )
253283 self .action_result .append (result_future .result ())
254284
255285 self .assertEqual (self .action_result [3 ].status , GoalStatus .STATUS_SUCCEEDED )
256286 self .assertTrue (self .action_result [3 ].result .success )
287+
288+
289+ @launch_testing .post_shutdown_test ()
290+ class TestProcessOutput (unittest .TestCase ):
291+
292+ def test_exit_code (self , proc_info ):
293+ # Check that all processes in the launch exit with code 0
294+ launch_testing .asserts .assertExitCodes (proc_info )
0 commit comments