Nav2 Navigation Stack - jazzy  jazzy
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': [8.21, 1.3, 1.57],
26  'shelf_B': [11.6, 1.3, -1.57],
27  'shelf_C': [12.6, 4.0, -1.57],
28  'shelf_D': [19.0, 4.0, 1.57],
29 }
30 
31 # Shipping destination for picked products
32 shipping_destinations = {
33  'frieght_bay_1': [-6.0, 5.0, 3.14],
34  'frieght_bay_2': [-6.0, 0.0, 3.14],
35  'frieght_bay_3': [-6.0, -5.0, 3.14],
36 }
37 
38 """
39 Basic item picking demo. In this demonstration, the expectation
40 is that there is a person at the item shelf to put the item on the robot
41 and at the pallet jack to remove it
42 (probably with some kind of button for 'got item, robot go do next task').
43 """
44 
45 
46 def main():
47  # Recieved virtual request for picking item at Shelf A and bring to
48  # worker at the pallet jack 7 for shipping. This request would
49  # contain the shelf ID ('shelf_A') and shipping destination ('frieght_bay_3')
50 
51  request_item_location = 'shelf_A'
52  request_destination = 'frieght_bay_3'
53 
54 
55  rclpy.init()
56 
57  navigator = BasicNavigator()
58 
59  # Set our demo's initial pose
60  initial_pose = PoseStamped()
61  initial_pose.header.frame_id = 'map'
62  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
63  initial_pose.pose.position.x = 0.0
64  initial_pose.pose.position.y = 0.0
65  initial_pose.pose.orientation.z = 0.0
66  initial_pose.pose.orientation.w = 1.0
67  navigator.setInitialPose(initial_pose)
68 
69  # Wait for navigation to fully activate
70  navigator.waitUntilNav2Active()
71 
72  shelf_item_pose = PoseStamped()
73  shelf_item_pose.header.frame_id = 'map'
74  shelf_item_pose.header.stamp = navigator.get_clock().now().to_msg()
75  shelf_item_pose.pose.position.x = shelf_positions[request_item_location][0]
76  shelf_item_pose.pose.position.y = shelf_positions[request_item_location][1]
77  # Simplification of angle handling for demonstration purposes
78  if shelf_positions[request_item_location][2] > 0:
79  shelf_item_pose.pose.orientation.z = 0.707
80  shelf_item_pose.pose.orientation.w = 0.707
81  else:
82  shelf_item_pose.pose.orientation.z = -0.707
83  shelf_item_pose.pose.orientation.w = 0.707
84  print(f'Received request for item picking at {request_item_location}.')
85  navigator.goToPose(shelf_item_pose)
86 
87  # Do something during our route
88  # (e.x. queue up future tasks or detect person for fine-tuned positioning)
89  # Simply print information for workers on the robot's ETA for the demonstation
90  i = 0
91  while not navigator.isTaskComplete():
92  i += 1
93  feedback = navigator.getFeedback()
94  if feedback and i % 5 == 0:
95  print(
96  'Estimated time of arrival at '
97  + request_item_location
98  + ' for worker: '
99  + '{0:.0f}'.format(
100  Duration.from_msg(feedback.estimated_time_remaining).nanoseconds
101  / 1e9
102  )
103  + ' seconds.'
104  )
105 
106  result = navigator.getResult()
107  if result == TaskResult.SUCCEEDED:
108  print(
109  'Got product from '
110  + request_item_location
111  + '! Bringing product to shipping destination ('
112  + request_destination
113  + ')...'
114  )
115  shipping_destination = PoseStamped()
116  shipping_destination.header.frame_id = 'map'
117  shipping_destination.header.stamp = navigator.get_clock().now().to_msg()
118  shipping_destination.pose.position.x = shipping_destinations[
119  request_destination
120  ][0]
121  shipping_destination.pose.position.y = shipping_destinations[
122  request_destination
123  ][1]
124  shipping_destination.pose.orientation.z = 1.0
125  shipping_destination.pose.orientation.w = 0.0
126  navigator.goToPose(shipping_destination)
127 
128  elif result == TaskResult.CANCELED:
129  print(
130  f'Task at {request_item_location} was canceled. Returning to staging point...'
131  )
132  initial_pose.header.stamp = navigator.get_clock().now().to_msg()
133  navigator.goToPose(initial_pose)
134 
135  elif result == TaskResult.FAILED:
136  print(f'Task at {request_item_location} failed!')
137  exit(-1)
138 
139  while not navigator.isTaskComplete():
140  pass
141 
142  exit(0)
143 
144 
145 if __name__ == '__main__':
146  main()