Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
example_follow_path.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 
20 
21 """
22 Basic navigation demo to follow a given path after smoothing
23 """
24 
25 
26 def main():
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 = 3.45
36  initial_pose.pose.position.y = 2.15
37  initial_pose.pose.orientation.z = 1.0
38  initial_pose.pose.orientation.w = 0.0
39  navigator.setInitialPose(initial_pose)
40 
41  # Wait for navigation to fully activate, since autostarting nav2
42  navigator.waitUntilNav2Active()
43 
44  # Go to our demos first goal pose
45  goal_pose = PoseStamped()
46  goal_pose.header.frame_id = 'map'
47  goal_pose.header.stamp = navigator.get_clock().now().to_msg()
48  goal_pose.pose.position.x = -3.0
49  goal_pose.pose.position.y = -2.0
50  goal_pose.pose.orientation.w = 1.0
51 
52  # Get the path, smooth it
53  path = navigator.getPath(initial_pose, goal_pose)
54  smoothed_path = navigator.smoothPath(path)
55 
56  # Follow path
57  navigator.followPath(smoothed_path)
58 
59  i = 0
60  while not navigator.isTaskComplete():
61 
66 
67  # Do something with the feedback
68  i += 1
69  feedback = navigator.getFeedback()
70  if feedback and i % 5 == 0:
71  print('Estimated distance remaining to goal position: ' +
72  '{0:.3f}'.format(feedback.distance_to_goal) +
73  '\nCurrent speed of the robot: ' +
74  '{0:.3f}'.format(feedback.speed))
75 
76  # Do something depending on the return code
77  result = navigator.getResult()
78  if result == TaskResult.SUCCEEDED:
79  print('Goal succeeded!')
80  elif result == TaskResult.CANCELED:
81  print('Goal was canceled!')
82  elif result == TaskResult.FAILED:
83  print('Goal failed!')
84  else:
85  print('Goal has an invalid return status!')
86 
87  navigator.lifecycleShutdown()
88 
89  exit(0)
90 
91 
92 if __name__ == '__main__':
93  main()