robodk.py
Go to the documentation of this file.
1 # Copyright 2017 - RoboDK Software S.L. - http://www.robodk.com/
2 # Licensed under the Apache License, Version 2.0 (the "License");
3 # you may not use this file except in compliance with the License.
4 # You may obtain a copy of the License at
5 # http://www.apache.org/licenses/LICENSE-2.0
6 # Unless required by applicable law or agreed to in writing, software
7 # distributed under the License is distributed on an "AS IS" BASIS,
8 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
9 # See the License for the specific language governing permissions and
10 # limitations under the License.
11 
12 # --------------------------------------------
13 # --------------- DESCRIPTION ----------------
14 #
15 # This is a robotics toolbox for RoboDK robot post processors and RoboDK API for Python
16 # This toolbox includes a simple matrix class for pose transofmrations (Mat)
17 # This toolbox has been inspired from Peter Corke's Robotics Toolbox:
18 # http://petercorke.com/wordpress/toolboxes/robotics-toolbox
19 #
20 # In this document: pose = transformation matrix = homogeneous matrix = 4x4 matrix
21 # Visit the Matrix and Quaternions FAQ for more information about pose/homogeneous transformations
22 # http://www.j3d.org/matrix_faq/matrfaq_latest.html
23 #
24 # More information about RoboDK post processors here:
25 # http://www.robodk.com/help#PostProcessor
26 #
27 # More information about the RoboDK API for Python here:
28 # http://www.robodk.com/doc/PythonAPI/index.html
29 # --------------------------------------------
30 
31 import math
32 import operator
33 import sys
34 import unittest
35 import time
36 
37 #----------------------------------------------------
38 #-------- Generic file usage ---------------
39 
40 import os.path
41 import time
42 
43 def searchfiles(pattern='C:\\RoboDK\\Library\\*.rdk'):
44  """List the files in a directory with a given extension"""
45  import glob
46  return glob.glob(pattern)
47 
48 def CurrentFile(file = __file__):
49  """Returns the current Python file being executed"""
50  return os.path.realpath(file)
51 
52 def getFileDir(filepath):
53  """Returns the directory of a file path"""
54  return os.path.dirname(filepath)
55 
56 def getBaseName(filepath):
57  """Returns the file name and extension of a file path"""
58  return os.path.basename(filepath)
59 
60 def getFileName(filepath):
61  """Returns the file name (with no extension) of a file path"""
62  return os.path.splitext(os.path.basename(filepath))[0]
63 
64 def DateModified(filepath, stringformat=False):
65  """Returns the time that a file was modified"""
66  time_in_s = os.path.getmtime(filepath)
67  if stringformat:
68  return time.ctime(time_in_s)
69  else:
70  return time_in_s
71 
72 def DateCreated(filepath, stringformat=False):
73  """Returns the time that a file was modified"""
74  time_in_s = os.path.getctime(filepath)
75  if stringformat:
76  return time.ctime(time_in_s)
77  else:
78  return time_in_s
79 
80 def DirExists(folder):
81  """Returns true if the folder exists"""
82  return os.path.isdir(folder)
83 
84 def FileExists(file):
85  """Returns true if the file exists"""
86  return os.path.exists(file)
87 
88 #----------------------------------------------------
89 #-------- Generic math usage ---------------
90 
91 pi = math.pi
92 
93 def pause(seconds):
94  """Pause in seconds
95 
96  :param pause: time in seconds
97  :type pause: float"""
98  time.sleep(seconds)
99 
100 def atan2(y,x):
101  """Returns angle of a 2D coordinate in the XY plane"""
102  return math.atan2(y,x)
103 
104 def sqrt(value):
105  """Returns the square root of a value"""
106  return math.sqrt(value)
107 
108 def sin(value):
109  """Returns the sinus of an angle in radians"""
110  return math.sin(value)
111 
112 def cos(value):
113  """Returns the cosinus of an angle in radians"""
114  return math.cos(value)
115 
116 def asin(value):
117  """Returns the arc sinus in radians"""
118  return math.asin(value)
119 
120 def acos(value):
121  """Returns the arc cosinus in radians"""
122  return math.acos(value)
123 
124 def name_2_id(str_name_id):
125  """Returns the number of a numbered object. For example: "Frame 3" returns 3"""
126  words = str_name_id.split()
127  number = words.pop()
128  if number.isdigit():
129  return float(number)
130  return -1
131 
132 
133 #----------------------------------------------------
134 #-------- Generic matrix usage ---------------
135 
136 def rotx(rx):
137  r"""Returns a rotation matrix around the X axis
138 
139  .. math::
140 
141  R_x(\theta) = \begin{bmatrix} 1 & 0 & 0 & 0 \\
142  0 & c_\theta & -s_\theta & 0 \\
143  0 & s_\theta & c_\theta & 0 \\
144  0 & 0 & 0 & 1
145  \end{bmatrix}
146 
147  :param rx: rotation around X axis in radians
148  :type rx: float"""
149  ct = math.cos(rx)
150  st = math.sin(rx)
151  return Mat([[1,0,0,0],[0,ct,-st,0],[0,st,ct,0],[0,0,0,1]])
152 
153 def roty(ry):
154  r"""Returns a rotation matrix around the Y axis
155 
156  .. math::
157 
158  R_y(\theta) = \begin{bmatrix} c_\theta & 0 & s_\theta & 0 \\
159  0 & 1 & 0 & 0 \\
160  -s_\theta & 0 & c_\theta & 0 \\
161  0 & 0 & 0 & 1
162  \end{bmatrix}
163 
164  :param ry: rotation around Y axis in radians
165  :type ry: float"""
166  ct = math.cos(ry)
167  st = math.sin(ry)
168  return Mat([[ct,0,st,0],[0,1,0,0],[-st,0,ct,0],[0,0,0,1]])
169 
170 def rotz(rz):
171  r"""Returns a rotation matrix around the Z axis
172 
173  .. math::
174 
175  R_x(\theta) = \begin{bmatrix} c_\theta & -s_\theta & 0 & 0 \\
176  s_\theta & c_\theta & 0 & 0 \\
177  0 & 0 & 1 & 0 \\
178  0 & 0 & 0 & 1
179  \end{bmatrix}
180 
181  :param ry: rotation around Y axis in radians
182  :type ry: float"""
183  ct = math.cos(rz)
184  st = math.sin(rz)
185  return Mat([[ct,-st,0,0],[st,ct,0,0],[0,0,1,0],[0,0,0,1]])
186 
187 def transl(tx,ty=None,tz=None):
188  r"""Returns a translation matrix
189 
190  .. math::
191 
192  T(t_x, t_y, t_z) = \begin{bmatrix} 0 & 0 & 0 & t_x \\
193  0 & 0 & 0 & t_y \\
194  0 & 0 & 0 & t_z \\
195  0 & 0 & 0 & 1
196  \end{bmatrix}
197 
198  :param tx: translation along the X axis
199  :type tx: float
200  :param ty: translation along the Y axis
201  :type ty: float
202  :param tz: translation along the Z axis
203  :type tz: float
204  """
205  if ty is None:
206  xx = tx[0]
207  yy = tx[1]
208  zz = tx[2]
209  else:
210  xx = tx
211  yy = ty
212  zz = tz
213  return Mat([[1,0,0,xx],[0,1,0,yy],[0,0,1,zz],[0,0,0,1]])
214 
215 def RelTool(target_pose, x, y, z, rx=0,ry=0,rz=0):
216  """Calculates a relative target with respect to the tool coordinates. This procedure has exactly the same behavior as ABB's RelTool instruction.
217  X,Y,Z are in mm, W,P,R are in degrees."""
218  if type(target_pose) != Mat:
219  target_pose = target_pose.Pose()
220  new_target = target_pose*transl(x,y,z)*rotx(rx*pi/180)*roty(ry*pi/180)*rotz(rz*pi/180)
221  return new_target
222 
223 def Offset(target_pose, x, y, z, rx=0,ry=0,rz=0):
224  """Calculates a relative target with respect to the reference frame coordinates.
225  X,Y,Z are in mm, W,P,R are in degrees."""
226  if type(target_pose) != Mat:
227  # item object assumed:
228  target_pose = target_pose.Pose()
229  if not target_pose.isHomogeneous():
230  raise Exception(MatrixError, "Pose matrix is not homogeneous!")
231  new_target = transl(x,y,z)*rotx(rx*pi/180.0)*roty(ry*pi/180.0)*rotz(rz*pi/180.0)*target_pose
232  return new_target
233 
234 def point_Zaxis_2_pose(point, zaxis, yaxis_hint1=[0,0,1], yaxis_hint2=[0,1,1]):
235  """Returns a pose given the origin as a point, a Z axis and a preferred orientation for the Y axis"""
236  pose = eye(4)
237  pose.setPos(point)
238  pose.setVZ(zaxis)
239  yaprox = yaxis_hint1
240  if angle3(zaxis, yaprox) < 2*pi/180:
241  yaprox = yaxis_hint2
242  xaxis = normalize3(cross(yaprox, zaxis))
243  yaxis = cross(zaxis, xaxis)
244  pose.setVX(xaxis)
245  pose.setVY(yaxis)
246  return pose
247 
248 def eye(size=4):
249  r"""Return the identity matrix
250 
251  .. math::
252 
253  T(t_x, t_y, t_z) = \begin{bmatrix} 1 & 0 & 0 & 0 \\
254  0 & 1 & 0 & 0 \\
255  0 & 0 & 1 & 0 \\
256  0 & 0 & 0 & 1
257  \end{bmatrix}
258 
259  :param size: square matrix size (4 by default)
260  :type size: int"""
261  return Mat([[1,0,0,0],[0,1,0,0],[0,0,1,0],[0,0,0,1]])
262 
263 def size(matrix,dim=None):
264  """Returns the size of a matrix (m,n).
265  Dim can be set to 0 to return m (rows) or 1 to return n (columns)
266 
267  :param matrix: pose
268  :type matrix: :class:`.Mat`
269  :param dim: dimension
270  :type dim: int
271  """
272  return matrix.size(dim)
273 
274 def tr(matrix):
275  """Returns the transpose of the matrix
276 
277  :param matrix: pose
278  :type matrix: :class:`.Mat`"""
279  return matrix.tr()
280 
281 def invH(matrix):
282  """Returns the inverse of a homogeneous matrix
283 
284  :param matrix: pose
285  :type matrix: :class:`.Mat`"""
286  return matrix.invH()
287 
288 def catV(mat1, mat2):
289  """Concatenate 2 matrices (vertical concatenation)"""
290  return mat1.catV(mat2)
291 
292 def catH(mat1, mat2):
293  """Concatenate 2 matrices (horizontal concatenation)"""
294  return mat1.catH(mat2)
295 
296 def tic():
297  """Start a stopwatch timer"""
298  import time
299  global TICTOC_START_TIME
300  TICTOC_START_TIME = time.time()
301 
302 def toc():
303  """Read the stopwatch timer"""
304  import time
305  if 'TICTOC_START_TIME' in globals():
306  elapsed = time.time() - TICTOC_START_TIME
307  #print("Elapsed time is " + str(elapsed) + " seconds.")
308  return elapsed
309  else:
310  print("Toc: start time not set")
311  return -1
312 
313 def LoadList(strfile, separator=','):
314  """Load data from a CSV file or a TXT file to a list of numbers"""
315  import csv
316  # Read all CSV data:
317  csvdata = []
318  with open(strfile) as csvfile:
319  csvread = csv.reader(csvfile, delimiter=separator, quotechar='|')
320  for row in csvread:
321  row_nums = [float(i) for i in row]
322  csvdata.append(row_nums)
323  return csvdata
324 
325 def LoadMat(strfile, separator=','):
326  """Load data from a CSV file or a TXT file to a :class:`.Mat` Matrix"""
327  return Mat(LoadList(strfile,separator))
328 
329 #----------------------------------------------------
330 #------ Pose to xyzrpw and xyzrpw to pose------------
332  """Calculates the equivalent position and euler angles ([x,y,z,r,p,w] array) of the given pose according to the following operation:
333  Note: transl(x,y,z)*rotz(w*pi/180)*roty(p*pi/180)*rotx(r*pi/180)
334  See also: xyzrpw_2_pose()
335 
336  :param H: pose
337  :type H: :class:`.Mat`"""
338  x = H[0,3]
339  y = H[1,3]
340  z = H[2,3]
341  if (H[2,0] > (1.0 - 1e-6)):
342  p = -pi/2
343  r = 0
344  w = math.atan2(-H[1,2],H[1,1])
345  elif H[2,0] < -1.0 + 1e-6:
346  p = pi/2
347  r = 0
348  w = math.atan2(H[1,2],H[1,1])
349  else:
350  p = math.atan2(-H[2,0],sqrt(H[0,0]*H[0,0]+H[1,0]*H[1,0]))
351  w = math.atan2(H[1,0],H[0,0])
352  r = math.atan2(H[2,1],H[2,2])
353  return [x, y, z, r*180/pi, p*180/pi, w*180/pi]
354 
355 def xyzrpw_2_pose(xyzrpw):
356  """Calculates the pose from the position and euler angles ([x,y,z,r,p,w] array)
357  The result is the same as calling: H = transl(x,y,z)*rotz(w*pi/180)*roty(p*pi/180)*rotx(r*pi/180)
358  See also: pose_2_xyzrpw()"""
359  [x,y,z,r,p,w] = xyzrpw
360  a = r*pi/180
361  b = p*pi/180
362  c = w*pi/180
363  ca = math.cos(a)
364  sa = math.sin(a)
365  cb = math.cos(b)
366  sb = math.sin(b)
367  cc = math.cos(c)
368  sc = math.sin(c)
369  H = Mat([[cb*cc, cc*sa*sb - ca*sc, sa*sc + ca*cc*sb, x],[cb*sc, ca*cc + sa*sb*sc, ca*sb*sc - cc*sa, y],[-sb, cb*sa, ca*cb, z],[0,0,0,1]])
370  return H
371 
372 def TxyzRxyz_2_Pose(xyzrpw):
373  """Calculates the pose from the position and euler angles ([x,y,z,rx,ry,rz] array)
374  The result is the same as calling: H = transl(x,y,z)*rotx(rx)*roty(ry)*rotz(rz)"""
375  [x,y,z,rx,ry,rz] = xyzrpw
376  srx = math.sin(rx);
377  crx = math.cos(rx);
378  sry = math.sin(ry);
379  cry = math.cos(ry);
380  srz = math.sin(rz);
381  crz = math.cos(rz);
382  H = Mat([[ cry*crz, -cry*srz, sry, x],[crx*srz + crz*srx*sry, crx*crz - srx*sry*srz, -cry*srx, y],[srx*srz - crx*crz*sry, crz*srx + crx*sry*srz, crx*cry, z],[0,0,0,1]])
383  return H
384 
386  """Converts a pose to a 6-value target as [x,y,z,rx,ry,rz]:
387  H = transl(x,y,z)*rotx(rx)*roty(ry)*rotz(rz).
388 
389  :param H: pose
390  :type H: :class:`.Mat`"""
391  x = H[0,3]
392  y = H[1,3]
393  z = H[2,3]
394  a = H[0,0]
395  b = H[0,1]
396  c = H[0,2]
397  d = H[1,2]
398  e = H[2,2]
399  if c > (1.0 - 1e-6):
400  ry1 = pi/2
401  rx1 = 0
402  rz1 = atan2(H[1,0],H[1,1])
403  elif c < (-1.0 + 1e-6):
404  ry1 = -pi/2
405  rx1 = 0
406  rz1 = atan2(H[1,0],H[1,1])
407  else:
408  sy = c
409  cy1 = +sqrt(1-sy*sy)
410  sx1 = -d/cy1
411  cx1 = e/cy1
412  sz1 = -b/cy1
413  cz1 =a/cy1
414  rx1 = atan2(sx1,cx1)
415  ry1 = atan2(sy,cy1)
416  rz1 = atan2(sz1,cz1)
417  return [x, y, z, rx1, ry1, rz1]
418 
420  """Converts a pose (4x4 matrix) to a Staubli XYZWPR target
421 
422  :param H: pose
423  :type H: :class:`.Mat`"""
424  xyzwpr = Pose_2_TxyzRxyz(H)
425  xyzwpr[3] = xyzwpr[3]*180.0/pi
426  xyzwpr[4] = xyzwpr[4]*180.0/pi
427  xyzwpr[5] = xyzwpr[5]*180.0/pi
428  return xyzwpr
429 
431  """Converts a pose (4x4 matrix) to a Motoman XYZWPR target
432 
433  :param H: pose
434  :type H: :class:`.Mat`"""
435  xyzwpr = pose_2_xyzrpw(H)
436  return xyzwpr
437 
439  """Converts a pose (4x4 matrix) to a Fanuc XYZWPR target
440 
441  :param H: pose
442  :type H: :class:`.Mat`"""
443  xyzwpr = pose_2_xyzrpw(H)
444  return xyzwpr
445 
446 def Motoman_2_Pose(xyzwpr):
447  """Converts a Motoman target to a pose (4x4 matrix)"""
448  return xyzrpw_2_pose(xyzwpr)
449 
450 def Pose_2_KUKA(H):
451  """Converts a pose (4x4 matrix) to a Kuka target
452 
453  :param H: pose
454  :type H: :class:`.Mat`"""
455  x = H[0,3]
456  y = H[1,3]
457  z = H[2,3]
458  if (H[2,0]) > (1.0 - 1e-6):
459  p = -pi/2
460  r = 0
461  w = atan2(-H[1,2],H[1,1])
462  elif (H[2,0]) < (-1.0 + 1e-6):
463  p = pi/2
464  r = 0
465  w = atan2(H[1,2],H[1,1])
466  else:
467  p = atan2(-H[2,0],sqrt(H[0,0]*H[0,0]+H[1,0]*H[1,0]))
468  w = atan2(H[1,0],H[0,0])
469  r = atan2(H[2,1],H[2,2])
470  return [x, y, z, w*180/pi, p*180/pi, r*180/pi]
471 
472 def KUKA_2_Pose(xyzrpw):
473  """Converts a KUKA XYZABC target to a pose (4x4 matrix)"""
474  [x,y,z,r,p,w] = xyzrpw
475  a = r*math.pi/180.0
476  b = p*math.pi/180.0
477  c = w*math.pi/180.0
478  ca = math.cos(a)
479  sa = math.sin(a)
480  cb = math.cos(b)
481  sb = math.sin(b)
482  cc = math.cos(c)
483  sc = math.sin(c)
484  return Mat([[cb*ca, ca*sc*sb - cc*sa, sc*sa + cc*ca*sb, x],[cb*sa, cc*ca + sc*sb*sa, cc*sb*sa - ca*sc, y],[-sb, cb*sc, cc*cb, z],[0.0,0.0,0.0,1.0]])
485 
486 def Adept_2_Pose(xyzrpw):
487  """Converts an Adept XYZRPW target to a pose (4x4 matrix)"""
488  [x,y,z,r,p,w] = xyzrpw
489  a = r*math.pi/180.0
490  b = p*math.pi/180.0
491  c = w*math.pi/180.0
492  ca = math.cos(a)
493  sa = math.sin(a)
494  cb = math.cos(b)
495  sb = math.sin(b)
496  cc = math.cos(c)
497  sc = math.sin(c)
498  return Mat([[ca*cb*cc - sa*sc, - cc*sa - ca*cb*sc, ca*sb, x],[ca*sc + cb*cc*sa, ca*cc - cb*sa*sc, sa*sb, y],[-cc*sb, sb*sc, cb, z],[0.0,0.0,0.0,1.0]])
499 
501  """Converts a pose to an Adept target
502 
503  :param H: pose
504  :type H: :class:`.Mat`"""
505  x = H[0,3]
506  y = H[1,3]
507  z = H[2,3]
508  if H[2,2] > (1.0 - 1e-6):
509  r = 0
510  p = 0
511  w = atan2(H[1,0],H[0,0])
512  elif H[2,2] < (-1.0 + 1e-6):
513  r = 0
514  p = pi
515  w = atan2(H[1,0],H[1,1])
516  else:
517  cb=H[2,2]
518  sb=+sqrt(1-cb*cb)
519  sc=H[2,1]/sb
520  cc=-H[2,0]/sb
521  sa=H[1,2]/sb
522  ca=H[0,2]/sb
523  r = atan2(sa,ca)
524  p = atan2(sb,cb)
525  w = atan2(sc,cc)
526  return [x, y, z, r*180/pi, p*180/pi, w*180/pi]
527 
528 def Comau_2_Pose(xyzrpw):
529  """Converts a Comau XYZRPW target to a pose (4x4 matrix)"""
530  return Adept_2_Pose(xyzrpw)
531 
533  """Converts a pose to a Comau target
534 
535  :param H: pose
536  :type H: :class:`.Mat`"""
537  return Pose_2_Adept(H)
538 
539 def Pose_2_Nachi(pose):
540  """Converts a pose to a Nachi XYZRPW target
541 
542  :param pose: pose
543  :type pose: :class:`.Mat`"""
544  [x,y,z,r,p,w] = pose_2_xyzrpw(pose)
545  return [x,y,z,w,p,r]
546 
547 def Nachi_2_Pose(xyzwpr):
548  """Converts a Nachi XYZRPW target to a pose (4x4 matrix)"""
549  return Fanuc_2_Pose(xyzwpr)
550 
552  """Returns the quaternion orientation vector of a pose (4x4 matrix)
553 
554  :param Ti: pose
555  :type Ti: :class:`.Mat`"""
556  a=(Ti[0,0])
557  b=(Ti[1,1])
558  c=(Ti[2,2])
559  sign2=1
560  sign3=1
561  sign4=1
562  if (Ti[2,1]-Ti[1,2])<0:
563  sign2=-1;
564  if (Ti[0,2]-Ti[2,0])<0:
565  sign3=-1;
566  if (Ti[1,0]-Ti[0,1])<0:
567  sign4=-1
568  q1=sqrt(max(a+b+c+1,0))/2
569  q2=sign2*sqrt(max(a-b-c+1,0))/2
570  q3=sign3*sqrt(max(-a+b-c+1,0))/2
571  q4=sign4*sqrt(max(-a-b+c+1,0))/2
572  return [q1, q2, q3, q4]
573 
575  """Returns the pose orientation matrix (4x4 matrix) from a quaternion orientation vector"""
576  qnorm = sqrt(qin[0]*qin[0]+qin[1]*qin[1]+qin[2]*qin[2]+qin[3]*qin[3])
577  q = qin
578  q[0] = q[0]/qnorm
579  q[1] = q[1]/qnorm
580  q[2] = q[2]/qnorm
581  q[3] = q[3]/qnorm
582  pose = Mat([[ 1 - 2*q[2]*q[2] - 2*q[3]*q[3] , 2*q[1]*q[2] - 2*q[3]*q[0] , 2*q[1]*q[3] + 2*q[2]*q[0] , 0],
583  [2*q[1]*q[2] + 2*q[3]*q[0] , 1 - 2*q[1]*q[1] - 2*q[3]*q[3] , 2*q[2]*q[3] - 2*q[1]*q[0] , 0],
584  [2*q[1]*q[3] - 2*q[2]*q[0] , 2*q[2]*q[3] + 2*q[1]*q[0] , 1 - 2*q[1]*q[1] - 2*q[2]*q[2], 0],
585  [0 , 0 , 0 , 1]])
586  return pose
587 
588 
589 def Pose_2_ABB(H):
590  """Converts a pose to an ABB target
591 
592  :param H: pose
593  :type H: :class:`.Mat`"""
594  q = pose_2_quaternion(H)
595  return [H[0,3],H[1,3],H[2,3],q[0],q[1],q[2],q[3]]
596 
597 def print_pose_ABB(pose):
598  """Displays an ABB RAPID target
599 
600  :param pose: pose
601  :type pose: :class:`.Mat`"""
602  q = pose_2_quaternion(pose)
603  print('[[%.3f,%.3f,%.3f],[%.6f,%.6f,%.6f,%.6f]]'%(pose[0,3],pose[1,3],pose[2,3],q[0],q[1],q[2],q[3]))
604 
605 def Pose_2_UR(pose):
606  """Calculate the p[x,y,z,rx,ry,rz] position for a pose target"""
607  def saturate_1(value):
608  return min(max(value,-1.0),1.0)
609 
610  angle = acos( saturate_1((pose[0,0]+pose[1,1]+pose[2,2]-1)/2) )
611  rxyz = [pose[2,1]-pose[1,2], pose[0,2]-pose[2,0], pose[1,0]-pose[0,1]]
612 
613  if angle == 0:
614  rxyz = [0,0,0]
615  else:
616  rxyz = normalize3(rxyz)
617  rxyz = mult3(rxyz, angle)
618  return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
619 
620 def UR_2_Pose(xyzwpr):
621  """Calculate the pose target given a p[x,y,z,rx,ry,rz] cartesian target"""
622  x,y,z,w,p,r = xyzwpr
623  wpr = [w,p,r]
624  angle = norm(wpr)
625  cosang = cos(0.5*angle)
626 
627  if angle == 0.0:
628  q234 = [0.0,0.0,0.0]
629  else:
630  ratio = sin(0.5*angle)/angle
631  q234 = mult3(wpr, ratio)
632 
633  q1234 = [cosang, q234[0], q234[1], q234[2]]
634  pose = quaternion_2_pose(q1234)
635  pose.setPos([x,y,z])
636  return pose
637 
638 #----------------------------------------------------
639 #-------- ROBOT MODEL (D-H and D-H M) ---------------
640 
641 def dh(rz,tx=None,tz=None,rx=None):
642  """Returns the Denavit-Hartenberg 4x4 matrix for a robot link.
643  calling dh(rz,tx,tz,rx) is the same as using rotz(rz)*transl(tx,0,tx)*rotx(rx)
644  calling dh(rz,tx,tz,rx) is the same as calling dh([rz,tx,tz,rx])
645  """
646  if tx is None: [rz,tx,tz,rx] = rz
647 
648  crx = math.cos(rx)
649  srx = math.sin(rx)
650  crz = math.cos(rz)
651  srz = math.sin(rz)
652  return Mat( [[crz, -srz*crx, srz*srx, tx*crz],
653  [srz, crz*crx, -crz*srx, tx*srz],
654  [ 0, srx, crx, tz],
655  [ 0, 0, 0, 1]]);
656 
657 def dhm(rx, tx=None, tz=None, rz=None):
658  """Returns the Denavit-Hartenberg Modified 4x4 matrix for a robot link (Craig 1986).
659  calling dhm(rx,tx,tz,rz) is the same as using rotx(rx)*transl(tx,0,tx)*rotz(rz)
660  calling dhm(rx,tx,tz,rz) is the same as calling dhm([rx,tx,tz,rz])
661  """
662  if tx is None: [rx,tx,tz,rz] = rx
663 
664  crx = math.cos(rx)
665  srx = math.sin(rx)
666  crz = math.cos(rz)
667  srz = math.sin(rz)
668  return Mat([[crz, -srz, 0, tx],
669  [crx*srz, crx*crz, -srx, -tz*srx],
670  [srx*srz, crz*srx, crx, tz*crx],
671  [ 0, 0, 0, 1]]);
672 
673 def joints_2_angles(jin, type):
674  """Converts the robot joints into angles between links depending on the type of the robot."""
675  jout = jin
676  if type == 2:
677  jout[2] = -jin[1] - jin[2]
678  jout[3] = -jin[3]
679  jout[4] = -jin[4]
680  jout[5] = -jin[5]
681  elif type == 3:
682  jout[2] = -jin[2]
683  jout[3] = -jin[3]
684  jout[4] = -jin[4]
685  jout[5] = -jin[5]
686  elif type == 4:
687  jout[2] = +jin[1] + jin[2]
688  return jout
689 
690 def angles_2_joints(jin, type):
691  """Converts the angles between links into the robot joint space depending on the type of the robot."""
692  jout = jin
693  if type == 2:
694  jout[2] = -jin[1] - jin[2]
695  jout[3] = -jin[3]
696  jout[4] = -jin[4]
697  jout[5] = -jin[5]
698  elif type == 3:
699  jout[2] = -jin[2]
700  jout[3] = -jin[3]
701  jout[4] = -jin[4]
702  jout[5] = -jin[5]
703  return jout
704 
705 #----------------------------------------------------
706 #-------- Useful geometric tools ---------------
707 
708 def norm(p):
709  """Returns the norm of a 3D vector"""
710  return sqrt(p[0]*p[0] + p[1]*p[1] + p[2]*p[2])
711 
712 def normalize3(a):
713  """Returns the unitary vector"""
714  norminv = 1.0/norm(a)
715  return [a[0]*norminv,a[1]*norminv,a[2]*norminv]
716 
717 def cross(a, b):
718  """Returns the cross product of two 3D vectors"""
719  c = [a[1]*b[2] - a[2]*b[1],
720  a[2]*b[0] - a[0]*b[2],
721  a[0]*b[1] - a[1]*b[0]]
722  return c
723 
724 def dot(a,b):
725  """Returns the dot product of two 3D vectors"""
726  return a[0]*b[0] + a[1]*b[1] + a[2]*b[2]
727 
728 def angle3(a,b):
729  """Returns the angle in radians of two 3D vectors"""
730  return acos(dot(normalize3(a),normalize3(b)))
731 
732 def pose_angle(pose):
733  """Returns the angle in radians of a 4x4 matrix pose
734 
735  :param pose: pose
736  :type pose: :class:`.Mat`"""
737  cos_ang = (pose[0,0]+pose[1,1]+pose[2,2]-1)/2
738  cos_ang = min(max(cos_ang,-1),1)
739  return acos(cos_ang)
740 
741 def pose_angle_between(pose1, pose2):
742  """Returns the angle in radians between two poses (4x4 matrix pose)"""
743  return pose_angle(invH(pose1)*pose2)
744 
745 def mult3(v,d):
746  """Multiplies a 3D vector to a scalar"""
747  return [v[0]*d, v[1]*d, v[2]*d]
748 
749 def subs3(a,b):
750  """Subtracts two 3D vectors c=a-b"""
751  return [a[0]-b[0],a[1]-b[1],a[2]-b[2]]
752 
753 def add3(a,b):
754  """Adds two 3D vectors c=a+b"""
755  return [a[0]+b[0],a[1]+b[1],a[2]+b[2]]
756 
757 def distance(a,b):
758  """Calculates the distance between two points"""
759  return norm(subs3(a,b))
760 
761 
762 def intersect_line_2_plane(pline,vline,pplane,vplane):
763  """Calculates the intersection betweeen a line and a plane"""
764  D = -dot(vplane,pplane)
765  k = -(D+dot(vplane,pline))/dot(vplane,vline)
766  p = add3(pline,mult3(vline,k))
767  return p
768 
769 def proj_pt_2_plane(point,planepoint,planeABC):
770  """Projects a point to a plane"""
771  return intersect_line_2_plane(point,planeABC,planepoint,planeABC);
772 
773 def proj_pt_2_line(point, paxe, vaxe):
774  """Projects a point to a line"""
775  vpaxe2point = subs3(point,paxe)
776  dist = dot(vaxe,vpaxe2point)/dot(vaxe,vaxe)
777  return add3(paxe,mult3(vaxe,dist))
778 
779 def fitPlane(points):
780  """Best fits a plane to a cloud of points"""
781  import numpy as np
782  XYZ = np.array(points)
783  [rows,cols] = XYZ.shape
784  # Set up constraint equations of the form AB = 0,
785  # where B is a column vector of the plane coefficients
786  # in the form b(1)*X + b(2)*Y +b(3)*Z + b(4) = 0.
787  p = (np.ones((rows,1)))
788  AB = np.hstack([XYZ,p])
789  [u, d, v] = np.linalg.svd(AB,0)
790  B = v[3,:] # Solution is last column of v.
791  nn = np.linalg.norm(B[0:3])
792  B = B / nn
793  pplane = [0,0,-(B[3]/B[2])]
794  vplane = B[0:3].tolist()
795  return pplane, vplane
796 
797 
798 #----------------------------------------------------
799 #-------- Mat matrix class ---------------
800 
801 class MatrixError(Exception):
802  """ An exception class for Matrix """
803  pass
804 
805 class Mat(object):
806  """A pose matrix object. A pose is a 4x4 matrix that represents the position and orientation of one reference frame with respect to another one, in the 3D space.
807  This type is meant to be used for robotics."""
808 
809  def __init__(self, rows=None, ncols=None):
810  if ncols is None:
811  if rows is None:
812  m = 4
813  n = 4
814  self.rows = [[0]*n for x in range(m)]
815  else:
816  if isinstance(rows,Mat):
817  rows = rows.copy().rows
818  m = len(rows)
819  transpose = 0
820  if not isinstance(rows[0],list):
821  rows = [rows]
822  transpose = 1
823  n = len(rows[0])
824  if any([len(row) != n for row in rows[1:]]):# Validity check
825  raise Exception(MatrixError, "inconsistent row length")
826  self.rows = rows
827  if transpose:
828  self.rows = [list(item) for item in zip(*self.rows)]
829  else:
830  m = rows
831  n = ncols
832  self.rows = [[0]*n for x in range(m)]
833  def copy(self):
834  sz = self.size()
835  newmat = Mat(sz[0],sz[1])
836  for i in range(sz[0]):
837  for j in range(sz[1]):
838  newmat[i,j] = self[i,j]
839  return newmat
840 
841  def __getitem__(self, idx):
842  if isinstance(idx,int):#integer A[1]
843  return tr(Mat(self.rows[idx]))
844  elif isinstance(idx,slice):#one slice: A[1:3]
845  return Mat(self.rows[idx])
846  else:#two slices: A[1:3,1:3]
847  idx1 = idx[0]
848  idx2 = idx[1]
849  if isinstance(idx1,int) and isinstance(idx2,int):
850  return self.rows[idx1][idx2]
851  matsize =self.size();
852  if isinstance(idx1,slice):
853  indices1 = idx1.indices(matsize[0])
854  rg1 = range(*indices1)
855  else: #is int
856  rg1 = range(idx1,idx1+1)
857  if isinstance(idx2,slice):
858  indices2 = idx2.indices(matsize[1])
859  rg2 = range(*indices2)
860  else: #is int
861  rg2 = range(idx2,idx2+1)
862  #newm = int(abs((rg1.stop-rg1.start)/rg1.step))
863  #newn = int(abs((rg2.stop-rg2.start)/rg2.step))
864  newm = rg1
865  newn = rg2
866  newmat = Mat(len(newm),len(newn))
867  cm = 0
868  for i in rg1:
869  cn = 0
870  for j in rg2:
871  newmat.rows[cm][cn] = self.rows[i][j]
872  cn = cn + 1
873  cm = cm + 1
874  return newmat
875  def __setitem__(self, idx, item):
876  if isinstance(item,float) or isinstance(item,int):
877  item = Mat([[item]])
878  elif isinstance(item, list):
879  item = Mat(item)
880 
881  matsize = self.size();
882  if isinstance(idx,int):#integer A[1]
883  idx1 = idx
884  idx2 = 0
885  #raise Exception(MatrixError, "Cannot set item. Use [i,:] instead.")
886  #self.rows[idx] = item
887  elif isinstance(idx,slice):#one slice: A[1:3]
888  # raise Exception(MatrixError, "Cannot set item. Use [a:b,:] instead.")
889  idx1 = idx
890  idx2 = 0
891  else:
892  idx1 = idx[0]
893  idx2 = idx[1]
894 
895  # at this point we have two slices: example A[1:3,1:3]
896  if isinstance(idx1,slice):
897  indices1 = idx1.indices(matsize[0])
898  rg1 = range(*indices1)
899  else: #is int
900  rg1 = range(idx1,idx1+1)
901  if isinstance(idx2,slice):
902  indices2 = idx2.indices(matsize[1])
903  rg2 = range(*indices2)
904  else: #is int
905  rg2 = range(idx2,idx2+1)
906  #newm = int(abs((rg1.stop-rg1.start)/rg1.step))
907  #newn = int(abs((rg2.stop-rg2.start)/rg2.step))
908  newm = rg1
909  newn = rg2
910  itmsz = item.size();
911  if len(newm) != itmsz[0] or len(newn) != itmsz[1]:
912  raise Exception(MatrixError, "Submatrix indices does not match the new matrix sizes",itmsz[0],"x",itmsz[1],"<-",newm,"x",newn)
913  #newmat = Mat(newm,newn)
914  cm = 0
915  for i in rg1:
916  cn = 0
917  for j in rg2:
918  self.rows[i][j] = item.rows[cm][cn]
919  cn = cn + 1
920  cm = cm + 1
921 
922  def __str__(self):
923  #s='\n [ '.join([(', '.join([str(item) for item in row])+' ],') for row in self.rows])
924  s='\n [ '.join([(', '.join(['%.3f'%item for item in row])+' ],') for row in self.rows])
925  return '[[ ' + s[:-1] + ']\n'
926 
927  def __repr__(self):
928  s=str(self)
929  rank = str(self.size())
930  rep="Matrix: %s\n%s" % (rank,s)
931  return rep
932 
933  def tr(self):
934  """Returns the transpose of the matrix"""
935  mat = Mat([list(item) for item in zip(*self.rows)])
936  return mat
937 
938  def size(self,dim=None):
939  """Returns the size of a matrix (m,n).
940  Dim can be set to 0 to return m (rows) or 1 to return n (columns)"""
941  m = len(self.rows)
942  n = len(self.rows[0])
943  if dim is None:
944  return (m, n)
945  elif dim==0:
946  return m
947  elif dim==1:
948  return n
949  else:
950  raise Exception(MatrixError, "Invalid dimension!")
951 
952  def catV(self,mat2):
953  """Concatenate with another matrix (vertical concatenation)"""
954  if not isinstance(mat2, Mat):
955  raise Exception(MatrixError, "Concatenation must be performed with 2 matrices")
956  sz1 = self.size()
957  sz2 = mat2.size()
958  if sz1[1] != sz2[1]:
959  raise Exception(MatrixError, "Horizontal size of matrices does not match")
960  newmat = Mat(sz1[0]+sz2[0],sz1[1])
961  newmat[0:sz1[0],:] = self
962  newmat[sz1[0]:,:] = mat2
963  return newmat
964 
965  def catH(self,mat2):
966  """Concatenate with another matrix (horizontal concatenation)"""
967  if not isinstance(mat2, Mat):
968  raise Exception(MatrixError, "Concatenation must be performed with 2 matrices")
969  sz1 = self.size()
970  sz2 = mat2.size()
971  if sz1[0] != sz2[0]:
972  raise Exception(MatrixError, "Horizontal size of matrices does not match")
973  newmat = Mat(sz1[0],sz1[1]+sz2[1])
974  newmat[:,:sz1[1]] = self
975  newmat[:,sz1[1]:] = mat2
976  return newmat
977  def __eq__(self, mat):
978  """Test equality"""
979  return (mat.rows == self.rows)
980 
981  def __add__(self, mat):
982  """Add a matrix to this matrix and
983  return the new matrix. It doesn't modify
984  the current matrix"""
985  if isinstance(mat,int) or isinstance(mat,float):
986  m, n = self.size()
987  result = Mat(m, n)
988  for x in range(m):
989  for y in range(n):
990  result.rows[x][y] = self.rows[x][y] + mat
991  return result
992  sz = self.size()
993  m = sz[0]
994  n = sz[1]
995  ret = Mat(m,n)
996  if sz != mat.size():
997  raise Exception(MatrixError, "Trying to add matrixes of varying size!")
998  for x in range(m):
999  row = [sum(item) for item in zip(self.rows[x], mat.rows[x])]
1000  ret.rows[x] = row
1001  return ret
1002 
1003  def __sub__(self, mat):
1004  """Subtract a matrix from this matrix and
1005  return the new matrix. It doesn't modify
1006  the current matrix"""
1007  if isinstance(mat,int) or isinstance(mat,float):
1008  m, n = self.size()
1009  result = Mat(m, n)
1010  for x in range(m):
1011  for y in range(n):
1012  result.rows[x][y] = self.rows[x][y] - mat
1013  return result
1014  sz = self.size()
1015  m = sz[0]
1016  n = sz[1]
1017  ret = Mat(m,n)
1018  if sz != mat.size():
1019  raise Exception(MatrixError, "Trying to add matrixes of varying size!")
1020  for x in range(m):
1021  row = [item[0]-item[1] for item in zip(self.rows[x], mat.rows[x])]
1022  ret.rows[x] = row
1023  return ret
1024 
1025  def __mul__(self, mat):
1026  """Multiply a matrix with this matrix and
1027  return the new matrix. It doesn't modify
1028  the current matrix"""
1029  if isinstance(mat,int) or isinstance(mat,float):
1030  m, n = self.size()
1031  mulmat = Mat(m, n)
1032  for x in range(m):
1033  for y in range(n):
1034  mulmat.rows[x][y] = self.rows[x][y]*mat
1035  return mulmat
1036  if isinstance(mat,list):#case of a matrix times a vector
1037  szvect = len(mat)
1038  m = self.size(0);
1039  matvect = Mat(mat)
1040  if szvect + 1 == m:
1041  vectok = catV(matvect,Mat([[1]]))
1042  result = self*vectok
1043  return (result[:-1,:]).tr().rows[0]
1044  elif szvect == m:
1045  result = self*Mat(matvect)
1046  return result.tr().rows[0]
1047  else:
1048  raise Exception(MatrixError, "Invalid product")
1049  else:
1050  matm, matn = mat.size()
1051  m, n = self.size()
1052  if (n != matm):
1053  raise Exception(MatrixError, "Matrices cannot be multipled!")
1054  mat_t = mat.tr()
1055  mulmat = Mat(m, matn)
1056  for x in range(m):
1057  for y in range(mat_t.size(0)):
1058  mulmat.rows[x][y] = sum([item[0]*item[1] for item in zip(self.rows[x], mat_t.rows[y])])
1059  return mulmat
1060 
1061  def eye(self, m=4):
1062  """Make identity matrix of size (mxm)"""
1063  rows = [[0]*m for x in range(m)]
1064  idx = 0
1065  for row in rows:
1066  row[idx] = 1
1067  idx += 1
1068  return Mat(rows)
1069 
1070  def isHomogeneous(self):
1071  """returns 1 if it is a Homogeneous matrix"""
1072  m,n = self.size()
1073  if m != 4 or n != 4:
1074  return False
1075  #if self[3,:] != Mat([[0.0,0.0,0.0,1.0]]):
1076  # return False
1077  test = self[0:3,0:3];
1078  test = test*test.tr()
1079  test[0,0] = test[0,0] - 1.0
1080  test[1,1] = test[1,1] - 1.0
1081  test[2,2] = test[2,2] - 1.0
1082  zero = 0.0
1083  for x in range(3):
1084  for y in range(3):
1085  zero = zero + abs(test[x,y])
1086  if zero > 1e-4:
1087  return False
1088  return True
1089 
1090  def RelTool(self, x, y, z, rx=0,ry=0,rz=0):
1091  """Calculates a target relative with respect to the tool coordinates.
1092  X,Y,Z are in mm, W,P,R are in degrees."""
1093  return RelTool(self, x, y, z, rx, ry, rz)
1094 
1095  def Offset(self, x, y, z, rx=0,ry=0,rz=0):
1096  """Calculates a target relative with respect to the reference frame coordinates.
1097  X,Y,Z are in mm, W,P,R are in degrees."""
1098  return Offset(self, x, y, z, rx, ry, rz)
1099 
1100  def invH(self):
1101  """Calculates the inverse of a homogeneous matrix"""
1102  if not self.isHomogeneous():
1103  raise Exception(MatrixError, "Pose matrix is not homogeneous. invH() can only compute the inverse of a homogeneous matrix")
1104  Hout = self.tr()
1105  Hout[3,0:3] = Mat([[0,0,0]]);
1106  Hout[0:3,3] = (Hout[0:3,0:3]*self[0:3,3])*(-1)
1107  return Hout
1108 
1109  def tolist(self):
1110  """Returns the first column vector of the matrix as a list"""
1111  return tr(self).rows[0]
1112 
1113  def Pos(self):
1114  """Returns the position of a pose (assumes that a 4x4 homogeneous matrix is being used)"""
1115  return self[0:3,3].tolist()
1116 
1117  def VX(self):
1118  """Returns the X vector of a pose (assumes that a 4x4 homogeneous matrix is being used)"""
1119  return self[0:3,0].tolist()
1120 
1121  def VY(self):
1122  """Returns the Y vector of a pose (assumes that a 4x4 homogeneous matrix is being used)"""
1123  return self[0:3,1].tolist()
1124 
1125  def VZ(self):
1126  """Returns the Z vector of a pose (assumes that a 4x4 homogeneous matrix is being used)"""
1127  return self[0:3,2].tolist()
1128 
1129  def setPos(self, newpos):
1130  """Sets the XYZ position of a pose (assumes that a 4x4 homogeneous matrix is being used)"""
1131  self[0,3] = newpos[0]
1132  self[1,3] = newpos[1]
1133  self[2,3] = newpos[2]
1134 
1135  def setVX(self, v_xyz):
1136  """Sets the VX vector of a pose, which is the first column of a homogeneous matrix (assumes that a 4x4 homogeneous matrix is being used)"""
1137  v_xyz = normalize3(v_xyz)
1138  self[0,0] = v_xyz[0]
1139  self[1,0] = v_xyz[1]
1140  self[2,0] = v_xyz[2]
1141 
1142  def setVY(self, v_xyz):
1143  """Sets the VY vector of a pose, which is the first column of a homogeneous matrix (assumes that a 4x4 homogeneous matrix is being used)"""
1144  v_xyz = normalize3(v_xyz)
1145  self[0,1] = v_xyz[0]
1146  self[1,1] = v_xyz[1]
1147  self[2,1] = v_xyz[2]
1148 
1149  def setVZ(self, v_xyz):
1150  """Sets the VZ vector of a pose, which is the first column of a homogeneous matrix (assumes that a 4x4 homogeneous matrix is being used)"""
1151  v_xyz = normalize3(v_xyz)
1152  self[0,2] = v_xyz[0]
1153  self[1,2] = v_xyz[1]
1154  self[2,2] = v_xyz[2]
1155 
1156  def SaveMat(self, strfile):
1157  """Save :class:`.Mat` Matrix to a CSV or TXT file"""
1158  sz = self.size()
1159  m = sz[0]
1160  n = sz[1]
1161  file = open(strfile, 'w')
1162  for j in range(n):
1163  for i in range(m):
1164  file.write('%.6f ' % self.rows[i][j])
1165  file.write('\n')
1166  file.close()
1167 
1168 #-------------------------------------------------------
1169 # FTP TRANSFER Tools
1170 def RemoveFileFTP(ftp, filepath):
1171  """Delete a file on a remote server."""
1172  import ftplib
1173  try:
1174  ftp.delete(filepath)
1175  except ftplib.all_errors as e:
1176  import sys
1177  print('POPUP: Could not remove file {0}: {1}'.format(filepath, e))
1178  sys.stdout.flush()
1179 
1180 def RemoveDirFTP(ftp, path):
1181  """Recursively delete a directory tree on a remote server."""
1182  import ftplib
1183  wd = ftp.pwd()
1184  try:
1185  names = ftp.nlst(path)
1186  except ftplib.all_errors as e:
1187  # some FTP servers complain when you try and list non-existent paths
1188  print('RemoveDirFTP: Could not remove folder {0}: {1}'.format(path, e))
1189  return
1190 
1191  for name in names:
1192  if os.path.split(name)[1] in ('.', '..'): continue
1193  print('RemoveDirFTP: Checking {0}'.format(name))
1194  try:
1195  ftp.cwd(path+'/'+name) # if we can cwd to it, it's a folder
1196  ftp.cwd(wd) # don't try a nuke a folder we're in
1197  RemoveDirFTP(ftp, path+'/'+name)
1198  except ftplib.all_errors:
1199  ftp.delete(path+'/'+name)
1200  #RemoveFileFTP(ftp, name)
1201 
1202  try:
1203  ftp.rmd(path)
1204  except ftplib.all_errors as e:
1205  print('RemoveDirFTP: Could not remove {0}: {1}'.format(path, e))
1206 
1207 def UploadDirFTP(localpath, server_ip, remote_path, username, password):
1208  """Upload a folder to a robot through FTP recursively"""
1209  import ftplib
1210  import os
1211  import sys
1212  main_folder = os.path.basename(os.path.normpath(localpath))
1213  print("POPUP: <p>Connecting to <strong>%s</strong> using user name <strong>%s</strong> and password ****</p><p>Please wait...</p>" % (server_ip, username))
1214  sys.stdout.flush()
1215  try:
1216  myFTP = ftplib.FTP(server_ip, username, password)
1217  print('Connection established')
1218  except:
1219  error_str = sys.exc_info()[1]
1220  print("POPUP: <font color=\"red\">Connection to %s failed: <p>%s</p></font>" % (server_ip,error_str))
1221  sys.stdout.flush()
1222  pause(4)
1223  return False
1224 
1225  remote_path_prog = remote_path + '/' + main_folder
1226  myPath = r'%s' % localpath
1227  print("POPUP: Connected. Deleting existing files on %s..." % remote_path_prog)
1228  sys.stdout.flush()
1229  RemoveDirFTP(myFTP, remote_path_prog)
1230  print("POPUP: Connected. Uploading program to %s..." % server_ip)
1231  sys.stdout.flush()
1232  try:
1233  myFTP.cwd(remote_path)
1234  myFTP.mkd(main_folder)
1235  myFTP.cwd(remote_path_prog)
1236  except:
1237  error_str = sys.exc_info()[1]
1238  print("POPUP: <font color=\"red\">Remote path not found or can't be created: %s</font>" % (remote_path))
1239  sys.stdout.flush()
1240  pause(4)
1241  #contin = mbox("Remote path\n%s\nnot found or can't create folder.\n\nChange path and permissions and retry." % remote_path)
1242  return False
1243 
1244  def uploadThis(path):
1245  files = os.listdir(path)
1246  os.chdir(path)
1247  for f in files:
1248  if os.path.isfile(path + r'\{}'.format(f)):
1249  print(' Sending file: %s' % f)
1250  print("POPUP: Sending file: %s" % f)
1251  sys.stdout.flush()
1252  fh = open(f, 'rb')
1253  myFTP.storbinary('STOR %s' % f, fh)
1254  fh.close()
1255  elif os.path.isdir(path + r'\{}'.format(f)):
1256  print(' Sending folder: %s' % f)
1257  myFTP.mkd(f)
1258  myFTP.cwd(f)
1259  uploadThis(path + r'\{}'.format(f))
1260  myFTP.cwd('..')
1261  os.chdir('..')
1262  uploadThis(myPath) # now call the recursive function
1263  myFTP.close()
1264  return True
1265 
1266 def UploadFileFTP(file_path_name, server_ip, remote_path, username, password):
1267  """Upload a file to a robot through FTP"""
1268  filepath = getFileDir(file_path_name)
1269  filename = getBaseName(file_path_name)
1270  import ftplib
1271  import os
1272  import sys
1273  print("POPUP: <p>Connecting to <strong>%s</strong> using user name <strong>%s</strong> and password ****</p><p>Please wait...</p>" % (server_ip, username))
1274  sys.stdout.flush()
1275  try:
1276  myFTP = ftplib.FTP(server_ip, username, password)
1277  except:
1278  error_str = sys.exc_info()[1]
1279  print("POPUP: <font color=\"red\">Connection to %s failed: <p>%s</p></font>" % (server_ip,error_str))
1280  sys.stdout.flush()
1281  pause(4)
1282  return False
1283 
1284  remote_path_prog = remote_path + '/' + filename
1285  print("POPUP: Connected. Deleting remote file %s..." % remote_path_prog)
1286  sys.stdout.flush()
1287  RemoveFileFTP(myFTP, remote_path_prog)
1288  print("POPUP: Connected. Uploading program to %s..." % server_ip)
1289  sys.stdout.flush()
1290  try:
1291  myFTP.cwd(remote_path)
1292  except:
1293  error_str = sys.exc_info()[1]
1294  print("POPUP: <font color=\"red\">Remote path not found or can't be created: %s</font>" % (remote_path))
1295  sys.stdout.flush()
1296  pause(4)
1297  #contin = mbox("Remote path\n%s\nnot found or can't create folder.\n\nChange path and permissions and retry." % remote_path)
1298  return False
1299 
1300  def uploadThis(localfile, filename):
1301  print(' Sending file: %s' % localfile)
1302  print("POPUP: Sending file: %s" % filename)
1303  sys.stdout.flush()
1304  fh = open(localfile, 'rb')
1305  myFTP.storbinary('STOR %s' % filename, fh)
1306  fh.close()
1307 
1308  uploadThis(file_path_name, filename)
1309  myFTP.close()
1310  return True
1311 
1312 def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass):
1313  """Upload a program or a list of programs to the robot through FTP provided the connection parameters"""
1314  # Iterate through program list if it is a list of files
1315  if isinstance(program, list):
1316  if len(program) == 0:
1317  print('POPUP: Nothing to transfer')
1318  return
1319  for prog in program:
1320  UploadFTP(prog, robot_ip, remote_path, ftp_user, ftp_pass)
1321  return
1322 
1323  import os
1324  if os.path.isfile(program):
1325  print('Sending program file %s...' % program)
1326  UploadFileFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
1327  else:
1328  print('Sending program folder %s...' % program)
1329  UploadDirFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
1330 
1331 
1332 
1333 #----------------------------------------------------
1334 #-------- MessageBox class ---------------
1335 # inspired from:
1336 # http://stackoverflow.com/questions/10057672/correct-way-to-implement-a-custom-popup-tkinter-dialog-box
1337 
1338 try:
1339 
1340  import Tkinter as tkinter
1341  import tkFileDialog as filedialog
1342 except ImportError:
1343 
1344  from tkinter import filedialog
1345 
1347  """Pop up a file dialog window to select a file to open."""
1348  root = tkinter.Tk()
1349  root.withdraw()
1350  file_path = filedialog.askopenfilename()
1351  # same as: file_path = tkinter.filedialog.askopenfilename()
1352  return file_path
1353 
1354 def getSaveFile(strdir='C:\\', strfile = 'file.txt', strtitle='Save file as ...'):
1355  """Pop up a file dialog window to select a file to save."""
1356  options = {}
1357  options['initialdir'] = strdir
1358  options['title'] = strtitle
1359  #options['defaultextension'] = '.txt'
1360  #options['filetypes'] = [('all files', '.*'), ('text files', '.txt')]
1361  options['initialfile'] = strfile
1362  #options['parent'] = root
1363  root = tkinter.Tk()
1364  root.withdraw()
1365  file_path = filedialog.asksaveasfile(**options)
1366  #same as: file_path = tkinter.filedialog.asksaveasfile(**options)
1367  return file_path
1368 
1369 class MessageBox(object):
1370 
1371  def __init__(self, msg, b1, b2, frame, t, entry):
1372 
1373  root = self.root = tkinter.Tk()
1374  root.title('Message')
1375  self.msg = str(msg)
1376  # ctrl+c to copy self.msg
1377  root.bind('<Control-c>', func=self.to_clip)
1378  # remove the outer frame if frame=False
1379  if not frame: root.overrideredirect(True)
1380  # default values for the buttons to return
1381  self.b1_return = True
1382  self.b2_return = False
1383  # if b1 or b2 is a tuple unpack into the button text & return value
1384  if isinstance(b1, tuple): b1, self.b1_return = b1
1385  if isinstance(b2, tuple): b2, self.b2_return = b2
1386  # main frame
1387  frm_1 = tkinter.Frame(root)
1388  frm_1.pack(ipadx=2, ipady=2)
1389  # the message
1390  message = tkinter.Label(frm_1, text=self.msg)
1391  message.pack(padx=8, pady=8)
1392  # if entry=True create and set focus
1393  if entry is not None:
1394  if entry == True:
1395  entry = ''
1396  self.entry = tkinter.Entry(frm_1)
1397  self.entry.pack()
1398  self.entry.insert(0, entry)
1399  self.entry.focus_set()
1400  # button frame
1401  frm_2 = tkinter.Frame(frm_1)
1402  frm_2.pack(padx=4, pady=4)
1403  # buttons
1404  btn_1 = tkinter.Button(frm_2, width=8, text=b1)
1405  btn_1['command'] = self.b1_action
1406  btn_1.pack(side='left')
1407  if not entry: btn_1.focus_set()
1408  btn_2 = tkinter.Button(frm_2, width=8, text=b2)
1409  btn_2['command'] = self.b2_action
1410  btn_2.pack(side='left')
1411  # the enter button will trigger the focused button's action
1412  btn_1.bind('<KeyPress-Return>', func=self.b1_action)
1413  btn_2.bind('<KeyPress-Return>', func=self.b2_action)
1414  # roughly center the box on screen
1415  # for accuracy see: http://stackoverflow.com/a/10018670/1217270
1416  root.update_idletasks()
1417  xp = (root.winfo_screenwidth() // 2) - (root.winfo_width() // 2)
1418  yp = (root.winfo_screenheight() // 2) - (root.winfo_height() // 2)
1419  geom = (root.winfo_width(), root.winfo_height(), xp, yp)
1420  root.geometry('{0}x{1}+{2}+{3}'.format(*geom))
1421  # call self.close_mod when the close button is pressed
1422  root.protocol("WM_DELETE_WINDOW", self.close_mod)
1423  # a trick to activate the window (on windows 7)
1424  root.deiconify()
1425  # if t is specified: call time_out after t seconds
1426  if t: root.after(int(t*1000), func=self.time_out)
1427 
1428  def b1_action(self, event=None):
1429  try: x = self.entry.get()
1430  except AttributeError:
1431  self.returning = self.b1_return
1432  self.root.quit()
1433  else:
1434  if x:
1435  self.returning = x
1436  self.root.quit()
1437 
1438  def b2_action(self, event=None):
1439  self.returning = self.b2_return
1440  self.root.quit()
1441 
1442  # remove this function and the call to protocol
1443  # then the close button will act normally
1444  def close_mod(self):
1445  pass
1446 
1447  def time_out(self):
1448  try: x = self.entry.get()
1449  except AttributeError: self.returning = None
1450  else: self.returning = x
1451  finally: self.root.quit()
1452 
1453  def to_clip(self, event=None):
1454  self.root.clipboard_clear()
1455  self.root.clipboard_append(self.msg)
1456 
1457 
1458 def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None):
1459  """Create an instance of MessageBox, and get data back from the user.
1460 
1461  :param msg: string to be displayed
1462  :type msg: str
1463  :param b1: left button text, or a tuple (<text for button>, <to return on press>)
1464  :type b1: str, tuple
1465  :param b2: right button text, or a tuple (<text for button>, <to return on press>)
1466  :type b2: str, tuple
1467  :param frame: include a standard outerframe: True or False
1468  :type frame: bool
1469  :param t: time in seconds (int or float) until the msgbox automatically closes
1470  :type t: int, float
1471  :param entry: include an entry widget that will provide its contents returned. Provide text to fill the box
1472  :type entry: None, bool, str
1473  Examples:
1474  mbox('Enter your name', entry=True)
1475  mbox('Enter your name', entry='default')
1476  mbox('Male or female?', ('male', 'm'), ('female', 'f'))
1477  mbox('Process dones')
1478  """
1479  msgbox = MessageBox(msg, b1, b2, frame, t, entry)
1480  msgbox.root.mainloop()
1481  # the function pauses here until the mainloop is quit
1482  msgbox.root.destroy()
1483  return msgbox.returning
def RemoveFileFTP(ftp, filepath)
Definition: robodk.py:1170
def transl(tx, ty=None, tz=None)
Definition: robodk.py:187
def intersect_line_2_plane(pline, vline, pplane, vplane)
Definition: robodk.py:762
def Offset(target_pose, x, y, z, rx=0, ry=0, rz=0)
Definition: robodk.py:223
def DateCreated(filepath, stringformat=False)
Definition: robodk.py:72
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
Definition: robodk.py:1312
def __init__(self, rows=None, ncols=None)
Definition: robodk.py:809
def point_Zaxis_2_pose(point, zaxis, yaxis_hint1=[0, yaxis_hint2=[0)
Definition: robodk.py:234
def LoadMat(strfile, separator=')
Definition: robodk.py:325
def pose_angle_between(pose1, pose2)
Definition: robodk.py:741
def RelTool(self, x, y, z, rx=0, ry=0, rz=0)
Definition: robodk.py:1090
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
Definition: robodk.py:1458
def UploadDirFTP(localpath, server_ip, remote_path, username, password)
Definition: robodk.py:1207
def proj_pt_2_plane(point, planepoint, planeABC)
Definition: robodk.py:769
def dh(rz, tx=None, tz=None, rx=None)
Definition: robodk.py:641
def searchfiles(pattern='C:\\RoboDK\\Library\\ *.rdk')
Definition: robodk.py:43
def DateModified(filepath, stringformat=False)
Definition: robodk.py:64
def dhm(rx, tx=None, tz=None, rz=None)
Definition: robodk.py:657
def Offset(self, x, y, z, rx=0, ry=0, rz=0)
Definition: robodk.py:1095
def __init__(self, msg, b1, b2, frame, t, entry)
Definition: robodk.py:1371
def size(matrix, dim=None)
Definition: robodk.py:263
def __setitem__(self, idx, item)
Definition: robodk.py:875
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
Definition: robodk.py:1354
def LoadList(strfile, separator=')
Definition: robodk.py:313
def RelTool(target_pose, x, y, z, rx=0, ry=0, rz=0)
Definition: robodk.py:215
def proj_pt_2_line(point, paxe, vaxe)
Definition: robodk.py:773
def UploadFileFTP(file_path_name, server_ip, remote_path, username, password)
Definition: robodk.py:1266
def CurrentFile(file=__file__)
Definition: robodk.py:48


ros_robodk_post_processors
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Sun Jun 7 2020 03:50:22