Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
demo_picking.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 
19 import rclpy
20 from rclpy.duration import Duration
21 
22 
23 # Shelf positions for picking
24 shelf_positions = {
25  'shelf_A': [-3.829, -7.604],
26  'shelf_B': [-3.791, -3.287],
27  'shelf_C': [-3.791, 1.254],
28  'shelf_D': [-3.24, 5.861]}
29 
30 # Shipping destination for picked products
31 shipping_destinations = {
32  'recycling': [-0.205, 7.403],
33  'pallet_jack7': [-0.073, -8.497],
34  'conveyer_432': [6.217, 2.153],
35  'frieght_bay_3': [-6.349, 9.147]}
36 
37 """
38 Basic item picking demo. In this demonstration, the expectation
39 is that there is a person at the item shelf to put the item on the robot
40 and at the pallet jack to remove it
41 (probably with some kind of button for 'got item, robot go do next task').
42 """
43 
44 
45 def main():
46  # Recieved virtual request for picking item at Shelf A and bring to
47  # worker at the pallet jack 7 for shipping. This request would
48  # contain the shelf ID ("shelf_A") and shipping destination ("pallet_jack7")
49 
50  request_item_location = 'shelf_C'
51  request_destination = 'pallet_jack7'
52 
53 
54  rclpy.init()
55 
56  navigator = BasicNavigator()
57 
58  # Set our demo's initial pose
59  initial_pose = PoseStamped()
60  initial_pose.header.frame_id = 'map'
61  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
62  initial_pose.pose.position.x = 3.45
63  initial_pose.pose.position.y = 2.15
64  initial_pose.pose.orientation.z = 1.0
65  initial_pose.pose.orientation.w = 0.0
66  navigator.setInitialPose(initial_pose)
67 
68  # Wait for navigation to fully activate
69  navigator.waitUntilNav2Active()
70 
71  shelf_item_pose = PoseStamped()
72  shelf_item_pose.header.frame_id = 'map'
73  shelf_item_pose.header.stamp = navigator.get_clock().now().to_msg()
74  shelf_item_pose.pose.position.x = shelf_positions[request_item_location][0]
75  shelf_item_pose.pose.position.y = shelf_positions[request_item_location][1]
76  shelf_item_pose.pose.orientation.z = 1.0
77  shelf_item_pose.pose.orientation.w = 0.0
78  print(f'Received request for item picking at {request_item_location}.')
79  navigator.goToPose(shelf_item_pose)
80 
81  # Do something during our route
82  # (e.x. queue up future tasks or detect person for fine-tuned positioning)
83  # Simply print information for workers on the robot's ETA for the demonstation
84  i = 0
85  while not navigator.isTaskComplete():
86  i += 1
87  feedback = navigator.getFeedback()
88  if feedback and i % 5 == 0:
89  print('Estimated time of arrival at ' + request_item_location +
90  ' for worker: ' + '{0:.0f}'.format(
91  Duration.from_msg(feedback.estimated_time_remaining).nanoseconds / 1e9)
92  + ' seconds.')
93 
94  result = navigator.getResult()
95  if result == TaskResult.SUCCEEDED:
96  print('Got product from ' + request_item_location +
97  '! Bringing product to shipping destination (' + request_destination + ')...')
98  shipping_destination = PoseStamped()
99  shipping_destination.header.frame_id = 'map'
100  shipping_destination.header.stamp = navigator.get_clock().now().to_msg()
101  shipping_destination.pose.position.x = shipping_destinations[request_destination][0]
102  shipping_destination.pose.position.y = shipping_destinations[request_destination][1]
103  shipping_destination.pose.orientation.z = 1.0
104  shipping_destination.pose.orientation.w = 0.0
105  navigator.goToPose(shipping_destination)
106 
107  elif result == TaskResult.CANCELED:
108  print(f'Task at {request_item_location} was canceled. Returning to staging point...')
109  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
110  navigator.goToPose(initial_pose)
111 
112  elif result == TaskResult.FAILED:
113  print(f'Task at {request_item_location} failed!')
114  exit(-1)
115 
116  while not navigator.isTaskComplete():
117  pass
118 
119  exit(0)
120 
121 
122 if __name__ == '__main__':
123  main()