Skip to content

Commit

Permalink
Fixed tests that catch runtime errors, check for replan counts instead
Browse files Browse the repository at this point in the history
Signed-off-by: Aaron Chong <aaronchongth@gmail.com>
  • Loading branch information
aaronchongth committed Jan 7, 2025
1 parent 69195fe commit 46f1616
Show file tree
Hide file tree
Showing 2 changed files with 32 additions and 122 deletions.
62 changes: 9 additions & 53 deletions free_fleet_adapter/tests/integration/test_nav1_robot_adapter.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

from free_fleet_adapter.nav1_robot_adapter import Nav1RobotAdapter
import rclpy
import rmf_adapter.easy_full_control as rmf_easy
from tf2_ros import Buffer

import zenoh
Expand Down Expand Up @@ -118,45 +117,6 @@ def test_robot_battery_soc(self):
battery_soc = robot_adapter.get_battery_soc()
assert math.isclose(battery_soc, 1.0)

def test_robot_unable_to_update(self):
tf_buffer = Buffer()

robot_adapter = Nav1RobotAdapter(
name='nav1_tb3',
configuration=None,
robot_config_yaml={
'initial_map': 'L1',
},
node=self.node,
zenoh_session=self.zenoh_session,
fleet_handle=None,
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

able_to_update = False
try:
robot_adapter.update(
rmf_easy.RobotState(
'L1',
[0.0, 0.0, 0.0],
1.0
)
)
able_to_update = True
except RuntimeError:
able_to_update = False
assert not able_to_update

def test_idle_robot_navigate_is_done(self):
tf_buffer = Buffer()

Expand Down Expand Up @@ -237,19 +197,15 @@ def test_robot_handle_navigate_to_invalid_map(self):

assert robot_exists

able_to_handle_navigate = False
try:
robot_adapter._handle_navigate_to_pose(
'invalid_map',
0.0,
1.0,
2.0,
0.0
)
able_to_handle_navigate = True
except RuntimeError:
able_to_handle_navigate = False
assert not able_to_handle_navigate
prev_replan_count = robot_adapter.replan_counts
robot_adapter._handle_navigate_to_pose(
'invalid_map',
0.0,
1.0,
2.0,
0.0
)
assert robot_adapter.replan_counts == prev_replan_count + 1

def test_robot_handle_navigate_to_pose(self):
tf_buffer = Buffer()
Expand Down
92 changes: 23 additions & 69 deletions free_fleet_adapter/tests/integration/test_nav2_robot_adapter.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

from free_fleet_adapter.nav2_robot_adapter import Nav2RobotAdapter
import rclpy
import rmf_adapter.easy_full_control as rmf_easy
from tf2_ros import Buffer

import zenoh
Expand Down Expand Up @@ -108,35 +107,6 @@ def test_robot_battery_soc(self):
battery_soc = robot_adapter.get_battery_soc()
assert math.isclose(battery_soc, 1.0)

def test_robot_unable_to_update(self):
tf_buffer = Buffer()

robot_adapter = Nav2RobotAdapter(
name='nav2_tb3',
configuration=None,
robot_config_yaml={
'initial_map': 'L1',
},
node=self.node,
zenoh_session=self.zenoh_session,
fleet_handle=None,
tf_buffer=tf_buffer
)

able_to_update = False
try:
robot_adapter.update(
rmf_easy.RobotState(
'L1',
[0.0, 0.0, 0.0],
1.0
)
)
able_to_update = True
except RuntimeError:
able_to_update = False
assert not able_to_update

def test_idle_robot_navigate_is_done(self):
tf_buffer = Buffer()

Expand Down Expand Up @@ -187,19 +157,15 @@ def test_robot_handle_navigate_to_invalid_map(self):
tf_buffer=tf_buffer
)

able_to_handle_navigate = False
try:
robot_adapter._handle_navigate_to_pose(
'invalid_map',
0.0,
1.0,
2.0,
0.0
)
able_to_handle_navigate = True
except RuntimeError:
able_to_handle_navigate = False
assert not able_to_handle_navigate
prev_replan_count = robot_adapter.replan_counts
robot_adapter._handle_navigate_to_pose(
'invalid_map',
0.0,
1.0,
2.0,
0.0
)
assert robot_adapter.replan_counts == prev_replan_count + 1

def test_robot_handle_navigate_to_pose(self):
tf_buffer = Buffer()
Expand All @@ -216,19 +182,13 @@ def test_robot_handle_navigate_to_pose(self):
tf_buffer=tf_buffer
)

able_to_handle_navigate = False
try:
robot_adapter._handle_navigate_to_pose(
'L1',
-0.395,
-0.606,
0.0,
0.0
)
able_to_handle_navigate = True
except RuntimeError:
able_to_handle_navigate = False
assert able_to_handle_navigate
robot_adapter._handle_navigate_to_pose(
'L1',
-0.395,
-0.606,
0.0,
0.0
)
time.sleep(5)
assert robot_adapter._is_navigation_done()

Expand All @@ -247,19 +207,13 @@ def test_robot_stop_navigate(self):
tf_buffer=tf_buffer
)

able_to_handle_navigate = False
try:
robot_adapter._handle_navigate_to_pose(
'L1',
1.808,
0.503,
0.0,
0.0
)
able_to_handle_navigate = True
except RuntimeError:
able_to_handle_navigate = False
assert able_to_handle_navigate
robot_adapter._handle_navigate_to_pose(
'L1',
1.808,
0.503,
0.0,
0.0
)
assert not robot_adapter._is_navigation_done()
time.sleep(1)
robot_adapter._handle_stop_navigation()
Expand Down

0 comments on commit 46f1616

Please sign in to comment.