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
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
49 def __init__(self, node_name='basic_navigator', namespace=''):
50 super().__init__(node_name=node_name, namespace=namespace)
58 amcl_pose_qos = QoSProfile(
59 durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
60 reliability=QoSReliabilityPolicy.RELIABLE,
61 history=QoSHistoryPolicy.KEEP_LAST,
67 'navigate_through_poses')
68 self.
nav_to_pose_clientnav_to_pose_client = ActionClient(self, NavigateToPose,
'navigate_to_pose')
70 self.
follow_path_clientfollow_path_client = ActionClient(self, FollowPath,
'follow_path')
72 'compute_path_to_pose')
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')
83 self.
initial_pose_pubinitial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
86 self.
change_maps_srvchange_maps_srv = self.create_client(LoadMap,
'map_server/load_map')
88 ClearEntireCostmap,
'global_costmap/clear_entirely_global_costmap')
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')
94 def destroyNode(self):
97 def destroy_node(self):
107 super().destroy_node()
110 """Set the initial pose to the localization system."""
116 """Send a `NavThroughPoses` action request."""
117 self.
debugdebug(
"Waiting for 'NavigateThroughPoses' action server")
119 self.
infoinfo(
"'NavigateThroughPoses' action server not available, waiting...")
121 goal_msg = NavigateThroughPoses.Goal()
122 goal_msg.poses = poses
123 goal_msg.behavior_tree = behavior_tree
125 self.
infoinfo(f
'Navigating with {len(goal_msg.poses)} goals....')
128 rclpy.spin_until_future_complete(self, send_goal_future)
129 self.
goal_handlegoal_handle = send_goal_future.result()
132 self.
errorerror(f
'Goal with {len(poses)} poses was rejected!')
139 """Send a `NavToPose` action request."""
140 self.
debugdebug(
"Waiting for 'NavigateToPose' action server")
142 self.
infoinfo(
"'NavigateToPose' action server not available, waiting...")
144 goal_msg = NavigateToPose.Goal()
146 goal_msg.behavior_tree = behavior_tree
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,
152 rclpy.spin_until_future_complete(self, send_goal_future)
153 self.
goal_handlegoal_handle = send_goal_future.result()
156 self.
errorerror(
'Goal to ' + str(pose.pose.position.x) +
' ' +
157 str(pose.pose.position.y) +
' was rejected!')
164 """Send a `FollowWaypoints` action request."""
165 self.
debugdebug(
"Waiting for 'FollowWaypoints' action server")
167 self.
infoinfo(
"'FollowWaypoints' action server not available, waiting...")
169 goal_msg = FollowWaypoints.Goal()
170 goal_msg.poses = poses
172 self.
infoinfo(f
'Following {len(goal_msg.poses)} goals....')
175 rclpy.spin_until_future_complete(self, send_goal_future)
176 self.
goal_handlegoal_handle = send_goal_future.result()
179 self.
errorerror(f
'Following {len(poses)} waypoints request was rejected!')
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)
193 self.
infoinfo(f
'Spinning to angle {goal_msg.target_yaw}....')
195 rclpy.spin_until_future_complete(self, send_goal_future)
196 self.
goal_handlegoal_handle = send_goal_future.result()
199 self.
errorerror(
'Spin request was rejected!')
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)
214 self.
infoinfo(f
'Backing up {goal_msg.target.x} m at {goal_msg.speed} m/s....')
216 rclpy.spin_until_future_complete(self, send_goal_future)
217 self.
goal_handlegoal_handle = send_goal_future.result()
220 self.
errorerror(
'Backup request was rejected!')
226 def assistedTeleop(self, time_allowance=30):
227 self.
debugdebug(
"Wainting for 'assisted_teleop' action server")
229 self.
infoinfo(
"'assisted_teleop' action server not available, waiting...")
230 goal_msg = AssistedTeleop.Goal()
231 goal_msg.time_allowance = Duration(sec=time_allowance)
233 self.
infoinfo(
"Running 'assisted_teleop'....")
236 rclpy.spin_until_future_complete(self, send_goal_future)
237 self.
goal_handlegoal_handle = send_goal_future.result()
240 self.
errorerror(
'Assisted Teleop request was rejected!')
246 def followPath(self, path, controller_id='', goal_checker_id=''):
247 """Send a `FollowPath` action request."""
248 self.
debugdebug(
"Waiting for 'FollowPath' action server")
250 self.
infoinfo(
"'FollowPath' action server not available, waiting...")
252 goal_msg = FollowPath.Goal()
254 goal_msg.controller_id = controller_id
255 goal_msg.goal_checker_id = goal_checker_id
257 self.
infoinfo(
'Executing path...')
258 send_goal_future = self.
follow_path_clientfollow_path_client.send_goal_async(goal_msg,
260 rclpy.spin_until_future_complete(self, send_goal_future)
261 self.
goal_handlegoal_handle = send_goal_future.result()
264 self.
errorerror(
'Follow path was rejected!')
271 """Cancel pending task request of any type."""
272 self.
infoinfo(
'Canceling current task.')
274 future = self.
goal_handlegoal_handle.cancel_goal_async()
275 rclpy.spin_until_future_complete(self, future)
279 """Check if the task request of any type is complete yet."""
283 rclpy.spin_until_future_complete(self, self.
result_futureresult_future, timeout_sec=0.10)
286 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
287 self.
debugdebug(f
'Task with failed with status code: {self.status}')
293 self.
debugdebug(
'Task succeeded!')
297 """Get the pending action feedback message."""
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
309 return TaskResult.UNKNOWN
312 """Block until the full navigation system is up and running."""
314 if localizer ==
'amcl':
317 self.
infoinfo(
'Nav2 is ready for use!')
320 def _getPathImpl(self, start, goal, planner_id='', use_start=False):
322 Send a `ComputePathToPose` action request.
324 Internal implementation to get the full result, not just the path.
326 self.
debugdebug(
"Waiting for 'ComputePathToPose' action server")
328 self.
infoinfo(
"'ComputePathToPose' action server not available, waiting...")
330 goal_msg = ComputePathToPose.Goal()
331 goal_msg.start = start
333 goal_msg.planner_id = planner_id
334 goal_msg.use_start = use_start
336 self.
infoinfo(
'Getting path...')
338 rclpy.spin_until_future_complete(self, send_goal_future)
339 self.
goal_handlegoal_handle = send_goal_future.result()
342 self.
errorerror(
'Get path was rejected!')
346 rclpy.spin_until_future_complete(self, self.
result_futureresult_future)
348 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
349 self.
warnwarn(f
'Getting path failed with status code: {self.status}')
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)
363 """Send a `ComputePathThroughPoses` action request."""
364 self.
debugdebug(
"Waiting for 'ComputePathThroughPoses' action server")
366 self.
infoinfo(
"'ComputePathThroughPoses' action server not available, waiting...")
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
374 self.
infoinfo(
'Getting path...')
376 rclpy.spin_until_future_complete(self, send_goal_future)
377 self.
goal_handlegoal_handle = send_goal_future.result()
380 self.
errorerror(
'Get path was rejected!')
384 rclpy.spin_until_future_complete(self, self.
result_futureresult_future)
386 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
387 self.
warnwarn(f
'Getting path failed with status code: {self.status}')
392 def _smoothPathImpl(self, path, smoother_id='', max_duration=2.0, check_for_collision=False):
394 Send a `SmoothPath` action request.
396 Internal implementation to get the full result, not just the path.
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...")
402 goal_msg = SmoothPath.Goal()
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
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()
414 self.
errorerror(
'Smooth path was rejected!')
418 rclpy.spin_until_future_complete(self, self.
result_futureresult_future)
420 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
421 self.
warnwarn(f
'Getting path failed with status code: {self.status}')
426 def smoothPath(self, path, smoother_id='', max_duration=2.0, check_for_collision=False):
427 """Send a `SmoothPath` action request."""
429 path, smoother_id, max_duration, check_for_collision)
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
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!')
447 self.
infoinfo(
'Change map request was successful!')
451 """Clear all costmaps."""
457 """Clear local costmap."""
459 self.
infoinfo(
'Clear local costmaps service not available, waiting...')
460 req = ClearEntireCostmap.Request()
462 rclpy.spin_until_future_complete(self, future)
466 """Clear global costmap."""
468 self.
infoinfo(
'Clear global costmaps service not available, waiting...')
469 req = ClearEntireCostmap.Request()
471 rclpy.spin_until_future_complete(self, future)
475 """Get the global costmap."""
477 self.
infoinfo(
'Get global costmaps service not available, waiting...')
478 req = GetCostmap.Request()
480 rclpy.spin_until_future_complete(self, future)
481 return future.result().map
484 """Get the local costmap."""
486 self.
infoinfo(
'Get local costmaps service not available, waiting...')
487 req = GetCostmap.Request()
489 rclpy.spin_until_future_complete(self, future)
490 return future.result().map
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)
508 rclpy.spin_until_future_complete(self, future, timeout_sec=0.10)
513 self.
infoinfo(
'Nav2 is ready for use!')
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)
532 def _waitForNodeToActivate(self, node_name):
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...')
540 req = GetState.Request()
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}')
552 def _waitForInitialPose(self):
554 self.
infoinfo(
'Setting initial pose')
556 self.
infoinfo(
'Waiting for amcl_pose to be received')
557 rclpy.spin_once(self, timeout_sec=1.0)
560 def _amclPoseCallback(self, msg):
561 self.
debugdebug(
'Received amcl pose')
565 def _feedbackCallback(self, msg):
566 self.
debugdebug(
'Received action feedback message')
567 self.
feedbackfeedback = msg.feedback
570 def _setInitialPose(self):
571 msg = PoseWithCovarianceStamped()
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')
580 self.get_logger().info(msg)
584 self.get_logger().warn(msg)
587 def error(self, msg):
588 self.get_logger().error(msg)
591 def debug(self, msg):
592 self.get_logger().debug(msg)
def clearAllCostmaps(self)
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)
compute_path_to_pose_client
def getPath(self, start, goal, planner_id='', use_start=False)
def goToPose(self, pose, behavior_tree='')
def followWaypoints(self, poses)
def getLocalCostmap(self)
def getPathThroughPoses(self, start, goals, planner_id='', use_start=False)
def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl')
def lifecycleStartup(self)
def goThroughPoses(self, poses, behavior_tree='')
def changeMap(self, map_filepath)
def _waitForInitialPose(self)
def clearLocalCostmap(self)
def clearGlobalCostmap(self)
def _amclPoseCallback(self, msg)
def _getPathImpl(self, start, goal, planner_id='', use_start=False)
def lifecycleShutdown(self)
def getGlobalCostmap(self)
def _waitForNodeToActivate(self, node_name)
def followPath(self, path, controller_id='', goal_checker_id='')
compute_path_through_poses_client
def _feedbackCallback(self, msg)
def _setInitialPose(self)
def setInitialPose(self, initial_pose)