Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
example_nav_to_pose.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 from geometry_msgs.msg import PoseStamped
17 from nav2_simple_commander.robot_navigator import BasicNavigator, TaskResult
18 import rclpy
19 from rclpy.duration import Duration
20 
21 """
22 Basic navigation demo to go to pose.
23 """
24 
25 
26 def main() -> None:
27  rclpy.init()
28 
29  navigator = BasicNavigator()
30 
31  # Set our demo's initial pose
32  initial_pose = PoseStamped()
33  initial_pose.header.frame_id = 'map'
34  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
35  initial_pose.pose.position.x = 0.0
36  initial_pose.pose.position.y = 0.0
37  initial_pose.pose.orientation.z = 0.0
38  initial_pose.pose.orientation.w = 1.0
39  navigator.setInitialPose(initial_pose)
40 
41  # Activate navigation, if not autostarted. This should be called after setInitialPose()
42  # or this will initialize at the origin of the map and update the costmap with bogus readings.
43  # If autostart, you should `waitUntilNav2Active()` instead.
44  # navigator.lifecycleStartup()
45 
46  # Wait for navigation to fully activate, since autostarting nav2
47  navigator.waitUntilNav2Active()
48 
49  # If desired, you can change or load the map as well
50  # navigator.changeMap('/path/to/map.yaml')
51 
52  # You may use the navigator to clear or obtain costmaps
53  # navigator.clearAllCostmaps() # also have clearLocalCostmap() and clearGlobalCostmap()
54  # global_costmap = navigator.getGlobalCostmap()
55  # local_costmap = navigator.getLocalCostmap()
56 
57  # Go to our demos first goal pose
58  goal_pose = PoseStamped()
59  goal_pose.header.frame_id = 'map'
60  goal_pose.header.stamp = navigator.get_clock().now().to_msg()
61  goal_pose.pose.position.x = 17.86
62  goal_pose.pose.position.y = -0.77
63  goal_pose.pose.orientation.w = 1.0
64  goal_pose.pose.orientation.z = 0.0
65 
66  # sanity check a valid path exists
67  # path = navigator.getPath(initial_pose, goal_pose)
68 
69  go_to_pose_task = navigator.goToPose(goal_pose)
70 
71  i = 0
72  while not navigator.isTaskComplete(task=go_to_pose_task):
73 
78 
79  # Do something with the feedback
80  i = i + 1
81  feedback = navigator.getFeedback(task=go_to_pose_task)
82  if feedback and i % 5 == 0:
83  print(
84  'Estimated time of arrival: '
85  + '{:.0f}'.format(
86  Duration.from_msg(feedback.estimated_time_remaining).nanoseconds
87  / 1e9
88  )
89  + ' seconds.'
90  )
91 
92  # Some navigation timeout to demo cancellation
93  if Duration.from_msg(feedback.navigation_time) > Duration(seconds=600.0):
94  navigator.cancelTask()
95 
96  # Some navigation request change to demo preemption
97  if Duration.from_msg(feedback.navigation_time) > Duration(seconds=18.0):
98  goal_pose.pose.position.x = 0.0
99  goal_pose.pose.position.y = 0.0
100  go_to_pose_task = navigator.goToPose(goal_pose)
101 
102  # Do something depending on the return code
103  result = navigator.getResult()
104  if result == TaskResult.SUCCEEDED:
105  print('Goal succeeded!')
106  elif result == TaskResult.CANCELED:
107  print('Goal was canceled!')
108  elif result == TaskResult.FAILED:
109  (error_code, error_msg) = navigator.getTaskError()
110  print('Goal failed!{error_code}:{error_msg}')
111  else:
112  print('Goal has an invalid return status!')
113 
114  navigator.lifecycleShutdown()
115 
116  exit(0)
117 
118 
119 if __name__ == '__main__':
120  main()