Skip to content

Commit

Permalink
Replace polling transform and pose tests with a 2 second wait for ini…
Browse files Browse the repository at this point in the history
…tialization before checks

Signed-off-by: Aaron Chong <aaronchongth@gmail.com>
  • Loading branch information
aaronchongth committed Jan 7, 2025
1 parent cccb403 commit e3a5a1f
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 126 deletions.
96 changes: 24 additions & 72 deletions free_fleet_adapter/tests/integration/test_nav1_robot_adapter.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,15 +54,9 @@ def test_non_existent_robot_pose(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert not robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is None

def test_robot_pose(self):
tf_buffer = Buffer()
Expand All @@ -79,15 +73,9 @@ def test_robot_pose(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None

def test_robot_battery_soc(self):
tf_buffer = Buffer()
Expand All @@ -104,15 +92,9 @@ def test_robot_battery_soc(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None

battery_soc = robot_adapter.get_battery_soc()
assert math.isclose(battery_soc, 1.0)
Expand All @@ -132,15 +114,9 @@ def test_idle_robot_navigate_is_done(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None
assert robot_adapter._is_navigation_done()

def test_robot_stop_without_command(self):
Expand All @@ -158,15 +134,9 @@ def test_robot_stop_without_command(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None
assert robot_adapter.execution is None
robot_adapter.stop(None)
assert robot_adapter.execution is None
Expand All @@ -187,15 +157,9 @@ def test_robot_handle_navigate_to_invalid_map(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None

prev_replan_count = robot_adapter.replan_counts
robot_adapter._handle_navigate_to_pose(
Expand All @@ -222,15 +186,9 @@ def test_robot_handle_navigate_to_pose(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None

robot_adapter._handle_navigate_to_pose(
'L1',
Expand Down Expand Up @@ -259,15 +217,9 @@ def test_robot_stop_navigate(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None

robot_adapter._handle_navigate_to_pose(
'L1',
Expand Down
24 changes: 6 additions & 18 deletions free_fleet_adapter/tests/integration/test_nav1_tf_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,15 +45,9 @@ def test_tf_does_not_exist(self):
'missing_nav1_tb3', self.zenoh_session, tf_buffer, self.node
)

transform_exists = False
for i in range(10):
transform = tf_handler.get_transform()
if transform is not None:
transform_exists = True
break
time.sleep(1)

assert not transform_exists
time.sleep(2)
transform = tf_handler.get_transform()
assert transform is None

def test_tf_exists(self):
tf_buffer = Buffer()
Expand All @@ -62,12 +56,6 @@ def test_tf_exists(self):
'nav1_tb3', self.zenoh_session, tf_buffer, self.node
)

transform_exists = False
for i in range(10):
transform = tf_handler.get_transform()
if transform is not None:
transform_exists = True
break
time.sleep(1)

assert transform_exists
time.sleep(2)
transform = tf_handler.get_transform()
assert transform is not None
24 changes: 6 additions & 18 deletions free_fleet_adapter/tests/integration/test_nav2_robot_adapter.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,15 +54,9 @@ def test_non_existent_robot_pose(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert not robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is None

def test_robot_pose(self):
tf_buffer = Buffer()
Expand All @@ -79,15 +73,9 @@ def test_robot_pose(self):
tf_buffer=tf_buffer
)

robot_exists = False
for i in range(10):
transform = robot_adapter.get_pose()
if transform is not None:
robot_exists = True
break
time.sleep(1)

assert robot_exists
time.sleep(2)
transform = robot_adapter.get_pose()
assert transform is not None

def test_robot_battery_soc(self):
tf_buffer = Buffer()
Expand Down
24 changes: 6 additions & 18 deletions free_fleet_adapter/tests/integration/test_nav2_tf_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,15 +45,9 @@ def test_tf_does_not_exist(self):
'missing_nav2_tb3', self.zenoh_session, tf_buffer, self.node
)

transform_exists = False
for i in range(10):
transform = tf_handler.get_transform()
if transform is not None:
transform_exists = True
break
time.sleep(1)

assert not transform_exists
time.sleep(2)
transform = tf_handler.get_transform()
assert transform is None

def test_tf_exists(self):
tf_buffer = Buffer()
Expand All @@ -62,12 +56,6 @@ def test_tf_exists(self):
'nav2_tb3', self.zenoh_session, tf_buffer, self.node
)

transform_exists = False
for i in range(10):
transform = tf_handler.get_transform()
if transform is not None:
transform_exists = True
break
time.sleep(1)

assert transform_exists
time.sleep(2)
transform = tf_handler.get_transform()
assert transform is not None

0 comments on commit e3a5a1f

Please sign in to comment.