Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
demo_recoveries.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 recoveries demo. In this demonstration, the robot navigates
23 to a dead-end where recoveries such as backup and spin are used
24 to get out of it.
25 """
26 
27 
28 def main() -> None:
29  rclpy.init()
30 
31  navigator = BasicNavigator()
32 
33  # Set our demo's initial pose
34  initial_pose = PoseStamped()
35  initial_pose.header.frame_id = 'map'
36  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
37  initial_pose.pose.position.x = 0.0
38  initial_pose.pose.position.y = 0.0
39  initial_pose.pose.orientation.z = 0.0
40  initial_pose.pose.orientation.w = 1.0
41  navigator.setInitialPose(initial_pose)
42 
43  # Wait for navigation to fully activate
44  navigator.waitUntilNav2Active()
45 
46  goal_pose = PoseStamped()
47  goal_pose.header.frame_id = 'map'
48  goal_pose.header.stamp = navigator.get_clock().now().to_msg()
49  goal_pose.pose.position.x = 8.21
50  goal_pose.pose.position.y = 1.3
51  goal_pose.pose.orientation.w = 1.0
52 
53  go_to_pose_task = navigator.goToPose(goal_pose)
54 
55  i = 0
56  while not navigator.isTaskComplete(task=go_to_pose_task):
57  i += 1
58  feedback = navigator.getFeedback(task=go_to_pose_task)
59  if feedback and i % 5 == 0:
60  print(
61  f'Estimated time of arrival to destination is: \
62  {Duration.from_msg(feedback.estimated_time_remaining).nanoseconds / 1e9}'
63  )
64 
65  # Robot hit a dead end, back it up
66  print("Robot hit a dead end (let's pretend), backing up...")
67  backup_task = navigator.backup(backup_dist=0.5, backup_speed=0.1)
68 
69  i = 0
70  while not navigator.isTaskComplete(task=backup_task):
71  i += 1
72  feedback = navigator.getFeedback(task=backup_task)
73  if feedback and i % 5 == 0:
74  print(f'Distance traveled: {feedback.distance_traveled}')
75 
76  # Turn it around
77  print('Spinning robot around...')
78  spin_task = navigator.spin(spin_dist=3.14)
79 
80  i = 0
81  while not navigator.isTaskComplete(task=spin_task):
82  i += 1
83  feedback = navigator.getFeedback(task=spin_task)
84  if feedback and i % 5 == 0:
85  print(f'Spin angle traveled: {feedback.angular_distance_traveled}')
86 
87  result = navigator.getResult()
88  if result == TaskResult.SUCCEEDED:
89  print('Dead end confirmed! Returning to start...')
90  elif result == TaskResult.CANCELED:
91  print('Recovery was canceled. Returning to start...')
92  elif result == TaskResult.FAILED:
93  (error_code, error_msg) = navigator.getTaskError()
94  print(f'Recovering from dead end failed!:{error_code}:{error_msg}')
95  print('Returning to start...')
96 
97  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
98  go_to_pose_task = navigator.goToPose(initial_pose)
99  while not navigator.isTaskComplete(task=go_to_pose_task):
100  pass
101 
102  exit(0)
103 
104 
105 if __name__ == '__main__':
106  main()