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