-
Notifications
You must be signed in to change notification settings - Fork 2
/
iros_2.py
293 lines (235 loc) · 10.1 KB
/
iros_2.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
#!/usr/bin/env python
# Scripts for iros challenge 2: lay out silverware
# re-stow silverware
import time
import copy
import math
import cv2
import imutils
from matplotlib import pyplot as plt
import iros_interface_cmds as ic
import iros_waypoints as iw
#import vision_copy as vc
#Joint positions for the picking ( just above)
pick_f = {"x": 77.82, "y": -86.76, "z": 105.13, "rx": -102.76, "ry": -92.04, "rz":-58.57}
pick_k = {"x": 74.00, "y": -86.55, "z": 107.18, "rx": -105.20, "ry": -92.41, "rz":-62.37}
pick_s = {"x": 85.44, "y": -85.50, "z": 105.73, "rx": -104.36, "ry": -91.28, "rz": -50.97}
#Joint positions for the placing
place_f = {"x": 35.87, "y": -46.09, "z": 48.92, "rx": -95.08, "ry": -93.37, "rz": -98.40}
place_k = {"x": 77.82, "y": -86.76, "z": 105.13, "rx": -102.76, "ry": -92.04, "rz": -58.57}
place_s = {"x": 26.63, "y": -77.99, "z": 95.92, "rx": -109.28, "ry": -90.67, "rz": -189.17}
pick_height = -14.0
place_height = -17.0
act_f = 70
act_k = 70
act_s = 75
def begin(c,ser_ee):
# pick up fork
demand_Grip = dict(iw.ee_home)
demand_Grip["act"]=act_f
msg = ic.safe_move(c,ser_ee,Pose=dict(iw.home_joints),Grip=demand_Grip,CMD=2)
ipt = raw_input("continue")
# Go to just above fork place_height
msg = ic.safe_move(c,ser_ee,Pose=dict(pick_f),CMD=2)
#ipt = raw_input("continue")
#Go down in the z to pick up the fork
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0]+12, "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Close the gripper
demand_Grip["servo"]=30
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
ipt = raw_input("continue")
# Raise
msg = ic.safe_ur_move(c,Pose=dict(pick_f),CMD=2)
#ipt = raw_input("continue")
# Go to place the fork
msg = ic.safe_ur_move(c,Pose=dict(place_f),CMD=2)
#ipt = raw_input("continue")
# Lower the fork
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = place_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Release
demand_Grip["servo"]=120
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
#ipt = raw_input("continue")
# Raise arm
msg = ic.safe_ur_move(c,Pose=dict(place_f),CMD=2)
test = raw_input("Go on to spoon?")
###############################################################################
# pick up spoon
demand_Grip = dict(iw.ee_home)
demand_Grip["act"]=act_s
msg = ic.end_effector_move(ser_ee,demand_Grip)
# Go to just above spoon place_height
msg = ic.safe_ur_move(c,Pose=dict(pick_s),CMD=2)
#Go down in the z to pick up the fork
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0]+10, "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Close the gripper
demand_Grip["servo"]=30
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise
msg = ic.safe_ur_move(c,Pose=dict(pick_s),CMD=2)
# Go to place the fork
msg = ic.safe_ur_move(c,Pose=dict(place_s),CMD=2)
# Lower the fork
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = place_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Release
demand_Grip["servo"]=120
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise arm
msg = ic.safe_ur_move(c,Pose=dict(place_s),CMD=2)
test = raw_input("Go on to knife?")
###############################################################################
# pick up knife
demand_Grip = dict(iw.ee_home)
demand_Grip["act"]=act_k
msg = ic.end_effector_move(ser_ee,demand_Grip)
# Go to just above spoon place_height
demand_Pose = dict(pick_k)
demand_Pose["x"] = demand_Pose["x"] + 20
msg = ic.safe_ur_move(c,Pose=dict(pick_k),CMD=2)
# Go to low ish and then mostly close gripper
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0]-2, "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height +15
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
demand_Grip["servo"]=50
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Move sideways
demand_Pose = ic.get_ur_position(c,1)
demand_Pose["x"] = demand_Pose["x"]
msg = ic.safe_ur_move(c,Pose=dict(pick_k),CMD=2)
#Go down in the z to pick up the fork
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0]-2, "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height -2
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Close the gripper
demand_Grip["servo"]=30
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise
msg = ic.safe_ur_move(c,Pose=dict(pick_k),CMD=2)
# Go to place the fork
msg = ic.safe_ur_move(c,Pose=dict(place_k),CMD=2)
# Lower the fork
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = place_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Release
demand_Grip["servo"]=120
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise arm
msg = ic.safe_ur_move(c,Pose=dict(place_k),CMD=2)
test = raw_input("Go on to retrieve fork?")
###############################################################################
# pick up fork
demand_Grip = dict(iw.ee_home)
demand_Grip["act"]=act_f
msg = ic.end_effector_move(ser_ee,demand_Grip)
# Go abouve place of fork
msg = ic.safe_ur_move(c,Pose=dict(place_f),CMD=2)
# Lower
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = place_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Pick up fork
demand_Grip["servo"]=30
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Lift and move above the tray for fokr
msg = ic.safe_ur_move(c,Pose=dict(place_f),CMD=2)
msg = ic.safe_ur_move(c,Pose=dict(pick_f),CMD=2)
# Lower
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Release
demand_Grip["servo"]=120
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise
msg = ic.safe_ur_move(c,Pose=dict(pick_k),CMD=2)
test = raw_input("Go on to retrieve spoon?")
###############################################################################
# pick up spoon
demand_Grip = dict(iw.ee_home)
demand_Grip["act"]=act_s
msg = ic.end_effector_move(ser_ee,demand_Grip)
# Go abouve place of spoon
msg = ic.safe_ur_move(c,Pose=dict(place_s),CMD=2)
# Lower
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = place_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Pick up fork
demand_Grip["servo"]=30
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Lift and move above the tray for fokr
msg = ic.safe_ur_move(c,Pose=dict(place_s),CMD=2)
msg = ic.safe_ur_move(c,Pose=dict(pick_s),CMD=2)
# Lower
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Release
demand_Grip["servo"]=120
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise
msg = ic.safe_ur_move(c,Pose=dict(pick_s),CMD=2)
test = raw_input("Go on to retrieve knife?")
###############################################################################
# pick up knife
demand_Grip = dict(iw.ee_home)
demand_Grip["act"]=act_k
msg = ic.end_effector_move(ser_ee,demand_Grip)
# Go abouve place of knife
msg = ic.safe_ur_move(c,Pose=dict(place_k),CMD=2)
# Lower
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = place_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Pick up fork
demand_Grip["servo"]=30
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Lift and move above the tray for fokr
msg = ic.safe_ur_move(c,Pose=dict(place_k),CMD=2)
msg = ic.safe_ur_move(c,Pose=dict(pick_k),CMD=2)
# Lower
current_Pose = ic.get_ur_position(c,1)
demand_Pose = {"x":current_Pose[0], "y":current_Pose[1], "z":current_Pose[2], "rx":current_Pose[3], "ry":current_Pose[4], "rz":current_Pose[5]}
demand_Pose["z"] = pick_height
msg = ic.safe_ur_move(c,Pose=demand_Pose,CMD=4)
# Release
demand_Grip["servo"]=120
msg = ic.end_effector_move(ser_ee,demand_Grip)
time.sleep(1)
# Raise
msg = ic.safe_ur_move(c,Pose=dict(pick_k),CMD=2)
msg = ic.safe_move(c,ser_ee,Pose=dict(iw.home_joints),CMD=2)
print ".....................Done......................"