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