-
Notifications
You must be signed in to change notification settings - Fork 20
/
robot_navigator.py
511 lines (432 loc) · 21.5 KB
/
robot_navigator.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
#! /usr/bin/env python3
# Copyright 2021 Samsung Research America
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from enum import Enum
import time
from action_msgs.msg import GoalStatus
from builtin_interfaces.msg import Duration
from geometry_msgs.msg import Point
from geometry_msgs.msg import PoseStamped
from geometry_msgs.msg import PoseWithCovarianceStamped
from lifecycle_msgs.srv import GetState
from nav2_msgs.action import BackUp, Spin
from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose
from nav2_msgs.action import FollowPath, FollowWaypoints, NavigateThroughPoses, NavigateToPose
from nav2_msgs.srv import ClearEntireCostmap, GetCostmap, LoadMap, ManageLifecycleNodes
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy
from rclpy.qos import QoSProfile, QoSReliabilityPolicy
class TaskResult(Enum):
UNKNOWN = 0
SUCCEEDED = 1
CANCELED = 2
FAILED = 3
class BasicNavigator(Node):
def __init__(self):
super().__init__(node_name='basic_navigator')
self.initial_pose = PoseStamped()
self.initial_pose.header.frame_id = 'map'
self.goal_handle = None
self.result_future = None
self.feedback = None
self.status = None
amcl_pose_qos = QoSProfile(
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
reliability=QoSReliabilityPolicy.RELIABLE,
history=QoSHistoryPolicy.KEEP_LAST,
depth=1)
self.initial_pose_received = False
self.nav_through_poses_client = ActionClient(self,
NavigateThroughPoses,
'navigate_through_poses')
self.nav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
self.follow_waypoints_client = ActionClient(self, FollowWaypoints, 'follow_waypoints')
self.follow_path_client = ActionClient(self, FollowPath, 'follow_path')
self.compute_path_to_pose_client = ActionClient(self, ComputePathToPose,
'compute_path_to_pose')
self.compute_path_through_poses_client = ActionClient(self, ComputePathThroughPoses,
'compute_path_through_poses')
self.spin_client = ActionClient(self, Spin, 'spin')
self.backup_client = ActionClient(self, BackUp, 'backup')
self.localization_pose_sub = self.create_subscription(PoseWithCovarianceStamped,
'amcl_pose',
self._amclPoseCallback,
amcl_pose_qos)
self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
'initialpose',
10)
self.change_maps_srv = self.create_client(LoadMap, '/map_server/load_map')
self.clear_costmap_global_srv = self.create_client(
ClearEntireCostmap, '/global_costmap/clear_entirely_global_costmap')
self.clear_costmap_local_srv = self.create_client(
ClearEntireCostmap, '/local_costmap/clear_entirely_local_costmap')
self.get_costmap_global_srv = self.create_client(GetCostmap, '/global_costmap/get_costmap')
self.get_costmap_local_srv = self.create_client(GetCostmap, '/local_costmap/get_costmap')
def destroyNode(self):
self.destroy_node()
def destroy_node(self):
self.nav_through_poses_client.destroy()
self.nav_to_pose_client.destroy()
self.follow_waypoints_client.destroy()
self.follow_path_client.destroy()
self.compute_path_to_pose_client.destroy()
self.compute_path_through_poses_client.destroy()
self.spin_client.destroy()
self.backup_client.destroy()
super().destroy_node()
def setInitialPose(self, initial_pose):
"""Set the initial pose to the localization system."""
self.initial_pose_received = False
self.initial_pose = initial_pose
self._setInitialPose()
def goThroughPoses(self, poses, behavior_tree=''):
"""Send a `NavThroughPoses` action request."""
self.debug("Waiting for 'NavigateThroughPoses' action server")
while not self.nav_through_poses_client.wait_for_server(timeout_sec=1.0):
self.info("'NavigateThroughPoses' action server not available, waiting...")
goal_msg = NavigateThroughPoses.Goal()
goal_msg.poses = poses
goal_msg.behavior_tree = behavior_tree
self.info(f'Navigating with {len(goal_msg.poses)} goals....')
send_goal_future = self.nav_through_poses_client.send_goal_async(goal_msg,
self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error(f'Goal with {len(poses)} poses was rejected!')
return False
self.result_future = self.goal_handle.get_result_async()
return True
def goToPose(self, pose, behavior_tree=''):
"""Send a `NavToPose` action request."""
self.debug("Waiting for 'NavigateToPose' action server")
while not self.nav_to_pose_client.wait_for_server(timeout_sec=1.0):
self.info("'NavigateToPose' action server not available, waiting...")
goal_msg = NavigateToPose.Goal()
goal_msg.pose = pose
goal_msg.behavior_tree = behavior_tree
self.info('Navigating to goal: ' + str(pose.pose.position.x) + ' ' +
str(pose.pose.position.y) + '...')
send_goal_future = self.nav_to_pose_client.send_goal_async(goal_msg,
self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error('Goal to ' + str(pose.pose.position.x) + ' ' +
str(pose.pose.position.y) + ' was rejected!')
return False
self.result_future = self.goal_handle.get_result_async()
return True
def followWaypoints(self, poses):
"""Send a `FollowWaypoints` action request."""
self.debug("Waiting for 'FollowWaypoints' action server")
while not self.follow_waypoints_client.wait_for_server(timeout_sec=1.0):
self.info("'FollowWaypoints' action server not available, waiting...")
goal_msg = FollowWaypoints.Goal()
goal_msg.poses = poses
self.info(f'Following {len(goal_msg.poses)} goals....')
send_goal_future = self.follow_waypoints_client.send_goal_async(goal_msg,
self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error(f'Following {len(poses)} waypoints request was rejected!')
return False
self.result_future = self.goal_handle.get_result_async()
return True
def spin(self, spin_dist=1.57):
self.debug("Waiting for 'Spin' action server")
while not self.spin_client.wait_for_server(timeout_sec=1.0):
self.info("'Spin' action server not available, waiting...")
goal_msg = Spin.Goal()
goal_msg.target_yaw = spin_dist
self.info(f'Spinning to angle {goal_msg.target_yaw}....')
send_goal_future = self.spin_client.send_goal_async(goal_msg, self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error('Spin request was rejected!')
return False
self.result_future = self.goal_handle.get_result_async()
return True
def backup(self, backup_dist=0.15, backup_speed=0.025):
self.debug("Waiting for 'Backup' action server")
while not self.backup_client.wait_for_server(timeout_sec=1.0):
self.info("'Backup' action server not available, waiting...")
goal_msg = BackUp.Goal()
goal_msg.target = Point(x=float(backup_dist))
goal_msg.speed = backup_speed
self.info(f'Backing up {goal_msg.target.x} m at {goal_msg.speed} m/s....')
send_goal_future = self.backup_client.send_goal_async(goal_msg, self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error('Backup request was rejected!')
return False
self.result_future = self.goal_handle.get_result_async()
return True
def followPath(self, path, controller_id='', goal_checker_id=''):
"""Send a `FollowPath` action request."""
self.debug("Waiting for 'FollowPath' action server")
while not self.follow_path_client.wait_for_server(timeout_sec=1.0):
self.info("'FollowPath' action server not available, waiting...")
goal_msg = FollowPath.Goal()
goal_msg.path = path
goal_msg.controller_id = controller_id
goal_msg.goal_checker_id = goal_checker_id
self.info('Executing path...')
send_goal_future = self.follow_path_client.send_goal_async(goal_msg,
self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error('Follow path was rejected!')
return False
self.result_future = self.goal_handle.get_result_async()
return True
def cancelTask(self):
"""Cancel pending task request of any type."""
self.info('Canceling current task.')
if self.result_future:
future = self.goal_handle.cancel_goal_async()
rclpy.spin_until_future_complete(self, future)
return
def isTaskComplete(self):
"""Check if the task request of any type is complete yet."""
if not self.result_future:
# task was cancelled or completed
return True
rclpy.spin_until_future_complete(self, self.result_future, timeout_sec=0.10)
if self.result_future.result():
self.status = self.result_future.result().status
if self.status != GoalStatus.STATUS_SUCCEEDED:
self.debug(f'Task with failed with status code: {self.status}')
return True
else:
# Timed out, still processing, not complete yet
return False
self.debug('Task succeeded!')
return True
def getFeedback(self):
"""Get the pending action feedback message."""
return self.feedback
def getResult(self):
"""Get the pending action result message."""
if self.status == GoalStatus.STATUS_SUCCEEDED:
return TaskResult.SUCCEEDED
elif self.status == GoalStatus.STATUS_ABORTED:
return TaskResult.FAILED
elif self.status == GoalStatus.STATUS_CANCELED:
return TaskResult.CANCELED
else:
return TaskResult.UNKNOWN
def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl'):
"""Block until the full navigation system is up and running."""
self._waitForNodeToActivate(localizer)
if localizer == 'amcl':
self._waitForInitialPose()
self._waitForNodeToActivate(navigator)
self.info('Nav2 is ready for use!')
return
def getPath(self, start, goal, planner_id='', use_start=False):
"""Send a `ComputePathToPose` action request."""
self.debug("Waiting for 'ComputePathToPose' action server")
while not self.compute_path_to_pose_client.wait_for_server(timeout_sec=1.0):
self.info("'ComputePathToPose' action server not available, waiting...")
goal_msg = ComputePathToPose.Goal()
goal_msg.start = start
goal_msg.goal = goal
goal_msg.planner_id = planner_id
goal_msg.use_start = use_start
self.info('Getting path...')
send_goal_future = self.compute_path_to_pose_client.send_goal_async(goal_msg)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error('Get path was rejected!')
return None
self.result_future = self.goal_handle.get_result_async()
rclpy.spin_until_future_complete(self, self.result_future)
self.status = self.result_future.result().status
if self.status != GoalStatus.STATUS_SUCCEEDED:
self.warn(f'Getting path failed with status code: {self.status}')
return None
return self.result_future.result().result.path
def getPathThroughPoses(self, start, goals, planner_id='', use_start=False):
"""Send a `ComputePathThroughPoses` action request."""
self.debug("Waiting for 'ComputePathThroughPoses' action server")
while not self.compute_path_through_poses_client.wait_for_server(timeout_sec=1.0):
self.info("'ComputePathThroughPoses' action server not available, waiting...")
goal_msg = ComputePathThroughPoses.Goal()
goal_msg.start = start
goal_msg.goals = goals
goal_msg.planner_id = planner_id
goal_msg.use_start = use_start
self.info('Getting path...')
send_goal_future = self.compute_path_through_poses_client.send_goal_async(goal_msg)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()
if not self.goal_handle.accepted:
self.error('Get path was rejected!')
return None
self.result_future = self.goal_handle.get_result_async()
rclpy.spin_until_future_complete(self, self.result_future)
self.status = self.result_future.result().status
if self.status != GoalStatus.STATUS_SUCCEEDED:
self.warn(f'Getting path failed with status code: {self.status}')
return None
return self.result_future.result().result.path
def changeMap(self, map_filepath):
"""Change the current static map in the map server."""
while not self.change_maps_srv.wait_for_service(timeout_sec=1.0):
self.info('change map service not available, waiting...')
req = LoadMap.Request()
req.map_url = map_filepath
future = self.change_maps_srv.call_async(req)
rclpy.spin_until_future_complete(self, future)
status = future.result().result
if status != LoadMap.Response().RESULT_SUCCESS:
self.error('Change map request failed!')
else:
self.info('Change map request was successful!')
return
def clearAllCostmaps(self):
"""Clear all costmaps."""
self.clearLocalCostmap()
self.clearGlobalCostmap()
return
def clearLocalCostmap(self):
"""Clear local costmap."""
while not self.clear_costmap_local_srv.wait_for_service(timeout_sec=1.0):
self.info('Clear local costmaps service not available, waiting...')
req = ClearEntireCostmap.Request()
future = self.clear_costmap_local_srv.call_async(req)
rclpy.spin_until_future_complete(self, future)
return
def clearGlobalCostmap(self):
"""Clear global costmap."""
while not self.clear_costmap_global_srv.wait_for_service(timeout_sec=1.0):
self.info('Clear global costmaps service not available, waiting...')
req = ClearEntireCostmap.Request()
future = self.clear_costmap_global_srv.call_async(req)
rclpy.spin_until_future_complete(self, future)
return
def getGlobalCostmap(self):
"""Get the global costmap."""
while not self.get_costmap_global_srv.wait_for_service(timeout_sec=1.0):
self.info('Get global costmaps service not available, waiting...')
req = GetCostmap.Request()
future = self.get_costmap_global_srv.call_async(req)
rclpy.spin_until_future_complete(self, future)
return future.result().map
def getLocalCostmap(self):
"""Get the local costmap."""
while not self.get_costmap_local_srv.wait_for_service(timeout_sec=1.0):
self.info('Get local costmaps service not available, waiting...')
req = GetCostmap.Request()
future = self.get_costmap_local_srv.call_async(req)
rclpy.spin_until_future_complete(self, future)
return future.result().map
def lifecycleStartup(self):
"""Startup nav2 lifecycle system."""
self.info('Starting up lifecycle nodes based on lifecycle_manager.')
for srv_name, srv_type in self.get_service_names_and_types():
if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
self.info(f'Starting up {srv_name}')
mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
while not mgr_client.wait_for_service(timeout_sec=1.0):
self.info(f'{srv_name} service not available, waiting...')
req = ManageLifecycleNodes.Request()
req.command = ManageLifecycleNodes.Request().STARTUP
future = mgr_client.call_async(req)
# starting up requires a full map->odom->base_link TF tree
# so if we're not successful, try forwarding the initial pose
while True:
rclpy.spin_until_future_complete(self, future, timeout_sec=0.10)
if not future:
self._waitForInitialPose()
else:
break
self.info('Nav2 is ready for use!')
return
def lifecycleShutdown(self):
"""Shutdown nav2 lifecycle system."""
self.info('Shutting down lifecycle nodes based on lifecycle_manager.')
for srv_name, srv_type in self.get_service_names_and_types():
if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
self.info(f'Shutting down {srv_name}')
mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
while not mgr_client.wait_for_service(timeout_sec=1.0):
self.info(f'{srv_name} service not available, waiting...')
req = ManageLifecycleNodes.Request()
req.command = ManageLifecycleNodes.Request().SHUTDOWN
future = mgr_client.call_async(req)
rclpy.spin_until_future_complete(self, future)
future.result()
return
def _waitForNodeToActivate(self, node_name):
# Waits for the node within the tester namespace to become active
self.debug(f'Waiting for {node_name} to become active..')
node_service = f'{node_name}/get_state'
state_client = self.create_client(GetState, node_service)
while not state_client.wait_for_service(timeout_sec=1.0):
self.info(f'{node_service} service not available, waiting...')
req = GetState.Request()
state = 'unknown'
while state != 'active':
self.debug(f'Getting {node_name} state...')
future = state_client.call_async(req)
rclpy.spin_until_future_complete(self, future)
if future.result() is not None:
state = future.result().current_state.label
self.debug(f'Result of get_state: {state}')
time.sleep(2)
return
def _waitForInitialPose(self):
while not self.initial_pose_received:
self.info('Setting initial pose')
self._setInitialPose()
self.info('Waiting for amcl_pose to be received')
rclpy.spin_once(self, timeout_sec=1.0)
return
def _amclPoseCallback(self, msg):
self.debug('Received amcl pose')
self.initial_pose_received = True
return
def _feedbackCallback(self, msg):
self.debug('Received action feedback message')
self.feedback = msg.feedback
return
def _setInitialPose(self):
msg = PoseWithCovarianceStamped()
msg.pose.pose = self.initial_pose.pose
msg.header.frame_id = self.initial_pose.header.frame_id
msg.header.stamp = self.initial_pose.header.stamp
self.info('Publishing Initial Pose')
self.initial_pose_pub.publish(msg)
return
def info(self, msg):
self.get_logger().info(msg)
return
def warn(self, msg):
self.get_logger().warn(msg)
return
def error(self, msg):
self.get_logger().error(msg)
return
def debug(self, msg):
self.get_logger().debug(msg)
return