Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
robot_navigator.py
1 #! /usr/bin/env python3
2 # Copyright 2021 Samsung Research America
3 #
4 # Licensed under the Apache License, Version 2.0 (the "License");
5 # you may not use this file except in compliance with the License.
6 # You may obtain a copy of the License at
7 #
8 # http://www.apache.org/licenses/LICENSE-2.0
9 #
10 # Unless required by applicable law or agreed to in writing, software
11 # distributed under the License is distributed on an "AS IS" BASIS,
12 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 # See the License for the specific language governing permissions and
14 # limitations under the License.
15 
16 
17 from enum import Enum
18 import time
19 
20 from action_msgs.msg import GoalStatus
21 from builtin_interfaces.msg import Duration
22 from geometry_msgs.msg import Point
23 from geometry_msgs.msg import PoseStamped
24 from geometry_msgs.msg import PoseWithCovarianceStamped
25 from lifecycle_msgs.srv import GetState
26 from nav2_msgs.action import AssistedTeleop, BackUp, DriveOnHeading, Spin
27 from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose
28 from nav2_msgs.action import (
29  DockRobot,
30  FollowGPSWaypoints,
31  FollowPath,
32  FollowWaypoints,
33  NavigateThroughPoses,
34  NavigateToPose,
35  UndockRobot,
36 )
37 from nav2_msgs.action import SmoothPath
38 from nav2_msgs.srv import ClearCostmapAroundPose, ClearCostmapAroundRobot, \
39  ClearCostmapExceptRegion, ClearEntireCostmap
40 from nav2_msgs.srv import GetCostmap, LoadMap, ManageLifecycleNodes
41 import rclpy
42 from rclpy.action import ActionClient
43 from rclpy.duration import Duration as rclpyDuration
44 from rclpy.node import Node
45 from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy
46 from rclpy.qos import QoSProfile, QoSReliabilityPolicy
47 
48 
49 class TaskResult(Enum):
50  UNKNOWN = 0
51  SUCCEEDED = 1
52  CANCELED = 2
53  FAILED = 3
54 
55 
56 class BasicNavigator(Node):
57 
58  def __init__(self, node_name='basic_navigator', namespace=''):
59  super().__init__(node_name=node_name, namespace=namespace)
60  self.initial_poseinitial_pose = PoseStamped()
61  self.initial_poseinitial_pose.header.frame_id = 'map'
62  self.goal_handlegoal_handle = None
63  self.result_futureresult_future = None
64  self.feedbackfeedback = None
65  self.statusstatus = None
66 
67  amcl_pose_qos = QoSProfile(
68  durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
69  reliability=QoSReliabilityPolicy.RELIABLE,
70  history=QoSHistoryPolicy.KEEP_LAST,
71  depth=1,
72  )
73 
74  self.initial_pose_receivedinitial_pose_received = False
75  self.nav_through_poses_clientnav_through_poses_client = ActionClient(
76  self, NavigateThroughPoses, 'navigate_through_poses'
77  )
78  self.nav_to_pose_clientnav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
79  self.follow_waypoints_clientfollow_waypoints_client = ActionClient(
80  self, FollowWaypoints, 'follow_waypoints'
81  )
82  self.follow_gps_waypoints_clientfollow_gps_waypoints_client = ActionClient(
83  self, FollowGPSWaypoints, 'follow_gps_waypoints'
84  )
85  self.follow_path_clientfollow_path_client = ActionClient(self, FollowPath, 'follow_path')
86  self.compute_path_to_pose_clientcompute_path_to_pose_client = ActionClient(
87  self, ComputePathToPose, 'compute_path_to_pose'
88  )
89  self.compute_path_through_poses_clientcompute_path_through_poses_client = ActionClient(
90  self, ComputePathThroughPoses, 'compute_path_through_poses'
91  )
92  self.smoother_clientsmoother_client = ActionClient(self, SmoothPath, 'smooth_path')
93  self.spin_clientspin_client = ActionClient(self, Spin, 'spin')
94  self.backup_clientbackup_client = ActionClient(self, BackUp, 'backup')
95  self.drive_on_heading_clientdrive_on_heading_client = ActionClient(
96  self, DriveOnHeading, 'drive_on_heading'
97  )
98  self.assisted_teleop_clientassisted_teleop_client = ActionClient(
99  self, AssistedTeleop, 'assisted_teleop'
100  )
101  self.docking_clientdocking_client = ActionClient(self, DockRobot, 'dock_robot')
102  self.undocking_clientundocking_client = ActionClient(self, UndockRobot, 'undock_robot')
103  self.localization_pose_sublocalization_pose_sub = self.create_subscription(
104  PoseWithCovarianceStamped,
105  'amcl_pose',
106  self._amclPoseCallback_amclPoseCallback,
107  amcl_pose_qos,
108  )
109  self.initial_pose_pubinitial_pose_pub = self.create_publisher(
110  PoseWithCovarianceStamped, 'initialpose', 10
111  )
112  self.change_maps_srvchange_maps_srv = self.create_client(LoadMap, 'map_server/load_map')
113  self.clear_costmap_global_srvclear_costmap_global_srv = self.create_client(
114  ClearEntireCostmap, 'global_costmap/clear_entirely_global_costmap'
115  )
116  self.clear_costmap_local_srvclear_costmap_local_srv = self.create_client(
117  ClearEntireCostmap, 'local_costmap/clear_entirely_local_costmap'
118  )
119  self.clear_costmap_except_region_srvclear_costmap_except_region_srv = self.create_client(
120  ClearCostmapExceptRegion, 'local_costmap/clear_costmap_except_region'
121  )
122  self.clear_costmap_around_robot_srvclear_costmap_around_robot_srv = self.create_client(
123  ClearCostmapAroundRobot, 'local_costmap/clear_costmap_around_robot'
124  )
125  self.clear_costmap_around_pose_srvclear_costmap_around_pose_srv = self.create_client(
126  ClearCostmapAroundPose, 'local_costmap/clear_costmap_around_pose'
127  )
128  self.get_costmap_global_srvget_costmap_global_srv = self.create_client(
129  GetCostmap, 'global_costmap/get_costmap'
130  )
131  self.get_costmap_local_srvget_costmap_local_srv = self.create_client(
132  GetCostmap, 'local_costmap/get_costmap'
133  )
134 
135  def destroyNode(self):
136  self.destroy_nodedestroy_node()
137 
138  def destroy_node(self):
139  self.nav_through_poses_clientnav_through_poses_client.destroy()
140  self.nav_to_pose_clientnav_to_pose_client.destroy()
141  self.follow_waypoints_clientfollow_waypoints_client.destroy()
142  self.follow_path_clientfollow_path_client.destroy()
143  self.compute_path_to_pose_clientcompute_path_to_pose_client.destroy()
144  self.compute_path_through_poses_clientcompute_path_through_poses_client.destroy()
145  self.smoother_clientsmoother_client.destroy()
146  self.spin_clientspin_client.destroy()
147  self.backup_clientbackup_client.destroy()
148  self.drive_on_heading_clientdrive_on_heading_client.destroy()
149  self.assisted_teleop_clientassisted_teleop_client.destroy()
150  self.follow_gps_waypoints_clientfollow_gps_waypoints_client.destroy()
151  self.docking_clientdocking_client.destroy()
152  self.undocking_clientundocking_client.destroy()
153  super().destroy_node()
154 
155  def setInitialPose(self, initial_pose):
156  """Set the initial pose to the localization system."""
157  self.initial_pose_receivedinitial_pose_received = False
158  self.initial_poseinitial_pose = initial_pose
159  self._setInitialPose_setInitialPose()
160 
161  def goThroughPoses(self, poses, behavior_tree=''):
162  """Send a `NavThroughPoses` action request."""
163  self.debugdebug("Waiting for 'NavigateThroughPoses' action server")
164  while not self.nav_through_poses_clientnav_through_poses_client.wait_for_server(timeout_sec=1.0):
165  self.infoinfo("'NavigateThroughPoses' action server not available, waiting...")
166 
167  goal_msg = NavigateThroughPoses.Goal()
168  goal_msg.poses = poses
169  goal_msg.behavior_tree = behavior_tree
170 
171  self.infoinfo(f'Navigating with {len(goal_msg.poses)} goals....')
172  send_goal_future = self.nav_through_poses_clientnav_through_poses_client.send_goal_async(
173  goal_msg, self._feedbackCallback_feedbackCallback
174  )
175  rclpy.spin_until_future_complete(self, send_goal_future)
176  self.goal_handlegoal_handle = send_goal_future.result()
177 
178  if not self.goal_handlegoal_handle.accepted:
179  self.errorerror(f'Goal with {len(poses)} poses was rejected!')
180  return False
181 
182  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
183  return True
184 
185  def goToPose(self, pose, behavior_tree=''):
186  """Send a `NavToPose` action request."""
187  self.debugdebug("Waiting for 'NavigateToPose' action server")
188  while not self.nav_to_pose_clientnav_to_pose_client.wait_for_server(timeout_sec=1.0):
189  self.infoinfo("'NavigateToPose' action server not available, waiting...")
190 
191  goal_msg = NavigateToPose.Goal()
192  goal_msg.pose = pose
193  goal_msg.behavior_tree = behavior_tree
194 
195  self.infoinfo(
196  'Navigating to goal: '
197  + str(pose.pose.position.x)
198  + ' '
199  + str(pose.pose.position.y)
200  + '...'
201  )
202  send_goal_future = self.nav_to_pose_clientnav_to_pose_client.send_goal_async(
203  goal_msg, self._feedbackCallback_feedbackCallback
204  )
205  rclpy.spin_until_future_complete(self, send_goal_future)
206  self.goal_handlegoal_handle = send_goal_future.result()
207 
208  if not self.goal_handlegoal_handle.accepted:
209  self.errorerror(
210  'Goal to '
211  + str(pose.pose.position.x)
212  + ' '
213  + str(pose.pose.position.y)
214  + ' was rejected!'
215  )
216  return False
217 
218  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
219  return True
220 
221  def followWaypoints(self, poses):
222  """Send a `FollowWaypoints` action request."""
223  self.debugdebug("Waiting for 'FollowWaypoints' action server")
224  while not self.follow_waypoints_clientfollow_waypoints_client.wait_for_server(timeout_sec=1.0):
225  self.infoinfo("'FollowWaypoints' action server not available, waiting...")
226 
227  goal_msg = FollowWaypoints.Goal()
228  goal_msg.poses = poses
229 
230  self.infoinfo(f'Following {len(goal_msg.poses)} goals....')
231  send_goal_future = self.follow_waypoints_clientfollow_waypoints_client.send_goal_async(
232  goal_msg, self._feedbackCallback_feedbackCallback
233  )
234  rclpy.spin_until_future_complete(self, send_goal_future)
235  self.goal_handlegoal_handle = send_goal_future.result()
236 
237  if not self.goal_handlegoal_handle.accepted:
238  self.errorerror(f'Following {len(poses)} waypoints request was rejected!')
239  return False
240 
241  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
242  return True
243 
244  def followGpsWaypoints(self, gps_poses):
245  """Send a `FollowGPSWaypoints` action request."""
246  self.debugdebug("Waiting for 'FollowWaypoints' action server")
247  while not self.follow_gps_waypoints_clientfollow_gps_waypoints_client.wait_for_server(timeout_sec=1.0):
248  self.infoinfo("'FollowWaypoints' action server not available, waiting...")
249 
250  goal_msg = FollowGPSWaypoints.Goal()
251  goal_msg.gps_poses = gps_poses
252 
253  self.infoinfo(f'Following {len(goal_msg.gps_poses)} gps goals....')
254  send_goal_future = self.follow_gps_waypoints_clientfollow_gps_waypoints_client.send_goal_async(
255  goal_msg, self._feedbackCallback_feedbackCallback
256  )
257  rclpy.spin_until_future_complete(self, send_goal_future)
258  self.goal_handlegoal_handle = send_goal_future.result()
259 
260  if not self.goal_handlegoal_handle.accepted:
261  self.errorerror(
262  f'Following {len(gps_poses)} gps waypoints request was rejected!'
263  )
264  return False
265 
266  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
267  return True
268 
269  def spin(self, spin_dist=1.57, time_allowance=10):
270  self.debugdebug("Waiting for 'Spin' action server")
271  while not self.spin_clientspin_client.wait_for_server(timeout_sec=1.0):
272  self.infoinfo("'Spin' action server not available, waiting...")
273  goal_msg = Spin.Goal()
274  goal_msg.target_yaw = spin_dist
275  goal_msg.time_allowance = Duration(sec=time_allowance)
276 
277  self.infoinfo(f'Spinning to angle {goal_msg.target_yaw}....')
278  send_goal_future = self.spin_clientspin_client.send_goal_async(
279  goal_msg, self._feedbackCallback_feedbackCallback
280  )
281  rclpy.spin_until_future_complete(self, send_goal_future)
282  self.goal_handlegoal_handle = send_goal_future.result()
283 
284  if not self.goal_handlegoal_handle.accepted:
285  self.errorerror('Spin request was rejected!')
286  return False
287 
288  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
289  return True
290 
291  def backup(self, backup_dist=0.15, backup_speed=0.025, time_allowance=10):
292  self.debugdebug("Waiting for 'Backup' action server")
293  while not self.backup_clientbackup_client.wait_for_server(timeout_sec=1.0):
294  self.infoinfo("'Backup' action server not available, waiting...")
295  goal_msg = BackUp.Goal()
296  goal_msg.target = Point(x=float(backup_dist))
297  goal_msg.speed = backup_speed
298  goal_msg.time_allowance = Duration(sec=time_allowance)
299 
300  self.infoinfo(f'Backing up {goal_msg.target.x} m at {goal_msg.speed} m/s....')
301  send_goal_future = self.backup_clientbackup_client.send_goal_async(
302  goal_msg, self._feedbackCallback_feedbackCallback
303  )
304  rclpy.spin_until_future_complete(self, send_goal_future)
305  self.goal_handlegoal_handle = send_goal_future.result()
306 
307  if not self.goal_handlegoal_handle.accepted:
308  self.errorerror('Backup request was rejected!')
309  return False
310 
311  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
312  return True
313 
314  def driveOnHeading(self, dist=0.15, speed=0.025, time_allowance=10):
315  self.debugdebug("Waiting for 'DriveOnHeading' action server")
316  while not self.backup_clientbackup_client.wait_for_server(timeout_sec=1.0):
317  self.infoinfo("'DriveOnHeading' action server not available, waiting...")
318  goal_msg = DriveOnHeading.Goal()
319  goal_msg.target = Point(x=float(dist))
320  goal_msg.speed = speed
321  goal_msg.time_allowance = Duration(sec=time_allowance)
322 
323  self.infoinfo(f'Drive {goal_msg.target.x} m on heading at {goal_msg.speed} m/s....')
324  send_goal_future = self.drive_on_heading_clientdrive_on_heading_client.send_goal_async(
325  goal_msg, self._feedbackCallback_feedbackCallback
326  )
327  rclpy.spin_until_future_complete(self, send_goal_future)
328  self.goal_handlegoal_handle = send_goal_future.result()
329 
330  if not self.goal_handlegoal_handle.accepted:
331  self.errorerror('Drive On Heading request was rejected!')
332  return False
333 
334  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
335  return True
336 
337  def assistedTeleop(self, time_allowance=30):
338  self.debugdebug("Wainting for 'assisted_teleop' action server")
339  while not self.assisted_teleop_clientassisted_teleop_client.wait_for_server(timeout_sec=1.0):
340  self.infoinfo("'assisted_teleop' action server not available, waiting...")
341  goal_msg = AssistedTeleop.Goal()
342  goal_msg.time_allowance = Duration(sec=time_allowance)
343 
344  self.infoinfo("Running 'assisted_teleop'....")
345  send_goal_future = self.assisted_teleop_clientassisted_teleop_client.send_goal_async(
346  goal_msg, self._feedbackCallback_feedbackCallback
347  )
348  rclpy.spin_until_future_complete(self, send_goal_future)
349  self.goal_handlegoal_handle = send_goal_future.result()
350 
351  if not self.goal_handlegoal_handle.accepted:
352  self.errorerror('Assisted Teleop request was rejected!')
353  return False
354 
355  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
356  return True
357 
358  def followPath(self, path, controller_id='', goal_checker_id=''):
359  """Send a `FollowPath` action request."""
360  self.debugdebug("Waiting for 'FollowPath' action server")
361  while not self.follow_path_clientfollow_path_client.wait_for_server(timeout_sec=1.0):
362  self.infoinfo("'FollowPath' action server not available, waiting...")
363 
364  goal_msg = FollowPath.Goal()
365  goal_msg.path = path
366  goal_msg.controller_id = controller_id
367  goal_msg.goal_checker_id = goal_checker_id
368 
369  self.infoinfo('Executing path...')
370  send_goal_future = self.follow_path_clientfollow_path_client.send_goal_async(
371  goal_msg, self._feedbackCallback_feedbackCallback
372  )
373  rclpy.spin_until_future_complete(self, send_goal_future)
374  self.goal_handlegoal_handle = send_goal_future.result()
375 
376  if not self.goal_handlegoal_handle.accepted:
377  self.errorerror('Follow path was rejected!')
378  return False
379 
380  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
381  return True
382 
383  def dockRobotByPose(self, dock_pose, dock_type, nav_to_dock=True):
384  """Send a `DockRobot` action request."""
385  self.infoinfo("Waiting for 'DockRobot' action server")
386  while not self.docking_clientdocking_client.wait_for_server(timeout_sec=1.0):
387  self.infoinfo('"DockRobot" action server not available, waiting...')
388 
389  goal_msg = DockRobot.Goal()
390  goal_msg.use_dock_id = False
391  goal_msg.dock_pose = dock_pose
392  goal_msg.dock_type = dock_type
393  goal_msg.navigate_to_staging_pose = nav_to_dock # if want to navigate before staging
394 
395  self.infoinfo('Docking at pose: ' + str(dock_pose) + '...')
396  send_goal_future = self.docking_clientdocking_client.send_goal_async(goal_msg,
397  self._feedbackCallback_feedbackCallback)
398  rclpy.spin_until_future_complete(self, send_goal_future)
399  self.goal_handlegoal_handle = send_goal_future.result()
400 
401  if not self.goal_handlegoal_handle.accepted:
402  self.infoinfo('Docking request was rejected!')
403  return False
404 
405  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
406  return True
407 
408  def dockRobotByID(self, dock_id, nav_to_dock=True):
409  """Send a `DockRobot` action request."""
410  self.infoinfo("Waiting for 'DockRobot' action server")
411  while not self.docking_clientdocking_client.wait_for_server(timeout_sec=1.0):
412  self.infoinfo('"DockRobot" action server not available, waiting...')
413 
414  goal_msg = DockRobot.Goal()
415  goal_msg.use_dock_id = True
416  goal_msg.dock_id = dock_id
417  goal_msg.navigate_to_staging_pose = nav_to_dock # if want to navigate before staging
418 
419  self.infoinfo('Docking at dock ID: ' + str(dock_id) + '...')
420  send_goal_future = self.docking_clientdocking_client.send_goal_async(goal_msg,
421  self._feedbackCallback_feedbackCallback)
422  rclpy.spin_until_future_complete(self, send_goal_future)
423  self.goal_handlegoal_handle = send_goal_future.result()
424 
425  if not self.goal_handlegoal_handle.accepted:
426  self.infoinfo('Docking request was rejected!')
427  return False
428 
429  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
430  return True
431 
432  def undockRobot(self, dock_type=''):
433  """Send a `UndockRobot` action request."""
434  self.infoinfo("Waiting for 'UndockRobot' action server")
435  while not self.undocking_clientundocking_client.wait_for_server(timeout_sec=1.0):
436  self.infoinfo('"UndockRobot" action server not available, waiting...')
437 
438  goal_msg = UndockRobot.Goal()
439  goal_msg.dock_type = dock_type
440 
441  self.infoinfo('Undocking from dock of type: ' + str(dock_type) + '...')
442  send_goal_future = self.undocking_clientundocking_client.send_goal_async(goal_msg,
443  self._feedbackCallback_feedbackCallback)
444  rclpy.spin_until_future_complete(self, send_goal_future)
445  self.goal_handlegoal_handle = send_goal_future.result()
446 
447  if not self.goal_handlegoal_handle.accepted:
448  self.infoinfo('Undocking request was rejected!')
449  return False
450 
451  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
452  return True
453 
454  def cancelTask(self):
455  """Cancel pending task request of any type."""
456  self.infoinfo('Canceling current task.')
457  if self.result_futureresult_future:
458  future = self.goal_handlegoal_handle.cancel_goal_async()
459  rclpy.spin_until_future_complete(self, future)
460  return
461 
462  def isTaskComplete(self):
463  """Check if the task request of any type is complete yet."""
464  if not self.result_futureresult_future:
465  # task was cancelled or completed
466  return True
467  rclpy.spin_until_future_complete(self, self.result_futureresult_future, timeout_sec=0.10)
468  if self.result_futureresult_future.result():
469  self.statusstatus = self.result_futureresult_future.result().status
470  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
471  self.debugdebug(f'Task with failed with status code: {self.status}')
472  return True
473  else:
474  # Timed out, still processing, not complete yet
475  return False
476 
477  self.debugdebug('Task succeeded!')
478  return True
479 
480  def getFeedback(self):
481  """Get the pending action feedback message."""
482  return self.feedbackfeedback
483 
484  def getResult(self):
485  """Get the pending action result message."""
486  if self.statusstatus == GoalStatus.STATUS_SUCCEEDED:
487  return TaskResult.SUCCEEDED
488  elif self.statusstatus == GoalStatus.STATUS_ABORTED:
489  return TaskResult.FAILED
490  elif self.statusstatus == GoalStatus.STATUS_CANCELED:
491  return TaskResult.CANCELED
492  else:
493  return TaskResult.UNKNOWN
494 
495  def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl'):
496  """Block until the full navigation system is up and running."""
497  if localizer != 'robot_localization': # non-lifecycle node
498  self._waitForNodeToActivate_waitForNodeToActivate(localizer)
499  if localizer == 'amcl':
500  self._waitForInitialPose_waitForInitialPose()
501  self._waitForNodeToActivate_waitForNodeToActivate(navigator)
502  self.infoinfo('Nav2 is ready for use!')
503  return
504 
505  def _getPathImpl(self, start, goal, planner_id='', use_start=False):
506  """
507  Send a `ComputePathToPose` action request.
508 
509  Internal implementation to get the full result, not just the path.
510  """
511  self.debugdebug("Waiting for 'ComputePathToPose' action server")
512  while not self.compute_path_to_pose_clientcompute_path_to_pose_client.wait_for_server(timeout_sec=1.0):
513  self.infoinfo("'ComputePathToPose' action server not available, waiting...")
514 
515  goal_msg = ComputePathToPose.Goal()
516  goal_msg.start = start
517  goal_msg.goal = goal
518  goal_msg.planner_id = planner_id
519  goal_msg.use_start = use_start
520 
521  self.infoinfo('Getting path...')
522  send_goal_future = self.compute_path_to_pose_clientcompute_path_to_pose_client.send_goal_async(goal_msg)
523  rclpy.spin_until_future_complete(self, send_goal_future)
524  self.goal_handlegoal_handle = send_goal_future.result()
525 
526  if not self.goal_handlegoal_handle.accepted:
527  self.errorerror('Get path was rejected!')
528  return None
529 
530  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
531  rclpy.spin_until_future_complete(self, self.result_futureresult_future)
532  self.statusstatus = self.result_futureresult_future.result().status
533 
534  return self.result_futureresult_future.result().result
535 
536  def getPath(self, start, goal, planner_id='', use_start=False):
537  """Send a `ComputePathToPose` action request."""
538  rtn = self._getPathImpl_getPathImpl(start, goal, planner_id, use_start)
539 
540  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
541  self.warnwarn(f'Getting path failed with status code: {self.status}')
542  return None
543 
544  if not rtn:
545  return None
546  else:
547  return rtn.path
548 
549  def _getPathThroughPosesImpl(self, start, goals, planner_id='', use_start=False):
550  """
551  Send a `ComputePathThroughPoses` action request.
552 
553  Internal implementation to get the full result, not just the path.
554  """
555  self.debugdebug("Waiting for 'ComputePathThroughPoses' action server")
556  while not self.compute_path_through_poses_clientcompute_path_through_poses_client.wait_for_server(
557  timeout_sec=1.0
558  ):
559  self.infoinfo(
560  "'ComputePathThroughPoses' action server not available, waiting..."
561  )
562 
563  goal_msg = ComputePathThroughPoses.Goal()
564  goal_msg.start = start
565  goal_msg.goals = goals
566  goal_msg.planner_id = planner_id
567  goal_msg.use_start = use_start
568 
569  self.infoinfo('Getting path...')
570  send_goal_future = self.compute_path_through_poses_clientcompute_path_through_poses_client.send_goal_async(
571  goal_msg
572  )
573  rclpy.spin_until_future_complete(self, send_goal_future)
574  self.goal_handlegoal_handle = send_goal_future.result()
575 
576  if not self.goal_handlegoal_handle.accepted:
577  self.errorerror('Get path was rejected!')
578  return None
579 
580  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
581  rclpy.spin_until_future_complete(self, self.result_futureresult_future)
582  self.statusstatus = self.result_futureresult_future.result().status
583 
584  return self.result_futureresult_future.result().result
585 
586  def getPathThroughPoses(self, start, goals, planner_id='', use_start=False):
587  """Send a `ComputePathThroughPoses` action request."""
588  rtn = self._getPathThroughPosesImpl_getPathThroughPosesImpl(start, goals, planner_id, use_start)
589 
590  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
591  self.warnwarn(f'Getting path failed with status code: {self.status}')
592  return None
593 
594  if not rtn:
595  return None
596  else:
597  return rtn.path
598 
599  def _smoothPathImpl(
600  self, path, smoother_id='', max_duration=2.0, check_for_collision=False
601  ):
602  """
603  Send a `SmoothPath` action request.
604 
605  Internal implementation to get the full result, not just the path.
606  """
607  self.debugdebug("Waiting for 'SmoothPath' action server")
608  while not self.smoother_clientsmoother_client.wait_for_server(timeout_sec=1.0):
609  self.infoinfo("'SmoothPath' action server not available, waiting...")
610 
611  goal_msg = SmoothPath.Goal()
612  goal_msg.path = path
613  goal_msg.max_smoothing_duration = rclpyDuration(seconds=max_duration).to_msg()
614  goal_msg.smoother_id = smoother_id
615  goal_msg.check_for_collisions = check_for_collision
616 
617  self.infoinfo('Smoothing path...')
618  send_goal_future = self.smoother_clientsmoother_client.send_goal_async(goal_msg)
619  rclpy.spin_until_future_complete(self, send_goal_future)
620  self.goal_handlegoal_handle = send_goal_future.result()
621 
622  if not self.goal_handlegoal_handle.accepted:
623  self.errorerror('Smooth path was rejected!')
624  return None
625 
626  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
627  rclpy.spin_until_future_complete(self, self.result_futureresult_future)
628  self.statusstatus = self.result_futureresult_future.result().status
629 
630  return self.result_futureresult_future.result().result
631 
633  self, path, smoother_id='', max_duration=2.0, check_for_collision=False
634  ):
635  """Send a `SmoothPath` action request."""
636  rtn = self._smoothPathImpl_smoothPathImpl(path, smoother_id, max_duration, check_for_collision)
637 
638  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
639  self.warnwarn(f'Getting path failed with status code: {self.status}')
640  return None
641 
642  if not rtn:
643  return None
644  else:
645  return rtn.path
646 
647  def changeMap(self, map_filepath):
648  """Change the current static map in the map server."""
649  while not self.change_maps_srvchange_maps_srv.wait_for_service(timeout_sec=1.0):
650  self.infoinfo('change map service not available, waiting...')
651  req = LoadMap.Request()
652  req.map_url = map_filepath
653  future = self.change_maps_srvchange_maps_srv.call_async(req)
654  rclpy.spin_until_future_complete(self, future)
655  status = future.result().result
656  if status != LoadMap.Response().RESULT_SUCCESS:
657  self.errorerror('Change map request failed!')
658  else:
659  self.infoinfo('Change map request was successful!')
660  return
661 
662  def clearAllCostmaps(self):
663  """Clear all costmaps."""
664  self.clearLocalCostmapclearLocalCostmap()
665  self.clearGlobalCostmapclearGlobalCostmap()
666  return
667 
668  def clearLocalCostmap(self):
669  """Clear local costmap."""
670  while not self.clear_costmap_local_srvclear_costmap_local_srv.wait_for_service(timeout_sec=1.0):
671  self.infoinfo('Clear local costmaps service not available, waiting...')
672  req = ClearEntireCostmap.Request()
673  future = self.clear_costmap_local_srvclear_costmap_local_srv.call_async(req)
674  rclpy.spin_until_future_complete(self, future)
675  return
676 
678  """Clear global costmap."""
679  while not self.clear_costmap_global_srvclear_costmap_global_srv.wait_for_service(timeout_sec=1.0):
680  self.infoinfo('Clear global costmaps service not available, waiting...')
681  req = ClearEntireCostmap.Request()
682  future = self.clear_costmap_global_srvclear_costmap_global_srv.call_async(req)
683  rclpy.spin_until_future_complete(self, future)
684  return
685 
686  def clearCostmapExceptRegion(self, reset_distance: float):
687  """Clear the costmap except for a specified region."""
688  while not self.clear_costmap_except_region_srvclear_costmap_except_region_srv.wait_for_service(timeout_sec=1.0):
689  self.infoinfo('ClearCostmapExceptRegion service not available, waiting...')
690  req = ClearCostmapExceptRegion.Request()
691  req.reset_distance = reset_distance
692  future = self.clear_costmap_except_region_srvclear_costmap_except_region_srv.call_async(req)
693  rclpy.spin_until_future_complete(self, future)
694  return
695 
696  def clearCostmapAroundRobot(self, reset_distance: float):
697  """Clear the costmap around the robot."""
698  while not self.clear_costmap_around_robot_srvclear_costmap_around_robot_srv.wait_for_service(timeout_sec=1.0):
699  self.infoinfo('ClearCostmapAroundRobot service not available, waiting...')
700  req = ClearCostmapAroundRobot.Request()
701  req.reset_distance = reset_distance
702  future = self.clear_costmap_around_robot_srvclear_costmap_around_robot_srv.call_async(req)
703  rclpy.spin_until_future_complete(self, future)
704  return
705 
706  def clearCostmapAroundPose(self, pose: PoseStamped, reset_distance: float):
707  """Clear the costmap around a specified pose."""
708  while not self.clear_costmap_around_pose_srvclear_costmap_around_pose_srv.wait_for_service(timeout_sec=1.0):
709  self.infoinfo('ClearCostmapAroundPose service not available, waiting...')
710  req = ClearCostmapAroundPose.Request()
711  req.pose = pose
712  req.reset_distance = reset_distance
713  future = self.clear_costmap_around_pose_srvclear_costmap_around_pose_srv.call_async(req)
714  rclpy.spin_until_future_complete(self, future)
715  return
716 
717  def getGlobalCostmap(self):
718  """Get the global costmap."""
719  while not self.get_costmap_global_srvget_costmap_global_srv.wait_for_service(timeout_sec=1.0):
720  self.infoinfo('Get global costmaps service not available, waiting...')
721  req = GetCostmap.Request()
722  future = self.get_costmap_global_srvget_costmap_global_srv.call_async(req)
723  rclpy.spin_until_future_complete(self, future)
724  return future.result().map
725 
726  def getLocalCostmap(self):
727  """Get the local costmap."""
728  while not self.get_costmap_local_srvget_costmap_local_srv.wait_for_service(timeout_sec=1.0):
729  self.infoinfo('Get local costmaps service not available, waiting...')
730  req = GetCostmap.Request()
731  future = self.get_costmap_local_srvget_costmap_local_srv.call_async(req)
732  rclpy.spin_until_future_complete(self, future)
733  return future.result().map
734 
735  def lifecycleStartup(self):
736  """Startup nav2 lifecycle system."""
737  self.infoinfo('Starting up lifecycle nodes based on lifecycle_manager.')
738  for srv_name, srv_type in self.get_service_names_and_types():
739  if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
740  self.infoinfo(f'Starting up {srv_name}')
741  mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
742  while not mgr_client.wait_for_service(timeout_sec=1.0):
743  self.infoinfo(f'{srv_name} service not available, waiting...')
744  req = ManageLifecycleNodes.Request()
745  req.command = ManageLifecycleNodes.Request().STARTUP
746  future = mgr_client.call_async(req)
747 
748  # starting up requires a full map->odom->base_link TF tree
749  # so if we're not successful, try forwarding the initial pose
750  while True:
751  rclpy.spin_until_future_complete(self, future, timeout_sec=0.10)
752  if not future:
753  self._waitForInitialPose_waitForInitialPose()
754  else:
755  break
756  self.infoinfo('Nav2 is ready for use!')
757  return
758 
759  def lifecycleShutdown(self):
760  """Shutdown nav2 lifecycle system."""
761  self.infoinfo('Shutting down lifecycle nodes based on lifecycle_manager.')
762  for srv_name, srv_type in self.get_service_names_and_types():
763  if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
764  self.infoinfo(f'Shutting down {srv_name}')
765  mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
766  while not mgr_client.wait_for_service(timeout_sec=1.0):
767  self.infoinfo(f'{srv_name} service not available, waiting...')
768  req = ManageLifecycleNodes.Request()
769  req.command = ManageLifecycleNodes.Request().SHUTDOWN
770  future = mgr_client.call_async(req)
771  rclpy.spin_until_future_complete(self, future)
772  future.result()
773  return
774 
775  def _waitForNodeToActivate(self, node_name):
776  # Waits for the node within the tester namespace to become active
777  self.debugdebug(f'Waiting for {node_name} to become active..')
778  node_service = f'{node_name}/get_state'
779  state_client = self.create_client(GetState, node_service)
780  while not state_client.wait_for_service(timeout_sec=1.0):
781  self.infoinfo(f'{node_service} service not available, waiting...')
782 
783  req = GetState.Request()
784  state = 'unknown'
785  while state != 'active':
786  self.debugdebug(f'Getting {node_name} state...')
787  future = state_client.call_async(req)
788  rclpy.spin_until_future_complete(self, future)
789  if future.result() is not None:
790  state = future.result().current_state.label
791  self.debugdebug(f'Result of get_state: {state}')
792  time.sleep(2)
793  return
794 
795  def _waitForInitialPose(self):
796  while not self.initial_pose_receivedinitial_pose_received:
797  self.infoinfo('Setting initial pose')
798  self._setInitialPose_setInitialPose()
799  self.infoinfo('Waiting for amcl_pose to be received')
800  rclpy.spin_once(self, timeout_sec=1.0)
801  return
802 
803  def _amclPoseCallback(self, msg):
804  self.debugdebug('Received amcl pose')
805  self.initial_pose_receivedinitial_pose_received = True
806  return
807 
808  def _feedbackCallback(self, msg):
809  self.debugdebug('Received action feedback message')
810  self.feedbackfeedback = msg.feedback
811  return
812 
813  def _setInitialPose(self):
814  msg = PoseWithCovarianceStamped()
815  msg.pose.pose = self.initial_poseinitial_pose.pose
816  msg.header.frame_id = self.initial_poseinitial_pose.header.frame_id
817  msg.header.stamp = self.initial_poseinitial_pose.header.stamp
818  self.infoinfo('Publishing Initial Pose')
819  self.initial_pose_pubinitial_pose_pub.publish(msg)
820  return
821 
822  def info(self, msg):
823  self.get_logger().info(msg)
824  return
825 
826  def warn(self, msg):
827  self.get_logger().warn(msg)
828  return
829 
830  def error(self, msg):
831  self.get_logger().error(msg)
832  return
833 
834  def debug(self, msg):
835  self.get_logger().debug(msg)
836  return
def _smoothPathImpl(self, path, smoother_id='', max_duration=2.0, check_for_collision=False)
def smoothPath(self, path, smoother_id='', max_duration=2.0, check_for_collision=False)
def getPath(self, start, goal, planner_id='', use_start=False)
def dockRobotByID(self, dock_id, nav_to_dock=True)
def clearCostmapAroundRobot(self, float reset_distance)
def _getPathThroughPosesImpl(self, start, goals, planner_id='', use_start=False)
def getPathThroughPoses(self, start, goals, planner_id='', use_start=False)
def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl')
def goThroughPoses(self, poses, behavior_tree='')
def clearCostmapAroundPose(self, PoseStamped pose, float reset_distance)
def _getPathImpl(self, start, goal, planner_id='', use_start=False)
def clearCostmapExceptRegion(self, float reset_distance)
def followPath(self, path, controller_id='', goal_checker_id='')
def dockRobotByPose(self, dock_pose, dock_type, nav_to_dock=True)