Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
demo_inspection.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 copy import deepcopy
17 
18 from geometry_msgs.msg import PoseStamped
19 from nav2_simple_commander.robot_navigator import BasicNavigator, TaskResult
20 import rclpy
21 
22 """
23 Basic stock inspection demo. In this demonstration, the expectation
24 is that there are cameras or RFID sensors mounted on the robots
25 collecting information about stock quantity and location.
26 """
27 
28 
29 def main():
30  rclpy.init()
31 
32  navigator = BasicNavigator()
33 
34  # Inspection route, probably read in from a file for a real application
35  # from either a map or drive and repeat.
36  inspection_route = [
37  [3.461, -0.450],
38  [5.531, -0.450],
39  [3.461, -2.200],
40  [5.531, -2.200],
41  [3.661, -4.121],
42  [5.431, -4.121],
43  [3.661, -5.850],
44  [5.431, -5.800]]
45 
46  # Set our demo's initial pose
47  initial_pose = PoseStamped()
48  initial_pose.header.frame_id = 'map'
49  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
50  initial_pose.pose.position.x = 3.45
51  initial_pose.pose.position.y = 2.15
52  initial_pose.pose.orientation.z = 1.0
53  initial_pose.pose.orientation.w = 0.0
54  navigator.setInitialPose(initial_pose)
55 
56  # Wait for navigation to fully activate
57  navigator.waitUntilNav2Active()
58 
59  # Send our route
60  inspection_points = []
61  inspection_pose = PoseStamped()
62  inspection_pose.header.frame_id = 'map'
63  inspection_pose.header.stamp = navigator.get_clock().now().to_msg()
64  inspection_pose.pose.orientation.z = 1.0
65  inspection_pose.pose.orientation.w = 0.0
66  for pt in inspection_route:
67  inspection_pose.pose.position.x = pt[0]
68  inspection_pose.pose.position.y = pt[1]
69  inspection_points.append(deepcopy(inspection_pose))
70  navigator.followWaypoints(inspection_points)
71 
72  # Do something during our route (e.x. AI to analyze stock information or upload to the cloud)
73  # Simply the current waypoint ID for the demonstation
74  i = 0
75  while not navigator.isTaskComplete():
76  i += 1
77  feedback = navigator.getFeedback()
78  if feedback and i % 5 == 0:
79  print('Executing current waypoint: ' +
80  str(feedback.current_waypoint + 1) + '/' + str(len(inspection_points)))
81 
82  result = navigator.getResult()
83  if result == TaskResult.SUCCEEDED:
84  print('Inspection of shelves complete! Returning to start...')
85  elif result == TaskResult.CANCELED:
86  print('Inspection of shelving was canceled. Returning to start...')
87  elif result == TaskResult.FAILED:
88  print('Inspection of shelving failed! Returning to start...')
89 
90  # go back to start
91  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
92  navigator.goToPose(initial_pose)
93  while not navigator.isTaskComplete():
94  pass
95 
96  exit(0)
97 
98 
99 if __name__ == '__main__':
100  main()