-
Notifications
You must be signed in to change notification settings - Fork 2
/
robot.py
367 lines (307 loc) · 11.1 KB
/
robot.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
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
"""
Python library to control an UR robot through its TCP/IP interface
DOC LINK
http://support.universal-robots.com/URRobot/RemoteAccess
"""
import math3d as m3d
import numpy as np
from urx.urrobot import URRobot
__author__ = "Olivier Roulet-Dubonnet"
__copyright__ = "Copyright 2011-2016, Sintef Raufoss Manufacturing"
__license__ = "LGPLv3"
class Robot(URRobot):
"""
Generic Python interface to an industrial robot.
Compared to the URRobot class, this class adds the possibilty to work directly with matrices
and includes support for setting a reference coordinate system
"""
def __init__(self, host, use_rt=False):
URRobot.__init__(self, host, use_rt)
self.csys = m3d.Transform()
def _get_lin_dist(self, target):
pose = URRobot.getl(self, wait=True)
target = m3d.Transform(target)
pose = m3d.Transform(pose)
return pose.dist(target)
def set_tcp(self, tcp):
"""
set robot flange to tool tip transformation
"""
if isinstance(tcp, m3d.Transform):
tcp = tcp.pose_vector
URRobot.set_tcp(self, tcp)
def set_csys(self, transform):
"""
Set reference coordinate system to use
"""
self.csys = transform
def set_orientation(self, orient, acc=0.01, vel=0.01, wait=True, threshold=None):
"""
set tool orientation using a orientation matric from math3d
or a orientation vector
"""
if not isinstance(orient, m3d.Orientation):
orient = m3d.Orientation(orient)
trans = self.get_pose()
trans.orient = orient
self.set_pose(trans, acc, vel, wait=wait, threshold=threshold)
def translate_tool(self, vect, acc=0.01, vel=0.01, wait=True, threshold=None):
"""
move tool in tool coordinate, keeping orientation
"""
t = m3d.Transform()
if not isinstance(vect, m3d.Vector):
vect = m3d.Vector(vect)
t.pos += vect
return self.add_pose_tool(t, acc, vel, wait=wait, threshold=threshold)
def back(self, z=0.05, acc=0.01, vel=0.01):
"""
move in z tool
"""
self.translate_tool((0, 0, -z), acc=acc, vel=vel)
def set_pos(self, vect, acc=0.01, vel=0.01, wait=True, threshold=None):
"""
set tool to given pos, keeping constant orientation
"""
if not isinstance(vect, m3d.Vector):
vect = m3d.Vector(vect)
trans = m3d.Transform(self.get_orientation(), m3d.Vector(vect))
return self.set_pose(trans, acc, vel, wait=wait, threshold=threshold)
def movec(self, pose_via, pose_to, acc=0.01, vel=0.01, wait=True, threshold=None):
"""
Move Circular: Move to position (circular in tool-space)
see UR documentation
"""
pose_via = self.csys * m3d.Transform(pose_via)
pose_to = self.csys * m3d.Transform(pose_to)
pose = URRobot.movec(self, pose_via.pose_vector, pose_to.pose_vector, acc=acc, vel=vel, wait=wait, threshold=threshold)
if pose is not None:
return self.csys.inverse * m3d.Transform(pose)
def set_pose(self, trans, acc=0.01, vel=0.01, wait=True, command="movel", threshold=None):
"""
move tcp to point and orientation defined by a transformation
UR robots have several move commands, by default movel is used but it can be changed
using the command argument
"""
self.logger.debug("Setting pose to %s", trans.pose_vector)
t = self.csys * trans
pose = URRobot.movex(self, command, t.pose_vector, acc=acc, vel=vel, wait=wait, threshold=threshold)
if pose is not None:
return self.csys.inverse * m3d.Transform(pose)
def add_pose_base(self, trans, acc=0.01, vel=0.01, wait=True, command="movel", threshold=None):
"""
Add transform expressed in base coordinate
"""
pose = self.get_pose()
return self.set_pose(trans * pose, acc, vel, wait=wait, command=command, threshold=threshold)
def add_pose_tool(self, trans, acc=0.01, vel=0.01, wait=True, command="movel", threshold=None):
"""
Add transform expressed in tool coordinate
"""
pose = self.get_pose()
return self.set_pose(pose * trans, acc, vel, wait=wait, command=command, threshold=threshold)
def get_pose(self, wait=False, _log=True):
"""
get current transform from base to to tcp
"""
pose = URRobot.getl(self, wait, _log)
trans = self.csys.inverse * m3d.Transform(pose)
if _log:
self.logger.debug("Returning pose to user: %s", trans.pose_vector)
return trans
def get_orientation(self, wait=False):
"""
get tool orientation in base coordinate system
"""
trans = self.get_pose(wait)
return trans.orient
def get_pos(self, wait=False):
"""
get tool tip pos(x, y, z) in base coordinate system
"""
trans = self.get_pose(wait)
return trans.pos
def speedl(self, velocities, acc, min_time):
"""
move at given velocities until minimum min_time seconds
"""
v = self.csys.orient * m3d.Vector(velocities[:3])
w = self.csys.orient * m3d.Vector(velocities[3:])
vels = np.concatenate((v.array, w.array))
return self.speedx("speedl", vels, acc, min_time)
def speedj(self, velocities, acc, min_time):
"""
move at given joint velocities until minimum min_time seconds
"""
return self.speedx("speedj", velocities, acc, min_time)
def speedl_tool(self, velocities, acc, min_time):
"""
move at given velocities in tool csys until minimum min_time seconds
"""
pose = self.get_pose()
v = pose.orient * m3d.Vector(velocities[:3])
w = pose.orient * m3d.Vector(velocities[3:])
self.speedl(np.concatenate((v.array, w.array)), acc, min_time)
def movex(self, command, pose, acc=0.01, vel=0.01, wait=True, relative=False, threshold=None):
"""
Send a move command to the robot. since UR robotene have several methods this one
sends whatever is defined in 'command' string
"""
t = m3d.Transform(pose)
if relative:
return self.add_pose_base(t, acc, vel, wait=wait, command=command, threshold=threshold)
else:
return self.set_pose(t, acc, vel, wait=wait, command=command, threshold=threshold)
def movexs(self, command, pose_list, acc=0.01, vel=0.01, radius=0.01, wait=True, threshold=None):
"""
Concatenate several movex commands and applies a blending radius
pose_list is a list of pose.
This method is usefull since any new command from python
to robot make the robot stop
"""
new_poses = []
for pose in pose_list:
t = self.csys * m3d.Transform(pose)
pose = t.pose_vector
new_poses.append(pose)
return URRobot.movexs(self, command, new_poses, acc, vel, radius, wait=wait, threshold=threshold)
def movel_tool(self, pose, acc=0.01, vel=0.01, wait=True, threshold=None):
"""
move linear to given pose in tool coordinate
"""
return self.movex_tool("movel", pose, acc=acc, vel=vel, wait=wait, threshold=threshold)
def movex_tool(self, command, pose, acc=0.01, vel=0.01, wait=True, threshold=None):
t = m3d.Transform(pose)
self.add_pose_tool(t, acc, vel, wait=wait, command=command, threshold=threshold)
def getl(self, wait=False, _log=True):
"""
return current transformation from tcp to current csys
"""
t = self.get_pose(wait, _log)
return t.pose_vector.tolist()
def set_gravity(self, vector):
if isinstance(vector, m3d.Vector):
vector = vector.list
return URRobot.set_gravity(self, vector)
def new_csys_from_xpy(self):
"""
Restores and returns new coordinate system calculated from three points: X, Origin, Y
based on math3d: Transform.new_from_xyp
"""
# Set coord. sys. to 0
self.csys = m3d.Transform()
print("A new coordinate system will be defined from the next three points")
print("Firs point is X, second Origin, third Y")
print("Set it as a new reference by calling myrobot.set_csys(new_csys)")
input("Move to first point and click Enter")
# we do not use get_pose so we avoid rounding values
pose = URRobot.getl(self)
print("Introduced point defining X: {}".format(pose[:3]))
px = m3d.Vector(pose[:3])
input("Move to second point and click Enter")
pose = URRobot.getl(self)
print("Introduced point defining Origo: {}".format(pose[:3]))
p0 = m3d.Vector(pose[:3])
input("Move to third point and click Enter")
pose = URRobot.getl(self)
print("Introduced point defining Y: {}".format(pose[:3]))
py = m3d.Vector(pose[:3])
new_csys = m3d.Transform.new_from_xyp(px - p0, py - p0, p0)
self.set_csys(new_csys)
return new_csys
@property
def x(self):
return self.get_pos().x
@x.setter
def x(self, val):
p = self.get_pos()
p.x = val
self.set_pos(p)
@property
def y(self):
return self.get_pos().y
@y.setter
def y(self, val):
p = self.get_pos()
p.y = val
self.set_pos(p)
@property
def z(self):
return self.get_pos().z
@z.setter
def z(self, val):
p = self.get_pos()
p.z = val
self.set_pos(p)
@property
def rx(self):
return 0
@rx.setter
def rx(self, val):
p = self.get_pose()
p.orient.rotate_xb(val)
self.set_pose(p)
@property
def ry(self):
return 0
@ry.setter
def ry(self, val):
p = self.get_pose()
p.orient.rotate_yb(val)
self.set_pose(p)
@property
def rz(self):
return 0
@rz.setter
def rz(self, val):
p = self.get_pose()
p.orient.rotate_zb(val)
self.set_pose(p)
@property
def x_t(self):
return 0
@x_t.setter
def x_t(self, val):
t = m3d.Transform()
t.pos.x += val
self.add_pose_tool(t)
@property
def y_t(self):
return 0
@y_t.setter
def y_t(self, val):
t = m3d.Transform()
t.pos.y += val
self.add_pose_tool(t)
@property
def z_t(self):
return 0
@z_t.setter
def z_t(self, val):
t = m3d.Transform()
t.pos.z += val
self.add_pose_tool(t)
@property
def rx_t(self):
return 0
@rx_t.setter
def rx_t(self, val):
t = m3d.Transform()
t.orient.rotate_xb(val)
self.add_pose_tool(t)
@property
def ry_t(self):
return 0
@ry_t.setter
def ry_t(self, val):
t = m3d.Transform()
t.orient.rotate_yb(val)
self.add_pose_tool(t)
@property
def rz_t(self):
return 0
@rz_t.setter
def rz_t(self, val):
t = m3d.Transform()
t.orient.rotate_zb(val)
self.add_pose_tool(t)