44 """List the files in a directory with a given extension""" 46 return glob.glob(pattern)
49 """Returns the current Python file being executed""" 50 return os.path.realpath(file)
53 """Returns the directory of a file path""" 54 return os.path.dirname(filepath)
57 """Returns the file name and extension of a file path""" 58 return os.path.basename(filepath)
61 """Returns the file name (with no extension) of a file path""" 62 return os.path.splitext(os.path.basename(filepath))[0]
65 """Returns the time that a file was modified""" 66 time_in_s = os.path.getmtime(filepath)
68 return time.ctime(time_in_s)
73 """Returns the time that a file was modified""" 74 time_in_s = os.path.getctime(filepath)
76 return time.ctime(time_in_s)
81 """Returns true if the folder exists""" 82 return os.path.isdir(folder)
85 """Returns true if the file exists""" 86 return os.path.exists(file)
96 :param pause: time in seconds 101 """Returns angle of a 2D coordinate in the XY plane""" 102 return math.atan2(y,x)
105 """Returns the square root of a value""" 106 return math.sqrt(value)
109 """Returns the sinus of an angle in radians""" 110 return math.sin(value)
113 """Returns the cosinus of an angle in radians""" 114 return math.cos(value)
117 """Returns the arc sinus in radians""" 118 return math.asin(value)
121 """Returns the arc cosinus in radians""" 122 return math.acos(value)
125 """Returns the number of a numbered object. For example: "Frame 3" returns 3""" 126 words = str_name_id.split()
137 r"""Returns a rotation matrix around the X axis 141 R_x(\theta) = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 142 0 & c_\theta & -s_\theta & 0 \\ 143 0 & s_\theta & c_\theta & 0 \\ 147 :param rx: rotation around X axis in radians 151 return Mat([[1,0,0,0],[0,ct,-st,0],[0,st,ct,0],[0,0,0,1]])
154 r"""Returns a rotation matrix around the Y axis 158 R_y(\theta) = \begin{bmatrix} c_\theta & 0 & s_\theta & 0 \\ 160 -s_\theta & 0 & c_\theta & 0 \\ 164 :param ry: rotation around Y axis in radians 168 return Mat([[ct,0,st,0],[0,1,0,0],[-st,0,ct,0],[0,0,0,1]])
171 r"""Returns a rotation matrix around the Z axis 175 R_x(\theta) = \begin{bmatrix} c_\theta & -s_\theta & 0 & 0 \\ 176 s_\theta & c_\theta & 0 & 0 \\ 181 :param ry: rotation around Y axis in radians 185 return Mat([[ct,-st,0,0],[st,ct,0,0],[0,0,1,0],[0,0,0,1]])
188 r"""Returns a translation matrix 192 T(t_x, t_y, t_z) = \begin{bmatrix} 0 & 0 & 0 & t_x \\ 198 :param tx: translation along the X axis 200 :param ty: translation along the Y axis 202 :param tz: translation along the Z axis 213 return Mat([[1,0,0,xx],[0,1,0,yy],[0,0,1,zz],[0,0,0,1]])
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)
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:
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
235 """Returns a pose given the origin as a point, a Z axis and a preferred orientation for the Y axis""" 240 if angle3(zaxis, yaprox) < 2*pi/180:
243 yaxis =
cross(zaxis, xaxis)
249 r"""Return the identity matrix 253 T(t_x, t_y, t_z) = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 259 :param size: square matrix size (4 by default) 261 return Mat([[1,0,0,0],[0,1,0,0],[0,0,1,0],[0,0,0,1]])
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) 268 :type matrix: :class:`.Mat` 269 :param dim: dimension 272 return matrix.size(dim)
275 """Returns the transpose of the matrix 278 :type matrix: :class:`.Mat`""" 282 """Returns the inverse of a homogeneous matrix 285 :type matrix: :class:`.Mat`""" 289 """Concatenate 2 matrices (vertical concatenation)""" 290 return mat1.catV(mat2)
293 """Concatenate 2 matrices (horizontal concatenation)""" 294 return mat1.catH(mat2)
297 """Start a stopwatch timer""" 299 global TICTOC_START_TIME
300 TICTOC_START_TIME = time.time()
303 """Read the stopwatch timer""" 305 if 'TICTOC_START_TIME' in globals():
306 elapsed = time.time() - TICTOC_START_TIME
310 print(
"Toc: start time not set")
314 """Load data from a CSV file or a TXT file to a list of numbers""" 318 with open(strfile)
as csvfile:
319 csvread = csv.reader(csvfile, delimiter=separator, quotechar=
'|')
321 row_nums = [float(i)
for i
in row]
322 csvdata.append(row_nums)
326 """Load data from a CSV file or a TXT file to a :class:`.Mat` Matrix""" 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() 337 :type H: :class:`.Mat`""" 341 if (H[2,0] > (1.0 - 1e-6)):
344 w = math.atan2(-H[1,2],H[1,1])
345 elif H[2,0] < -1.0 + 1e-6:
348 w = math.atan2(H[1,2],H[1,1])
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]
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
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]])
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
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]])
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). 390 :type H: :class:`.Mat`""" 402 rz1 =
atan2(H[1,0],H[1,1])
403 elif c < (-1.0 + 1e-6):
406 rz1 =
atan2(H[1,0],H[1,1])
417 return [x, y, z, rx1, ry1, rz1]
420 """Converts a pose (4x4 matrix) to a Staubli XYZWPR target 423 :type H: :class:`.Mat`""" 425 xyzwpr[3] = xyzwpr[3]*180.0/pi
426 xyzwpr[4] = xyzwpr[4]*180.0/pi
427 xyzwpr[5] = xyzwpr[5]*180.0/pi
431 """Converts a pose (4x4 matrix) to a Motoman XYZWPR target 434 :type H: :class:`.Mat`""" 439 """Converts a pose (4x4 matrix) to a Fanuc XYZWPR target 442 :type H: :class:`.Mat`""" 447 """Converts a Motoman target to a pose (4x4 matrix)""" 451 """Converts a pose (4x4 matrix) to a Kuka target 454 :type H: :class:`.Mat`""" 458 if (H[2,0]) > (1.0 - 1e-6):
461 w =
atan2(-H[1,2],H[1,1])
462 elif (H[2,0]) < (-1.0 + 1e-6):
465 w =
atan2(H[1,2],H[1,1])
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]
473 """Converts a KUKA XYZABC target to a pose (4x4 matrix)""" 474 [x,y,z,r,p,w] = xyzrpw
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]])
487 """Converts an Adept XYZRPW target to a pose (4x4 matrix)""" 488 [x,y,z,r,p,w] = xyzrpw
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]])
501 """Converts a pose to an Adept target 504 :type H: :class:`.Mat`""" 508 if H[2,2] > (1.0 - 1e-6):
511 w =
atan2(H[1,0],H[0,0])
512 elif H[2,2] < (-1.0 + 1e-6):
515 w =
atan2(H[1,0],H[1,1])
526 return [x, y, z, r*180/pi, p*180/pi, w*180/pi]
529 """Converts a Comau XYZRPW target to a pose (4x4 matrix)""" 533 """Converts a pose to a Comau target 536 :type H: :class:`.Mat`""" 540 """Converts a pose to a Nachi XYZRPW target 543 :type pose: :class:`.Mat`""" 548 """Converts a Nachi XYZRPW target to a pose (4x4 matrix)""" 549 return Fanuc_2_Pose(xyzwpr)
552 """Returns the quaternion orientation vector of a pose (4x4 matrix) 555 :type Ti: :class:`.Mat`""" 562 if (Ti[2,1]-Ti[1,2])<0:
564 if (Ti[0,2]-Ti[2,0])<0:
566 if (Ti[1,0]-Ti[0,1])<0:
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]
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])
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],
590 """Converts a pose to an ABB target 593 :type H: :class:`.Mat`""" 595 return [H[0,3],H[1,3],H[2,3],q[0],q[1],q[2],q[3]]
598 """Displays an ABB RAPID target 601 :type pose: :class:`.Mat`""" 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]))
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)
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]]
617 rxyz =
mult3(rxyz, angle)
618 return [pose[0,3], pose[1,3], pose[2,3], rxyz[0], rxyz[1], rxyz[2]]
621 """Calculate the pose target given a p[x,y,z,rx,ry,rz] cartesian target""" 625 cosang =
cos(0.5*angle)
630 ratio =
sin(0.5*angle)/angle
631 q234 =
mult3(wpr, ratio)
633 q1234 = [cosang, q234[0], q234[1], q234[2]]
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]) 646 if tx
is None: [rz,tx,tz,rx] = rz
652 return Mat( [[crz, -srz*crx, srz*srx, tx*crz],
653 [srz, crz*crx, -crz*srx, tx*srz],
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]) 662 if tx
is None: [rx,tx,tz,rz] = rx
668 return Mat([[crz, -srz, 0, tx],
669 [crx*srz, crx*crz, -srx, -tz*srx],
670 [srx*srz, crz*srx, crx, tz*crx],
674 """Converts the robot joints into angles between links depending on the type of the robot.""" 677 jout[2] = -jin[1] - jin[2]
687 jout[2] = +jin[1] + jin[2]
691 """Converts the angles between links into the robot joint space depending on the type of the robot.""" 694 jout[2] = -jin[1] - jin[2]
709 """Returns the norm of a 3D vector""" 710 return sqrt(p[0]*p[0] + p[1]*p[1] + p[2]*p[2])
713 """Returns the unitary vector""" 714 norminv = 1.0/
norm(a)
715 return [a[0]*norminv,a[1]*norminv,a[2]*norminv]
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]]
725 """Returns the dot product of two 3D vectors""" 726 return a[0]*b[0] + a[1]*b[1] + a[2]*b[2]
729 """Returns the angle in radians of two 3D vectors""" 733 """Returns the angle in radians of a 4x4 matrix 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)
742 """Returns the angle in radians between two poses (4x4 matrix pose)""" 746 """Multiplies a 3D vector to a scalar""" 747 return [v[0]*d, v[1]*d, v[2]*d]
750 """Subtracts two 3D vectors c=a-b""" 751 return [a[0]-b[0],a[1]-b[1],a[2]-b[2]]
754 """Adds two 3D vectors c=a+b""" 755 return [a[0]+b[0],a[1]+b[1],a[2]+b[2]]
758 """Calculates the distance between two points""" 763 """Calculates the intersection betweeen a line and a plane""" 764 D = -
dot(vplane,pplane)
765 k = -(D+
dot(vplane,pline))/
dot(vplane,vline)
770 """Projects a point to a plane""" 774 """Projects a point to a line""" 775 vpaxe2point =
subs3(point,paxe)
776 dist =
dot(vaxe,vpaxe2point)/
dot(vaxe,vaxe)
780 """Best fits a plane to a cloud of points""" 782 XYZ = np.array(points)
783 [rows,cols] = XYZ.shape
787 p = (np.ones((rows,1)))
788 AB = np.hstack([XYZ,p])
789 [u, d, v] = np.linalg.svd(AB,0)
791 nn = np.linalg.norm(B[0:3])
793 pplane = [0,0,-(B[3]/B[2])]
794 vplane = B[0:3].tolist()
795 return pplane, vplane
802 """ An exception class for Matrix """ 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.""" 814 self.
rows = [[0]*n
for x
in range(m)]
816 if isinstance(rows,Mat):
817 rows = rows.copy().rows
820 if not isinstance(rows[0],list):
824 if any([len(row) != n
for row
in rows[1:]]):
825 raise Exception(MatrixError,
"inconsistent row length")
828 self.
rows = [list(item)
for item
in zip(*self.
rows)]
832 self.
rows = [[0]*n
for x
in range(m)]
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]
842 if isinstance(idx,int):
844 elif isinstance(idx,slice):
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)
856 rg1 = range(idx1,idx1+1)
857 if isinstance(idx2,slice):
858 indices2 = idx2.indices(matsize[1])
859 rg2 = range(*indices2)
861 rg2 = range(idx2,idx2+1)
866 newmat =
Mat(len(newm),len(newn))
871 newmat.rows[cm][cn] = self.
rows[i][j]
876 if isinstance(item,float)
or isinstance(item,int):
878 elif isinstance(item, list):
881 matsize = self.
size();
882 if isinstance(idx,int):
887 elif isinstance(idx,slice):
896 if isinstance(idx1,slice):
897 indices1 = idx1.indices(matsize[0])
898 rg1 = range(*indices1)
900 rg1 = range(idx1,idx1+1)
901 if isinstance(idx2,slice):
902 indices2 = idx2.indices(matsize[1])
903 rg2 = range(*indices2)
905 rg2 = range(idx2,idx2+1)
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)
918 self.
rows[i][j] = item.rows[cm][cn]
924 s=
'\n [ '.join([(
', '.join([
'%.3f'%item
for item
in row])+
' ],')
for row
in self.
rows])
925 return '[[ ' + s[:-1] +
']\n' 929 rank = str(self.
size())
930 rep=
"Matrix: %s\n%s" % (rank,s)
934 """Returns the transpose of the matrix""" 935 mat =
Mat([list(item)
for item
in zip(*self.
rows)])
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)""" 942 n = len(self.
rows[0])
950 raise Exception(MatrixError,
"Invalid dimension!")
953 """Concatenate with another matrix (vertical concatenation)""" 954 if not isinstance(mat2, Mat):
955 raise Exception(MatrixError,
"Concatenation must be performed with 2 matrices")
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
966 """Concatenate with another matrix (horizontal concatenation)""" 967 if not isinstance(mat2, Mat):
968 raise Exception(MatrixError,
"Concatenation must be performed with 2 matrices")
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
979 return (mat.rows == self.
rows)
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):
990 result.rows[x][y] = self.
rows[x][y] + mat
997 raise Exception(MatrixError,
"Trying to add matrixes of varying size!")
999 row = [sum(item)
for item
in zip(self.
rows[x], mat.rows[x])]
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):
1012 result.rows[x][y] = self.
rows[x][y] - mat
1018 if sz != mat.size():
1019 raise Exception(MatrixError,
"Trying to add matrixes of varying size!")
1021 row = [item[0]-item[1]
for item
in zip(self.
rows[x], mat.rows[x])]
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):
1034 mulmat.rows[x][y] = self.
rows[x][y]*mat
1036 if isinstance(mat,list):
1041 vectok =
catV(matvect,
Mat([[1]]))
1042 result = self*vectok
1043 return (result[:-1,:]).
tr().rows[0]
1045 result = self*
Mat(matvect)
1046 return result.tr().rows[0]
1048 raise Exception(MatrixError,
"Invalid product")
1050 matm, matn = mat.size()
1053 raise Exception(MatrixError,
"Matrices cannot be multipled!")
1055 mulmat =
Mat(m, matn)
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])])
1062 """Make identity matrix of size (mxm)""" 1063 rows = [[0]*m
for x
in range(m)]
1071 """returns 1 if it is a Homogeneous matrix""" 1073 if m != 4
or n != 4:
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
1085 zero = zero + abs(test[x,y])
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)
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)
1101 """Calculates the inverse of a homogeneous matrix""" 1103 raise Exception(MatrixError,
"Pose matrix is not homogeneous. invH() can only compute the inverse of a homogeneous matrix")
1105 Hout[3,0:3] =
Mat([[0,0,0]]);
1106 Hout[0:3,3] = (Hout[0:3,0:3]*self[0:3,3])*(-1)
1110 """Returns the first column vector of the matrix as a list""" 1111 return tr(self).rows[0]
1114 """Returns the position of a pose (assumes that a 4x4 homogeneous matrix is being used)""" 1115 return self[0:3,3].
tolist()
1118 """Returns the X vector of a pose (assumes that a 4x4 homogeneous matrix is being used)""" 1119 return self[0:3,0].
tolist()
1122 """Returns the Y vector of a pose (assumes that a 4x4 homogeneous matrix is being used)""" 1123 return self[0:3,1].
tolist()
1126 """Returns the Z vector of a pose (assumes that a 4x4 homogeneous matrix is being used)""" 1127 return self[0:3,2].
tolist()
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]
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)""" 1138 self[0,0] = v_xyz[0]
1139 self[1,0] = v_xyz[1]
1140 self[2,0] = v_xyz[2]
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)""" 1145 self[0,1] = v_xyz[0]
1146 self[1,1] = v_xyz[1]
1147 self[2,1] = v_xyz[2]
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)""" 1152 self[0,2] = v_xyz[0]
1153 self[1,2] = v_xyz[1]
1154 self[2,2] = v_xyz[2]
1157 """Save :class:`.Mat` Matrix to a CSV or TXT file""" 1161 file = open(strfile,
'w')
1164 file.write(
'%.6f ' % self.
rows[i][j])
1171 """Delete a file on a remote server.""" 1174 ftp.delete(filepath)
1175 except ftplib.all_errors
as e:
1177 print(
'POPUP: Could not remove file {0}: {1}'.format(filepath, e))
1181 """Recursively delete a directory tree on a remote server.""" 1185 names = ftp.nlst(path)
1186 except ftplib.all_errors
as e:
1188 print(
'RemoveDirFTP: Could not remove folder {0}: {1}'.format(path, e))
1192 if os.path.split(name)[1]
in (
'.',
'..'):
continue 1193 print(
'RemoveDirFTP: Checking {0}'.format(name))
1195 ftp.cwd(path+
'/'+name)
1198 except ftplib.all_errors:
1199 ftp.delete(path+
'/'+name)
1204 except ftplib.all_errors
as e:
1205 print(
'RemoveDirFTP: Could not remove {0}: {1}'.format(path, e))
1208 """Upload a folder to a robot through FTP recursively""" 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))
1216 myFTP = ftplib.FTP(server_ip, username, password)
1217 print(
'Connection established')
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))
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)
1230 print(
"POPUP: Connected. Uploading program to %s..." % server_ip)
1233 myFTP.cwd(remote_path)
1234 myFTP.mkd(main_folder)
1235 myFTP.cwd(remote_path_prog)
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))
1244 def uploadThis(path):
1245 files = os.listdir(path)
1248 if os.path.isfile(path +
r'\{}'.format(f)):
1249 print(
' Sending file: %s' % f)
1250 print(
"POPUP: Sending file: %s" % f)
1253 myFTP.storbinary(
'STOR %s' % f, fh)
1255 elif os.path.isdir(path +
r'\{}'.format(f)):
1256 print(
' Sending folder: %s' % f)
1259 uploadThis(path +
r'\{}'.format(f))
1267 """Upload a file to a robot through FTP""" 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))
1276 myFTP = ftplib.FTP(server_ip, username, password)
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))
1284 remote_path_prog = remote_path +
'/' + filename
1285 print(
"POPUP: Connected. Deleting remote file %s..." % remote_path_prog)
1288 print(
"POPUP: Connected. Uploading program to %s..." % server_ip)
1291 myFTP.cwd(remote_path)
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))
1300 def uploadThis(localfile, filename):
1301 print(
' Sending file: %s' % localfile)
1302 print(
"POPUP: Sending file: %s" % filename)
1304 fh = open(localfile,
'rb')
1305 myFTP.storbinary(
'STOR %s' % filename, fh)
1308 uploadThis(file_path_name, filename)
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""" 1315 if isinstance(program, list):
1316 if len(program) == 0:
1317 print(
'POPUP: Nothing to transfer')
1319 for prog
in program:
1320 UploadFTP(prog, robot_ip, remote_path, ftp_user, ftp_pass)
1324 if os.path.isfile(program):
1325 print(
'Sending program file %s...' % program)
1326 UploadFileFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
1328 print(
'Sending program folder %s...' % program)
1329 UploadDirFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
1340 import Tkinter
as tkinter
1341 import tkFileDialog
as filedialog
1344 from tkinter
import filedialog
1347 """Pop up a file dialog window to select a file to open.""" 1350 file_path = filedialog.askopenfilename()
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.""" 1357 options[
'initialdir'] = strdir
1358 options[
'title'] = strtitle
1361 options[
'initialfile'] = strfile
1365 file_path = filedialog.asksaveasfile(**options)
1374 root.title(
'Message')
1377 root.bind(
'<Control-c>', func=self.
to_clip)
1379 if not frame: root.overrideredirect(
True)
1384 if isinstance(b1, tuple): b1, self.
b1_return = b1
1385 if isinstance(b2, tuple): b2, self.
b2_return = b2
1387 frm_1 = tkinter.Frame(root)
1388 frm_1.pack(ipadx=2, ipady=2)
1390 message = tkinter.Label(frm_1, text=self.
msg)
1391 message.pack(padx=8, pady=8)
1393 if entry
is not None:
1398 self.
entry.insert(0, entry)
1399 self.
entry.focus_set()
1401 frm_2 = tkinter.Frame(frm_1)
1402 frm_2.pack(padx=4, pady=4)
1404 btn_1 = tkinter.Button(frm_2, width=8, text=b1)
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)
1410 btn_2.pack(side=
'left')
1412 btn_1.bind(
'<KeyPress-Return>', func=self.
b1_action)
1413 btn_2.bind(
'<KeyPress-Return>', func=self.
b2_action)
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))
1422 root.protocol(
"WM_DELETE_WINDOW", self.
close_mod)
1426 if t: root.after(int(t*1000), func=self.
time_out)
1429 try: x = self.
entry.get()
1430 except AttributeError:
1448 try: x = self.entry.get()
1449 except AttributeError: self.returning =
None 1450 else: self.returning = x
1451 finally: self.root.quit()
1454 self.
root.clipboard_clear()
1455 self.
root.clipboard_append(self.
msg)
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. 1461 :param msg: string to be displayed 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 1469 :param t: time in seconds (int or float) until the msgbox automatically closes 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 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') 1479 msgbox =
MessageBox(msg, b1, b2, frame, t, entry)
1480 msgbox.root.mainloop()
1482 msgbox.root.destroy()
1483 return msgbox.returning
def RemoveFileFTP(ftp, filepath)
def SaveMat(self, strfile)
def b1_action(self, event=None)
def joints_2_angles(jin, type)
def transl(tx, ty=None, tz=None)
def intersect_line_2_plane(pline, vline, pplane, vplane)
def b2_action(self, event=None)
def Offset(target_pose, x, y, z, rx=0, ry=0, rz=0)
def name_2_id(str_name_id)
def getFileName(filepath)
def DateCreated(filepath, stringformat=False)
def xyzrpw_2_pose(xyzrpw)
def UploadFTP(program, robot_ip, remote_path, ftp_user, ftp_pass)
def pose_2_quaternion(Ti)
def TxyzRxyz_2_Pose(xyzrpw)
def Motoman_2_Pose(xyzwpr)
def to_clip(self, event=None)
def __init__(self, rows=None, ncols=None)
def point_Zaxis_2_pose(point, zaxis, yaxis_hint1=[0, yaxis_hint2=[0)
def LoadMat(strfile, separator=')
def pose_angle_between(pose1, pose2)
def RelTool(self, x, y, z, rx=0, ry=0, rz=0)
def mbox(msg, b1='OK', b2='Cancel', frame=True, t=False, entry=None)
def UploadDirFTP(localpath, server_ip, remote_path, username, password)
def getBaseName(filepath)
def proj_pt_2_plane(point, planepoint, planeABC)
def dh(rz, tx=None, tz=None, rx=None)
def searchfiles(pattern='C:\\RoboDK\\Library\\ *.rdk')
def angles_2_joints(jin, type)
def DateModified(filepath, stringformat=False)
def quaternion_2_pose(qin)
def dhm(rx, tx=None, tz=None, rz=None)
def Offset(self, x, y, z, rx=0, ry=0, rz=0)
def __init__(self, msg, b1, b2, frame, t, entry)
def size(matrix, dim=None)
def __setitem__(self, idx, item)
def getSaveFile(strdir='C:\\', strfile='file.txt', strtitle='Save file as ...')
def LoadList(strfile, separator=')
def RelTool(target_pose, x, y, z, rx=0, ry=0, rz=0)
def proj_pt_2_line(point, paxe, vaxe)
def __getitem__(self, idx)
def UploadFileFTP(file_path_name, server_ip, remote_path, username, password)
def RemoveDirFTP(ftp, path)
def CurrentFile(file=__file__)