Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
example_nav_through_poses.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 poses.
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  # set our demo's goal poses
58  goal_poses = []
59  goal_pose1 = PoseStamped()
60  goal_pose1.header.frame_id = 'map'
61  goal_pose1.header.stamp = navigator.get_clock().now().to_msg()
62  goal_pose1.pose.position.x = 10.15
63  goal_pose1.pose.position.y = -0.77
64  goal_pose1.pose.orientation.w = 1.0
65  goal_pose1.pose.orientation.z = 0.0
66  goal_poses.append(goal_pose1)
67 
68  # additional goals can be appended
69  goal_pose2 = PoseStamped()
70  goal_pose2.header.frame_id = 'map'
71  goal_pose2.header.stamp = navigator.get_clock().now().to_msg()
72  goal_pose2.pose.position.x = 17.86
73  goal_pose2.pose.position.y = -0.77
74  goal_pose2.pose.orientation.w = 1.0
75  goal_pose2.pose.orientation.z = 0.0
76  goal_poses.append(goal_pose2)
77  goal_pose3 = PoseStamped()
78  goal_pose3.header.frame_id = 'map'
79  goal_pose3.header.stamp = navigator.get_clock().now().to_msg()
80  goal_pose3.pose.position.x = 21.58
81  goal_pose3.pose.position.y = -3.5
82  goal_pose3.pose.orientation.w = 1.0
83  goal_pose3.pose.orientation.z = 0.0
84  goal_poses.append(goal_pose3)
85 
86  # sanity check a valid path exists
87  # path = navigator.getPathThroughPoses(initial_pose, goal_poses)
88 
89  nav_through_poses_task = navigator.goThroughPoses(goal_poses)
90 
91  i = 0
92  while not navigator.isTaskComplete(task=nav_through_poses_task):
93 
98 
99  # Do something with the feedback
100  i = i + 1
101  feedback = navigator.getFeedback(task=nav_through_poses_task)
102  if feedback and i % 5 == 0:
103  print(
104  'Estimated time of arrival: '
105  + '{:.0f}'.format(
106  Duration.from_msg(feedback.estimated_time_remaining).nanoseconds
107  / 1e9
108  )
109  + ' seconds.'
110  )
111 
112  # Some navigation timeout to demo cancellation
113  if Duration.from_msg(feedback.navigation_time) > Duration(seconds=600.0):
114  navigator.cancelTask()
115 
116  # Some navigation request change to demo preemption
117  if Duration.from_msg(feedback.navigation_time) > Duration(seconds=35.0):
118  goal_pose4 = PoseStamped()
119  goal_pose4.header.frame_id = 'map'
120  goal_pose4.header.stamp = navigator.get_clock().now().to_msg()
121  goal_pose4.pose.position.x = 0.0
122  goal_pose4.pose.position.y = 0.0
123  goal_pose4.pose.orientation.w = 1.0
124  goal_pose4.pose.orientation.z = 0.0
125  navigator.goThroughPoses([goal_pose4])
126 
127  # Do something depending on the return code
128  result = navigator.getResult()
129  if result == TaskResult.SUCCEEDED:
130  print('Goal succeeded!')
131  elif result == TaskResult.CANCELED:
132  print('Goal was canceled!')
133  elif result == TaskResult.FAILED:
134  (error_code, error_msg) = navigator.getTaskError()
135  print('Goal failed!{error_code}:{error_msg}')
136  else:
137  print('Goal has an invalid return status!')
138 
139  navigator.lifecycleShutdown()
140 
141  exit(0)
142 
143 
144 if __name__ == '__main__':
145  main()