Skip to content

Commit 637f818

Browse files
committed
opennav_docking - attempt remove test_docking_server flakeyness
Wait some time for tf to propogate. Allows docking_server time to activate and not reject initial action request. Will try to sleep before assert to allow logs of docking server to be produced before being killed by end of test shutdown due to assert.
1 parent ed40eae commit 637f818

File tree

1 file changed

+50
-6
lines changed

1 file changed

+50
-6
lines changed

nav2_docking/opennav_docking/test/test_docking_server.py

Lines changed: 50 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,12 @@
2424
from nav2_msgs.action import DockRobot, NavigateToPose, UndockRobot
2525
import pytest
2626
import rclpy
27-
from rclpy.action import ActionClient, ActionServer
27+
import rclpy.time
28+
import rclpy.duration
29+
from rclpy.action.client import ActionClient
30+
from rclpy.action.server import ActionServer
2831
from sensor_msgs.msg import BatteryState
29-
from tf2_ros import TransformBroadcaster
32+
from tf2_ros import TransformBroadcaster, Buffer, TransformListener
3033

3134

3235
# This test can be run standalone with:
@@ -142,9 +145,40 @@ def nav_execute_callback(self, goal_handle):
142145
result.error_code = 0
143146
return result
144147

148+
def check_transform(self, timeout_sec, source_frame='odom', target_frame='base_link'):
149+
"""Try to look up the transform we're publishing"""
150+
if self.transform_available:
151+
return True
152+
153+
try:
154+
# Wait for transform to become available with timeout
155+
when = rclpy.time.Time()
156+
transform = self.tf_buffer.lookup_transform(
157+
target_frame,
158+
source_frame,
159+
when,
160+
timeout=rclpy.duration.Duration(seconds=timeout_sec)
161+
)
162+
163+
self.node.get_logger().info('Successfully found transform:')
164+
self.node.get_logger().info(f'Translation: [{transform.transform.translation.x}, '
165+
f'{transform.transform.translation.y}, '
166+
f'{transform.transform.translation.z}]')
167+
self.transform_available = True
168+
except Exception as e:
169+
self.node.get_logger().error(f'Error looking up transform: {str(e)}')
170+
self.transform_available = False
171+
172+
return self.transform_available
173+
145174
def test_docking_server(self):
146175
# Publish TF for odometry
147176
self.tf_broadcaster = TransformBroadcaster(self.node)
177+
# Create tf buffer and listener
178+
self.tf_buffer = Buffer()
179+
self.tf_listener = TransformListener(self.tf_buffer, self.node)
180+
self.transform_available = False
181+
148182

149183
# Create a timer to run "control loop" at 20hz
150184
self.timer = self.node.create_timer(0.05, self.timer_callback)
@@ -175,20 +209,30 @@ def test_docking_server(self):
175209
'navigate_to_pose',
176210
self.nav_execute_callback)
177211

178-
# Spin once so that TF is published
179-
rclpy.spin_once(self.node, timeout_sec=0.1)
212+
# Publish transform
213+
self.publish()
214+
215+
# Run for 2 seconds to allow tf to propogate
216+
for i in range(20):
217+
rclpy.spin_once(self.node, timeout_sec=0.1)
218+
time.sleep(0.1)
219+
220+
assert self.check_transform(timeout_sec=1.0), 'transform not available'
180221

181222
# Test docking action
182223
self.action_result = []
183-
self.dock_action_client.wait_for_server(timeout_sec=5.0)
224+
assert self.dock_action_client.wait_for_server(timeout_sec=5.0), \
225+
'dock_robot service not available'
226+
184227
goal = DockRobot.Goal()
185228
goal.use_dock_id = True
186229
goal.dock_id = 'test_dock'
187230
future = self.dock_action_client.send_goal_async(
188231
goal, feedback_callback=self.action_feedback_callback)
189232
rclpy.spin_until_future_complete(self.node, future)
190233
self.goal_handle = future.result()
191-
assert self.goal_handle.accepted
234+
assert self.goal_handle is not None, 'goal_handle should not be None'
235+
assert self.goal_handle.accepted, 'goal not accepted'
192236
result_future_original = self.goal_handle.get_result_async()
193237

194238
# Run for 2 seconds

0 commit comments

Comments
 (0)