Skip to content

Commit 06f1a37

Browse files
committed
New image builds and new tests
Signed-off-by: Aaron Chong <[email protected]>
1 parent e873a8f commit 06f1a37

File tree

5 files changed

+137
-39
lines changed

5 files changed

+137
-39
lines changed

.github/docker/minimal-nav1-bringup/Dockerfile

+6-1
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,13 @@ RUN mkdir -p /tb3 && cd /tb3 \
99

1010
ENV TURTLEBOT3_MODEL=burger
1111

12+
# Modify existing launch file to add initial pose
13+
RUN cd /tb3 \
14+
&& curl --output turtlebot3_navigation.launch "https://raw.githubusercontent.com/ROBOTIS-GIT/turtlebot3/refs/heads/noetic-devel/turtlebot3_navigation/launch/turtlebot3_navigation.launch" \
15+
&& sed -z 's|amcl.launch"/>|amcl.launch"><arg name="initial_pose_x" value="-2.0"/><arg name="initial_pose_y" value="-0.5"/></include>|' turtlebot3_navigation.launch > turtlebot3_navigation_edited.launch
16+
1217
RUN rm -rf \
1318
/var/lib/apt/lists \
1419
/dist
1520

16-
ENTRYPOINT ["bash", "-c", ". /opt/ros/$ROS_DISTRO/setup.bash && roslaunch --wait turtlebot3_navigation turtlebot3_navigation.launch map_file:=/tb3/navigation2/nav2_bringup/maps/tb3_sandbox.yaml open_rviz:=false initial_pose_x:=-2.0 initial_pose_y:=-0.5 initial_pose_a:=0.0"]
21+
ENTRYPOINT ["bash", "-c", ". /opt/ros/$ROS_DISTRO/setup.bash && roslaunch --wait /tb3/turtlebot3_navigation_edited.launch map_file:=/tb3/navigation2/nav2_bringup/maps/tb3_sandbox.yaml open_rviz:=false"]

.github/workflows/nightly.yaml

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
11
name: nightly
22

3-
on:
4-
schedule:
5-
# 2am SGT
6-
- cron: '0 18 * * *'
3+
# on:
4+
# schedule:
5+
# # 2am SGT
6+
# - cron: '0 18 * * *'
77

8-
# on: [push]
8+
on: [push]
99

1010
jobs:
1111
build-minimal-nav2-docker-images:

free_fleet_adapter/tests/integration/test_nav1_robot_adapter.py

+126-29
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,16 @@ def test_robot_battery_soc(self):
105105
tf_buffer=tf_buffer
106106
)
107107

108+
robot_exists = False
109+
for i in range(10):
110+
transform = robot_adapter.get_pose()
111+
if transform is not None:
112+
robot_exists = True
113+
break
114+
time.sleep(1)
115+
116+
assert robot_exists
117+
108118
battery_soc = robot_adapter.get_battery_soc()
109119
assert math.isclose(battery_soc, 1.0)
110120

@@ -123,6 +133,16 @@ def test_robot_unable_to_update(self):
123133
tf_buffer=tf_buffer
124134
)
125135

136+
robot_exists = False
137+
for i in range(10):
138+
transform = robot_adapter.get_pose()
139+
if transform is not None:
140+
robot_exists = True
141+
break
142+
time.sleep(1)
143+
144+
assert robot_exists
145+
126146
able_to_update = False
127147
try:
128148
robot_adapter.update(
@@ -151,6 +171,16 @@ def test_idle_robot_navigate_is_done(self):
151171
fleet_handle=None,
152172
tf_buffer=tf_buffer
153173
)
174+
175+
robot_exists = False
176+
for i in range(10):
177+
transform = robot_adapter.get_pose()
178+
if transform is not None:
179+
robot_exists = True
180+
break
181+
time.sleep(1)
182+
183+
assert robot_exists
154184
assert robot_adapter._is_navigation_done()
155185

156186
def test_robot_stop_without_command(self):
@@ -167,6 +197,16 @@ def test_robot_stop_without_command(self):
167197
fleet_handle=None,
168198
tf_buffer=tf_buffer
169199
)
200+
201+
robot_exists = False
202+
for i in range(10):
203+
transform = robot_adapter.get_pose()
204+
if transform is not None:
205+
robot_exists = True
206+
break
207+
time.sleep(1)
208+
209+
assert robot_exists
170210
assert robot_adapter.execution is None
171211
robot_adapter.stop(None)
172212
assert robot_adapter.execution is None
@@ -187,6 +227,16 @@ def test_robot_handle_navigate_to_invalid_map(self):
187227
tf_buffer=tf_buffer
188228
)
189229

230+
robot_exists = False
231+
for i in range(10):
232+
transform = robot_adapter.get_pose()
233+
if transform is not None:
234+
robot_exists = True
235+
break
236+
time.sleep(1)
237+
238+
assert robot_exists
239+
190240
able_to_handle_navigate = False
191241
try:
192242
robot_adapter._handle_navigate_to_pose(
@@ -201,35 +251,82 @@ def test_robot_handle_navigate_to_invalid_map(self):
201251
able_to_handle_navigate = False
202252
assert not able_to_handle_navigate
203253

204-
# def test_robot_stop_navigate(self):
205-
# tf_buffer = Buffer()
206-
207-
# robot_adapter = Nav1RobotAdapter(
208-
# name='tb3_0',
209-
# configuration=None,
210-
# robot_config_yaml={
211-
# 'initial_map': 'L1',
212-
# },
213-
# node=self.node,
214-
# zenoh_session=self.zenoh_session,
215-
# fleet_handle=None,
216-
# tf_buffer=tf_buffer
217-
# )
218-
219-
# robot_adapter._handle_navigate_to_pose(
220-
# 'L1',
221-
# -1.6,
222-
# -0.5,
223-
# 0.0,
224-
# 0.0,
225-
# 5.0
226-
# )
227-
# assert robot_adapter.nav_goal_id is not None
228-
# assert not robot_adapter._is_navigation_done()
229-
# time.sleep(1)
230-
# robot_adapter._handle_stop_navigation()
231-
# time.sleep(1)
232-
# assert robot_adapter._is_navigation_done()
254+
def test_robot_handle_navigate_to_pose(self):
255+
tf_buffer = Buffer()
256+
257+
robot_adapter = Nav1RobotAdapter(
258+
name='tb3_0',
259+
configuration=None,
260+
robot_config_yaml={
261+
'initial_map': 'L1',
262+
},
263+
node=self.node,
264+
zenoh_session=self.zenoh_session,
265+
fleet_handle=None,
266+
tf_buffer=tf_buffer
267+
)
268+
269+
robot_exists = False
270+
for i in range(10):
271+
transform = robot_adapter.get_pose()
272+
if transform is not None:
273+
robot_exists = True
274+
break
275+
time.sleep(1)
276+
277+
assert robot_exists
278+
279+
robot_adapter._handle_navigate_to_pose(
280+
'L1',
281+
-1.8,
282+
-0.5,
283+
0.0,
284+
0.0,
285+
5.0
286+
)
287+
assert not robot_adapter._is_navigation_done()
288+
time.sleep(5)
289+
assert robot_adapter._is_navigation_done()
290+
291+
def test_robot_stop_navigate(self):
292+
tf_buffer = Buffer()
293+
294+
robot_adapter = Nav1RobotAdapter(
295+
name='tb3_0',
296+
configuration=None,
297+
robot_config_yaml={
298+
'initial_map': 'L1',
299+
},
300+
node=self.node,
301+
zenoh_session=self.zenoh_session,
302+
fleet_handle=None,
303+
tf_buffer=tf_buffer
304+
)
305+
306+
robot_exists = False
307+
for i in range(10):
308+
transform = robot_adapter.get_pose()
309+
if transform is not None:
310+
robot_exists = True
311+
break
312+
time.sleep(1)
313+
314+
assert robot_exists
315+
316+
robot_adapter._handle_navigate_to_pose(
317+
'L1',
318+
1.808,
319+
0.503,
320+
0.0,
321+
0.0,
322+
5.0
323+
)
324+
assert robot_adapter.nav_goal_id is not None
325+
assert not robot_adapter._is_navigation_done()
326+
time.sleep(1)
327+
robot_adapter._handle_stop_navigation()
328+
time.sleep(1)
329+
assert robot_adapter._is_navigation_done()
233330

234331
def test_robot_execute_unknown_action(self):
235332
tf_buffer = Buffer()

free_fleet_examples/free_fleet_examples/nav1_move_base_cancel.py

-3
Original file line numberDiff line numberDiff line change
@@ -17,12 +17,9 @@
1717

1818
import argparse
1919
import sys
20-
import time
21-
2220

2321
from free_fleet_adapter.nav1_robot_adapter import Nav1MoveBaseHandler
2422
import rclpy
25-
from tf2_ros import Buffer
2623

2724
import zenoh
2825

free_fleet_examples/free_fleet_examples/nav1_move_base_simple_goal.py

-1
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222

2323
from free_fleet_adapter.nav1_robot_adapter import Nav1MoveBaseHandler
2424
import rclpy
25-
from tf2_ros import Buffer
2625

2726
import zenoh
2827

0 commit comments

Comments
 (0)