@@ -105,6 +105,16 @@ def test_robot_battery_soc(self):
105
105
tf_buffer = tf_buffer
106
106
)
107
107
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
+
108
118
battery_soc = robot_adapter .get_battery_soc ()
109
119
assert math .isclose (battery_soc , 1.0 )
110
120
@@ -123,6 +133,16 @@ def test_robot_unable_to_update(self):
123
133
tf_buffer = tf_buffer
124
134
)
125
135
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
+
126
146
able_to_update = False
127
147
try :
128
148
robot_adapter .update (
@@ -151,6 +171,16 @@ def test_idle_robot_navigate_is_done(self):
151
171
fleet_handle = None ,
152
172
tf_buffer = tf_buffer
153
173
)
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
154
184
assert robot_adapter ._is_navigation_done ()
155
185
156
186
def test_robot_stop_without_command (self ):
@@ -167,6 +197,16 @@ def test_robot_stop_without_command(self):
167
197
fleet_handle = None ,
168
198
tf_buffer = tf_buffer
169
199
)
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
170
210
assert robot_adapter .execution is None
171
211
robot_adapter .stop (None )
172
212
assert robot_adapter .execution is None
@@ -187,6 +227,16 @@ def test_robot_handle_navigate_to_invalid_map(self):
187
227
tf_buffer = tf_buffer
188
228
)
189
229
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
+
190
240
able_to_handle_navigate = False
191
241
try :
192
242
robot_adapter ._handle_navigate_to_pose (
@@ -201,35 +251,82 @@ def test_robot_handle_navigate_to_invalid_map(self):
201
251
able_to_handle_navigate = False
202
252
assert not able_to_handle_navigate
203
253
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 ()
233
330
234
331
def test_robot_execute_unknown_action (self ):
235
332
tf_buffer = Buffer ()
0 commit comments