00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 import numpy
00034 from numpy import matrix, vsplit, sin, cos, reshape, zeros, pi
00035 import rospy
00036 
00037 import tf.transformations as transformations
00038 import yaml, math
00039 
00040 
00041 
00042 
00043 param_names = ['x','y','z','a','b','c']
00044 
00045 class SingleTransform:
00046     def __init__(self, config = [0, 0, 0, 0, 0, 0], name=""):
00047         self._name = name
00048         eval_config = [eval(str(x)) for x in config]
00049         self._config = reshape(matrix(eval_config, float), (-1,1))
00050 
00051         rospy.logdebug("Initializing single transform %s with params [%s]", name, ", ".join(["% 2.4f" % x for x in eval_config]))
00052         self.inflate(self._config)
00053 
00054     def calc_free(self, free_config):
00055         return [x == 1 for x in free_config]
00056 
00057     def params_to_config(self, param_vec):
00058         return param_vec.T.tolist()[0]
00059 
00060     
00061     def inflate(self, p):
00062         self._config = p.copy()  
00063 
00064         
00065         T = matrix( zeros((4,4,), float))
00066         T[3,3] = 1.0
00067         
00068         
00069         T[0:3,3] = p[0:3,0]
00070         
00071         
00072         U,S,Vt = numpy.linalg.svd(p[3:6,0])
00073         a = U[:,0]
00074         rot_angle = S[0]*Vt[0,0]
00075         
00076         
00077         c = cos(rot_angle)
00078         s = sin(rot_angle)
00079         R = matrix( [ [   a[0,0]**2+(1-a[0,0]**2)*c, a[0,0]*a[1,0]*(1-c)-a[2,0]*s, a[0,0]*a[2,0]*(1-c)+a[1,0]*s],
00080                       [a[0,0]*a[1,0]*(1-c)+a[2,0]*s,    a[1,0]**2+(1-a[1,0]**2)*c, a[1,0]*a[2,0]*(1-c)-a[0,0]*s],
00081                       [a[0,0]*a[2,0]*(1-c)-a[1,0]*s, a[1,0]*a[2,0]*(1-c)+a[0,0]*s,    a[2,0]**2+(1-a[2,0]**2)*c] ] )
00082 
00083         T[0:3,0:3] = R
00084         self.transform = T
00085 
00086     
00087     def deflate(self):
00088         
00089         return self._config
00090 
00091     
00092     def get_length(self):
00093         return len(param_names)
00094 
00095 
00096 
00097 def angle_axis_to_RPY(vec):
00098     angle = math.sqrt(sum([vec[i]**2 for i in range(3)]))
00099     hsa = math.sin(angle/2.)
00100     if epsEq(angle, 0):
00101         return (0.,0.,0.)
00102     quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)]
00103     rpy = quat_to_rpy(quat)
00104     return rpy
00105 
00106 
00107 def RPY_to_angle_axis(vec):
00108     if epsEq(vec[0], 0) and epsEq(vec[1], 0) and epsEq(vec[2], 0):
00109         return [0.0, 0.0, 0.0]
00110     quat = rpy_to_quat(vec)
00111     angle = math.acos(quat[3])*2.0
00112     hsa = math.sin(angle/2.)
00113     axis = [quat[0]/hsa*angle, quat[1]/hsa*angle, quat[2]/hsa*angle]
00114     return axis
00115     
00116 def rpy_to_quat(rpy):
00117     return transformations.quaternion_from_euler(rpy[0], rpy[1], rpy[2], 'sxyz')
00118 
00119 def quat_to_rpy(q):
00120     rpy = transformations.euler_from_quaternion(q, 'sxyz')
00121     return rpy
00122 
00123 
00124 def epsEq(value1, value2, eps = 1e-10):
00125     if math.fabs(value1-value2) <= eps:
00126         return 1
00127     return 0
00128