34 from numpy
import matrix, vsplit, sin, cos, reshape, zeros, pi
43 param_names = [
'x',
'y',
'z',
'a',
'b',
'c']
46 def __init__(self, config = [0, 0, 0, 0, 0, 0], name=""):
48 eval_config = [eval(str(x))
for x
in config]
49 self.
_config = reshape(matrix(eval_config, float), (-1,1))
51 rospy.logdebug(
"Initializing single transform %s with params [%s]", name,
", ".join([
"% 2.4f" % x
for x
in eval_config]))
55 return [x == 1
for x
in free_config]
58 return param_vec.T.tolist()[0]
65 T = matrix( zeros((4,4,), float))
72 U,S,Vt = numpy.linalg.svd(p[3:6,0])
74 rot_angle = S[0]*Vt[0,0]
79 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],
80 [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],
81 [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] ] )
93 return len(param_names)
98 angle = math.sqrt(sum([vec[i]**2
for i
in range(3)]))
99 hsa = math.sin(angle/2.)
102 quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)]
109 return [0.0, 0.0, 0.0]
111 angle = math.acos(quat[3])*2.0
112 hsa = math.sin(angle/2.)
113 axis = [quat[0]/hsa*angle, quat[1]/hsa*angle, quat[2]/hsa*angle]
117 return PyKDL.Rotation.RPY(rpy[0], rpy[1], rpy[2]).GetQuaternion()
120 return PyKDL.Rotation.Quaternion(q[0], q[1], q[2], q[3]).GetRPY()
123 def epsEq(value1, value2, eps = 1e-10):
124 if math.fabs(value1-value2) <= eps: