Nav2 Navigation Stack - humble  humble
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, Spin
27 from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose
28 from nav2_msgs.action import FollowPath, FollowWaypoints, NavigateThroughPoses, NavigateToPose
29 from nav2_msgs.action import SmoothPath
30 from nav2_msgs.srv import ClearEntireCostmap, GetCostmap, LoadMap, ManageLifecycleNodes
31 
32 import rclpy
33 from rclpy.action import ActionClient
34 from rclpy.duration import Duration as rclpyDuration
35 from rclpy.node import Node
36 from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy
37 from rclpy.qos import QoSProfile, QoSReliabilityPolicy
38 
39 
40 class TaskResult(Enum):
41  UNKNOWN = 0
42  SUCCEEDED = 1
43  CANCELED = 2
44  FAILED = 3
45 
46 
47 class BasicNavigator(Node):
48 
49  def __init__(self, node_name='basic_navigator', namespace=''):
50  super().__init__(node_name=node_name, namespace=namespace)
51  self.initial_poseinitial_pose = PoseStamped()
52  self.initial_poseinitial_pose.header.frame_id = 'map'
53  self.goal_handlegoal_handle = None
54  self.result_futureresult_future = None
55  self.feedbackfeedback = None
56  self.statusstatus = None
57 
58  amcl_pose_qos = QoSProfile(
59  durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
60  reliability=QoSReliabilityPolicy.RELIABLE,
61  history=QoSHistoryPolicy.KEEP_LAST,
62  depth=1)
63 
64  self.initial_pose_receivedinitial_pose_received = False
65  self.nav_through_poses_clientnav_through_poses_client = ActionClient(self,
66  NavigateThroughPoses,
67  'navigate_through_poses')
68  self.nav_to_pose_clientnav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
69  self.follow_waypoints_clientfollow_waypoints_client = ActionClient(self, FollowWaypoints, 'follow_waypoints')
70  self.follow_path_clientfollow_path_client = ActionClient(self, FollowPath, 'follow_path')
71  self.compute_path_to_pose_clientcompute_path_to_pose_client = ActionClient(self, ComputePathToPose,
72  'compute_path_to_pose')
73  self.compute_path_through_poses_clientcompute_path_through_poses_client = ActionClient(self, ComputePathThroughPoses,
74  'compute_path_through_poses')
75  self.smoother_clientsmoother_client = ActionClient(self, SmoothPath, 'smooth_path')
76  self.spin_clientspin_client = ActionClient(self, Spin, 'spin')
77  self.backup_clientbackup_client = ActionClient(self, BackUp, 'backup')
78  self.assisted_teleop_clientassisted_teleop_client = ActionClient(self, AssistedTeleop, 'assisted_teleop')
79  self.localization_pose_sublocalization_pose_sub = self.create_subscription(PoseWithCovarianceStamped,
80  'amcl_pose',
81  self._amclPoseCallback_amclPoseCallback,
82  amcl_pose_qos)
83  self.initial_pose_pubinitial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
84  'initialpose',
85  10)
86  self.change_maps_srvchange_maps_srv = self.create_client(LoadMap, 'map_server/load_map')
87  self.clear_costmap_global_srvclear_costmap_global_srv = self.create_client(
88  ClearEntireCostmap, 'global_costmap/clear_entirely_global_costmap')
89  self.clear_costmap_local_srvclear_costmap_local_srv = self.create_client(
90  ClearEntireCostmap, 'local_costmap/clear_entirely_local_costmap')
91  self.get_costmap_global_srvget_costmap_global_srv = self.create_client(GetCostmap, 'global_costmap/get_costmap')
92  self.get_costmap_local_srvget_costmap_local_srv = self.create_client(GetCostmap, 'local_costmap/get_costmap')
93 
94  def destroyNode(self):
95  self.destroy_nodedestroy_node()
96 
97  def destroy_node(self):
98  self.nav_through_poses_clientnav_through_poses_client.destroy()
99  self.nav_to_pose_clientnav_to_pose_client.destroy()
100  self.follow_waypoints_clientfollow_waypoints_client.destroy()
101  self.follow_path_clientfollow_path_client.destroy()
102  self.compute_path_to_pose_clientcompute_path_to_pose_client.destroy()
103  self.compute_path_through_poses_clientcompute_path_through_poses_client.destroy()
104  self.smoother_clientsmoother_client.destroy()
105  self.spin_clientspin_client.destroy()
106  self.backup_clientbackup_client.destroy()
107  super().destroy_node()
108 
109  def setInitialPose(self, initial_pose):
110  """Set the initial pose to the localization system."""
111  self.initial_pose_receivedinitial_pose_received = False
112  self.initial_poseinitial_pose = initial_pose
113  self._setInitialPose_setInitialPose()
114 
115  def goThroughPoses(self, poses, behavior_tree=''):
116  """Send a `NavThroughPoses` action request."""
117  self.debugdebug("Waiting for 'NavigateThroughPoses' action server")
118  while not self.nav_through_poses_clientnav_through_poses_client.wait_for_server(timeout_sec=1.0):
119  self.infoinfo("'NavigateThroughPoses' action server not available, waiting...")
120 
121  goal_msg = NavigateThroughPoses.Goal()
122  goal_msg.poses = poses
123  goal_msg.behavior_tree = behavior_tree
124 
125  self.infoinfo(f'Navigating with {len(goal_msg.poses)} goals....')
126  send_goal_future = self.nav_through_poses_clientnav_through_poses_client.send_goal_async(goal_msg,
127  self._feedbackCallback_feedbackCallback)
128  rclpy.spin_until_future_complete(self, send_goal_future)
129  self.goal_handlegoal_handle = send_goal_future.result()
130 
131  if not self.goal_handlegoal_handle.accepted:
132  self.errorerror(f'Goal with {len(poses)} poses was rejected!')
133  return False
134 
135  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
136  return True
137 
138  def goToPose(self, pose, behavior_tree=''):
139  """Send a `NavToPose` action request."""
140  self.debugdebug("Waiting for 'NavigateToPose' action server")
141  while not self.nav_to_pose_clientnav_to_pose_client.wait_for_server(timeout_sec=1.0):
142  self.infoinfo("'NavigateToPose' action server not available, waiting...")
143 
144  goal_msg = NavigateToPose.Goal()
145  goal_msg.pose = pose
146  goal_msg.behavior_tree = behavior_tree
147 
148  self.infoinfo('Navigating to goal: ' + str(pose.pose.position.x) + ' ' +
149  str(pose.pose.position.y) + '...')
150  send_goal_future = self.nav_to_pose_clientnav_to_pose_client.send_goal_async(goal_msg,
151  self._feedbackCallback_feedbackCallback)
152  rclpy.spin_until_future_complete(self, send_goal_future)
153  self.goal_handlegoal_handle = send_goal_future.result()
154 
155  if not self.goal_handlegoal_handle.accepted:
156  self.errorerror('Goal to ' + str(pose.pose.position.x) + ' ' +
157  str(pose.pose.position.y) + ' was rejected!')
158  return False
159 
160  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
161  return True
162 
163  def followWaypoints(self, poses):
164  """Send a `FollowWaypoints` action request."""
165  self.debugdebug("Waiting for 'FollowWaypoints' action server")
166  while not self.follow_waypoints_clientfollow_waypoints_client.wait_for_server(timeout_sec=1.0):
167  self.infoinfo("'FollowWaypoints' action server not available, waiting...")
168 
169  goal_msg = FollowWaypoints.Goal()
170  goal_msg.poses = poses
171 
172  self.infoinfo(f'Following {len(goal_msg.poses)} goals....')
173  send_goal_future = self.follow_waypoints_clientfollow_waypoints_client.send_goal_async(goal_msg,
174  self._feedbackCallback_feedbackCallback)
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'Following {len(poses)} waypoints request was rejected!')
180  return False
181 
182  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
183  return True
184 
185  def spin(self, spin_dist=1.57, time_allowance=10):
186  self.debugdebug("Waiting for 'Spin' action server")
187  while not self.spin_clientspin_client.wait_for_server(timeout_sec=1.0):
188  self.infoinfo("'Spin' action server not available, waiting...")
189  goal_msg = Spin.Goal()
190  goal_msg.target_yaw = spin_dist
191  goal_msg.time_allowance = Duration(sec=time_allowance)
192 
193  self.infoinfo(f'Spinning to angle {goal_msg.target_yaw}....')
194  send_goal_future = self.spin_clientspin_client.send_goal_async(goal_msg, self._feedbackCallback_feedbackCallback)
195  rclpy.spin_until_future_complete(self, send_goal_future)
196  self.goal_handlegoal_handle = send_goal_future.result()
197 
198  if not self.goal_handlegoal_handle.accepted:
199  self.errorerror('Spin request was rejected!')
200  return False
201 
202  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
203  return True
204 
205  def backup(self, backup_dist=0.15, backup_speed=0.025, time_allowance=10):
206  self.debugdebug("Waiting for 'Backup' action server")
207  while not self.backup_clientbackup_client.wait_for_server(timeout_sec=1.0):
208  self.infoinfo("'Backup' action server not available, waiting...")
209  goal_msg = BackUp.Goal()
210  goal_msg.target = Point(x=float(backup_dist))
211  goal_msg.speed = backup_speed
212  goal_msg.time_allowance = Duration(sec=time_allowance)
213 
214  self.infoinfo(f'Backing up {goal_msg.target.x} m at {goal_msg.speed} m/s....')
215  send_goal_future = self.backup_clientbackup_client.send_goal_async(goal_msg, self._feedbackCallback_feedbackCallback)
216  rclpy.spin_until_future_complete(self, send_goal_future)
217  self.goal_handlegoal_handle = send_goal_future.result()
218 
219  if not self.goal_handlegoal_handle.accepted:
220  self.errorerror('Backup request was rejected!')
221  return False
222 
223  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
224  return True
225 
226  def assistedTeleop(self, time_allowance=30):
227  self.debugdebug("Wainting for 'assisted_teleop' action server")
228  while not self.assisted_teleop_clientassisted_teleop_client.wait_for_server(timeout_sec=1.0):
229  self.infoinfo("'assisted_teleop' action server not available, waiting...")
230  goal_msg = AssistedTeleop.Goal()
231  goal_msg.time_allowance = Duration(sec=time_allowance)
232 
233  self.infoinfo("Running 'assisted_teleop'....")
234  send_goal_future = \
235  self.assisted_teleop_clientassisted_teleop_client.send_goal_async(goal_msg, self._feedbackCallback_feedbackCallback)
236  rclpy.spin_until_future_complete(self, send_goal_future)
237  self.goal_handlegoal_handle = send_goal_future.result()
238 
239  if not self.goal_handlegoal_handle.accepted:
240  self.errorerror('Assisted Teleop request was rejected!')
241  return False
242 
243  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
244  return True
245 
246  def followPath(self, path, controller_id='', goal_checker_id=''):
247  """Send a `FollowPath` action request."""
248  self.debugdebug("Waiting for 'FollowPath' action server")
249  while not self.follow_path_clientfollow_path_client.wait_for_server(timeout_sec=1.0):
250  self.infoinfo("'FollowPath' action server not available, waiting...")
251 
252  goal_msg = FollowPath.Goal()
253  goal_msg.path = path
254  goal_msg.controller_id = controller_id
255  goal_msg.goal_checker_id = goal_checker_id
256 
257  self.infoinfo('Executing path...')
258  send_goal_future = self.follow_path_clientfollow_path_client.send_goal_async(goal_msg,
259  self._feedbackCallback_feedbackCallback)
260  rclpy.spin_until_future_complete(self, send_goal_future)
261  self.goal_handlegoal_handle = send_goal_future.result()
262 
263  if not self.goal_handlegoal_handle.accepted:
264  self.errorerror('Follow path was rejected!')
265  return False
266 
267  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
268  return True
269 
270  def cancelTask(self):
271  """Cancel pending task request of any type."""
272  self.infoinfo('Canceling current task.')
273  if self.result_futureresult_future:
274  future = self.goal_handlegoal_handle.cancel_goal_async()
275  rclpy.spin_until_future_complete(self, future)
276  return
277 
278  def isTaskComplete(self):
279  """Check if the task request of any type is complete yet."""
280  if not self.result_futureresult_future:
281  # task was cancelled or completed
282  return True
283  rclpy.spin_until_future_complete(self, self.result_futureresult_future, timeout_sec=0.10)
284  if self.result_futureresult_future.result():
285  self.statusstatus = self.result_futureresult_future.result().status
286  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
287  self.debugdebug(f'Task with failed with status code: {self.status}')
288  return True
289  else:
290  # Timed out, still processing, not complete yet
291  return False
292 
293  self.debugdebug('Task succeeded!')
294  return True
295 
296  def getFeedback(self):
297  """Get the pending action feedback message."""
298  return self.feedbackfeedback
299 
300  def getResult(self):
301  """Get the pending action result message."""
302  if self.statusstatus == GoalStatus.STATUS_SUCCEEDED:
303  return TaskResult.SUCCEEDED
304  elif self.statusstatus == GoalStatus.STATUS_ABORTED:
305  return TaskResult.FAILED
306  elif self.statusstatus == GoalStatus.STATUS_CANCELED:
307  return TaskResult.CANCELED
308  else:
309  return TaskResult.UNKNOWN
310 
311  def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl'):
312  """Block until the full navigation system is up and running."""
313  self._waitForNodeToActivate_waitForNodeToActivate(localizer)
314  if localizer == 'amcl':
315  self._waitForInitialPose_waitForInitialPose()
316  self._waitForNodeToActivate_waitForNodeToActivate(navigator)
317  self.infoinfo('Nav2 is ready for use!')
318  return
319 
320  def _getPathImpl(self, start, goal, planner_id='', use_start=False):
321  """
322  Send a `ComputePathToPose` action request.
323 
324  Internal implementation to get the full result, not just the path.
325  """
326  self.debugdebug("Waiting for 'ComputePathToPose' action server")
327  while not self.compute_path_to_pose_clientcompute_path_to_pose_client.wait_for_server(timeout_sec=1.0):
328  self.infoinfo("'ComputePathToPose' action server not available, waiting...")
329 
330  goal_msg = ComputePathToPose.Goal()
331  goal_msg.start = start
332  goal_msg.goal = goal
333  goal_msg.planner_id = planner_id
334  goal_msg.use_start = use_start
335 
336  self.infoinfo('Getting path...')
337  send_goal_future = self.compute_path_to_pose_clientcompute_path_to_pose_client.send_goal_async(goal_msg)
338  rclpy.spin_until_future_complete(self, send_goal_future)
339  self.goal_handlegoal_handle = send_goal_future.result()
340 
341  if not self.goal_handlegoal_handle.accepted:
342  self.errorerror('Get path was rejected!')
343  return None
344 
345  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
346  rclpy.spin_until_future_complete(self, self.result_futureresult_future)
347  self.statusstatus = self.result_futureresult_future.result().status
348  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
349  self.warnwarn(f'Getting path failed with status code: {self.status}')
350  return None
351 
352  return self.result_futureresult_future.result().result
353 
354  def getPath(self, start, goal, planner_id='', use_start=False):
355  """Send a `ComputePathToPose` action request."""
356  rtn = self._getPathImpl_getPathImpl(start, goal, planner_id, use_start)
357  if not rtn:
358  return None
359  else:
360  return rtn.path
361 
362  def getPathThroughPoses(self, start, goals, planner_id='', use_start=False):
363  """Send a `ComputePathThroughPoses` action request."""
364  self.debugdebug("Waiting for 'ComputePathThroughPoses' action server")
365  while not self.compute_path_through_poses_clientcompute_path_through_poses_client.wait_for_server(timeout_sec=1.0):
366  self.infoinfo("'ComputePathThroughPoses' action server not available, waiting...")
367 
368  goal_msg = ComputePathThroughPoses.Goal()
369  goal_msg.start = start
370  goal_msg.goals = goals
371  goal_msg.planner_id = planner_id
372  goal_msg.use_start = use_start
373 
374  self.infoinfo('Getting path...')
375  send_goal_future = self.compute_path_through_poses_clientcompute_path_through_poses_client.send_goal_async(goal_msg)
376  rclpy.spin_until_future_complete(self, send_goal_future)
377  self.goal_handlegoal_handle = send_goal_future.result()
378 
379  if not self.goal_handlegoal_handle.accepted:
380  self.errorerror('Get path was rejected!')
381  return None
382 
383  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
384  rclpy.spin_until_future_complete(self, self.result_futureresult_future)
385  self.statusstatus = self.result_futureresult_future.result().status
386  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
387  self.warnwarn(f'Getting path failed with status code: {self.status}')
388  return None
389 
390  return self.result_futureresult_future.result().result.path
391 
392  def _smoothPathImpl(self, path, smoother_id='', max_duration=2.0, check_for_collision=False):
393  """
394  Send a `SmoothPath` action request.
395 
396  Internal implementation to get the full result, not just the path.
397  """
398  self.debugdebug("Waiting for 'SmoothPath' action server")
399  while not self.smoother_clientsmoother_client.wait_for_server(timeout_sec=1.0):
400  self.infoinfo("'SmoothPath' action server not available, waiting...")
401 
402  goal_msg = SmoothPath.Goal()
403  goal_msg.path = path
404  goal_msg.max_smoothing_duration = rclpyDuration(seconds=max_duration).to_msg()
405  goal_msg.smoother_id = smoother_id
406  goal_msg.check_for_collisions = check_for_collision
407 
408  self.infoinfo('Smoothing path...')
409  send_goal_future = self.smoother_clientsmoother_client.send_goal_async(goal_msg)
410  rclpy.spin_until_future_complete(self, send_goal_future)
411  self.goal_handlegoal_handle = send_goal_future.result()
412 
413  if not self.goal_handlegoal_handle.accepted:
414  self.errorerror('Smooth path was rejected!')
415  return None
416 
417  self.result_futureresult_future = self.goal_handlegoal_handle.get_result_async()
418  rclpy.spin_until_future_complete(self, self.result_futureresult_future)
419  self.statusstatus = self.result_futureresult_future.result().status
420  if self.statusstatus != GoalStatus.STATUS_SUCCEEDED:
421  self.warnwarn(f'Getting path failed with status code: {self.status}')
422  return None
423 
424  return self.result_futureresult_future.result().result
425 
426  def smoothPath(self, path, smoother_id='', max_duration=2.0, check_for_collision=False):
427  """Send a `SmoothPath` action request."""
428  rtn = self._smoothPathImpl_smoothPathImpl(
429  path, smoother_id, max_duration, check_for_collision)
430  if not rtn:
431  return None
432  else:
433  return rtn.path
434 
435  def changeMap(self, map_filepath):
436  """Change the current static map in the map server."""
437  while not self.change_maps_srvchange_maps_srv.wait_for_service(timeout_sec=1.0):
438  self.infoinfo('change map service not available, waiting...')
439  req = LoadMap.Request()
440  req.map_url = map_filepath
441  future = self.change_maps_srvchange_maps_srv.call_async(req)
442  rclpy.spin_until_future_complete(self, future)
443  status = future.result().result
444  if status != LoadMap.Response().RESULT_SUCCESS:
445  self.errorerror('Change map request failed!')
446  else:
447  self.infoinfo('Change map request was successful!')
448  return
449 
450  def clearAllCostmaps(self):
451  """Clear all costmaps."""
452  self.clearLocalCostmapclearLocalCostmap()
453  self.clearGlobalCostmapclearGlobalCostmap()
454  return
455 
456  def clearLocalCostmap(self):
457  """Clear local costmap."""
458  while not self.clear_costmap_local_srvclear_costmap_local_srv.wait_for_service(timeout_sec=1.0):
459  self.infoinfo('Clear local costmaps service not available, waiting...')
460  req = ClearEntireCostmap.Request()
461  future = self.clear_costmap_local_srvclear_costmap_local_srv.call_async(req)
462  rclpy.spin_until_future_complete(self, future)
463  return
464 
466  """Clear global costmap."""
467  while not self.clear_costmap_global_srvclear_costmap_global_srv.wait_for_service(timeout_sec=1.0):
468  self.infoinfo('Clear global costmaps service not available, waiting...')
469  req = ClearEntireCostmap.Request()
470  future = self.clear_costmap_global_srvclear_costmap_global_srv.call_async(req)
471  rclpy.spin_until_future_complete(self, future)
472  return
473 
474  def getGlobalCostmap(self):
475  """Get the global costmap."""
476  while not self.get_costmap_global_srvget_costmap_global_srv.wait_for_service(timeout_sec=1.0):
477  self.infoinfo('Get global costmaps service not available, waiting...')
478  req = GetCostmap.Request()
479  future = self.get_costmap_global_srvget_costmap_global_srv.call_async(req)
480  rclpy.spin_until_future_complete(self, future)
481  return future.result().map
482 
483  def getLocalCostmap(self):
484  """Get the local costmap."""
485  while not self.get_costmap_local_srvget_costmap_local_srv.wait_for_service(timeout_sec=1.0):
486  self.infoinfo('Get local costmaps service not available, waiting...')
487  req = GetCostmap.Request()
488  future = self.get_costmap_local_srvget_costmap_local_srv.call_async(req)
489  rclpy.spin_until_future_complete(self, future)
490  return future.result().map
491 
492  def lifecycleStartup(self):
493  """Startup nav2 lifecycle system."""
494  self.infoinfo('Starting up lifecycle nodes based on lifecycle_manager.')
495  for srv_name, srv_type in self.get_service_names_and_types():
496  if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
497  self.infoinfo(f'Starting up {srv_name}')
498  mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
499  while not mgr_client.wait_for_service(timeout_sec=1.0):
500  self.infoinfo(f'{srv_name} service not available, waiting...')
501  req = ManageLifecycleNodes.Request()
502  req.command = ManageLifecycleNodes.Request().STARTUP
503  future = mgr_client.call_async(req)
504 
505  # starting up requires a full map->odom->base_link TF tree
506  # so if we're not successful, try forwarding the initial pose
507  while True:
508  rclpy.spin_until_future_complete(self, future, timeout_sec=0.10)
509  if not future:
510  self._waitForInitialPose_waitForInitialPose()
511  else:
512  break
513  self.infoinfo('Nav2 is ready for use!')
514  return
515 
516  def lifecycleShutdown(self):
517  """Shutdown nav2 lifecycle system."""
518  self.infoinfo('Shutting down lifecycle nodes based on lifecycle_manager.')
519  for srv_name, srv_type in self.get_service_names_and_types():
520  if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
521  self.infoinfo(f'Shutting down {srv_name}')
522  mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
523  while not mgr_client.wait_for_service(timeout_sec=1.0):
524  self.infoinfo(f'{srv_name} service not available, waiting...')
525  req = ManageLifecycleNodes.Request()
526  req.command = ManageLifecycleNodes.Request().SHUTDOWN
527  future = mgr_client.call_async(req)
528  rclpy.spin_until_future_complete(self, future)
529  future.result()
530  return
531 
532  def _waitForNodeToActivate(self, node_name):
533  # Waits for the node within the tester namespace to become active
534  self.debugdebug(f'Waiting for {node_name} to become active..')
535  node_service = f'{node_name}/get_state'
536  state_client = self.create_client(GetState, node_service)
537  while not state_client.wait_for_service(timeout_sec=1.0):
538  self.infoinfo(f'{node_service} service not available, waiting...')
539 
540  req = GetState.Request()
541  state = 'unknown'
542  while state != 'active':
543  self.debugdebug(f'Getting {node_name} state...')
544  future = state_client.call_async(req)
545  rclpy.spin_until_future_complete(self, future)
546  if future.result() is not None:
547  state = future.result().current_state.label
548  self.debugdebug(f'Result of get_state: {state}')
549  time.sleep(2)
550  return
551 
552  def _waitForInitialPose(self):
553  while not self.initial_pose_receivedinitial_pose_received:
554  self.infoinfo('Setting initial pose')
555  self._setInitialPose_setInitialPose()
556  self.infoinfo('Waiting for amcl_pose to be received')
557  rclpy.spin_once(self, timeout_sec=1.0)
558  return
559 
560  def _amclPoseCallback(self, msg):
561  self.debugdebug('Received amcl pose')
562  self.initial_pose_receivedinitial_pose_received = True
563  return
564 
565  def _feedbackCallback(self, msg):
566  self.debugdebug('Received action feedback message')
567  self.feedbackfeedback = msg.feedback
568  return
569 
570  def _setInitialPose(self):
571  msg = PoseWithCovarianceStamped()
572  msg.pose.pose = self.initial_poseinitial_pose.pose
573  msg.header.frame_id = self.initial_poseinitial_pose.header.frame_id
574  msg.header.stamp = self.initial_poseinitial_pose.header.stamp
575  self.infoinfo('Publishing Initial Pose')
576  self.initial_pose_pubinitial_pose_pub.publish(msg)
577  return
578 
579  def info(self, msg):
580  self.get_logger().info(msg)
581  return
582 
583  def warn(self, msg):
584  self.get_logger().warn(msg)
585  return
586 
587  def error(self, msg):
588  self.get_logger().error(msg)
589  return
590 
591  def debug(self, msg):
592  self.get_logger().debug(msg)
593  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 getPathThroughPoses(self, start, goals, planner_id='', use_start=False)
def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl')
def goThroughPoses(self, poses, behavior_tree='')
def _getPathImpl(self, start, goal, planner_id='', use_start=False)
def followPath(self, path, controller_id='', goal_checker_id='')