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 #ifndef DUAL_QUATERNION_HPP
00032 #define DUAL_QUATERNION_HPP
00033
00034 #include "math3d.h"
00035
00036 using math3d::point3d;
00037 using math3d::matrix;
00038 using math3d::quaternion;
00039
00040
00041 template<typename T> inline int sign(T v) { return (v<0)?-1:1; }
00042
00043 void set_quaternion_matrix(matrix<double>&M, const quaternion<double>& q, int i=0, int j=0, double w=1.0)
00044 {
00045
00046 M(i,j) = w*q.w; M(i,j+1) =-w*q.i; M(i,j+2) =-w*q.j; M(i,j+3) =-w*q.k;
00047 M(i+1,j)= w*q.i; M(i+1,j+1)= w*q.w; M(i+1,j+2)=-w*q.k; M(i+1,j+3)= w*q.j;
00048 M(i+2,j)= w*q.j; M(i+2,j+1)= w*q.k; M(i+2,j+2)= w*q.w; M(i+2,j+3)=-w*q.i;
00049 M(i+3,j)= w*q.k; M(i+3,j+1)=-w*q.j; M(i+3,j+2)= w*q.i; M(i+3,j+3)= w*q.w;
00050 }
00051
00052 struct dual_quaternion
00053 {
00054 quaternion<double> R, tR_2;
00055
00056 dual_quaternion(double v=1.0) : R(v), tR_2(0) {}
00057
00058 static constexpr double dq_epsilon= 1e-8;
00059
00060 static dual_quaternion rigid_transformation(const quaternion<double>& r, const point3d& t)
00061 {
00062 dual_quaternion result;
00063 result.R = r;
00064 result.tR_2 = (quaternion<double>::convert(t) * r) *= 0.5;
00065 return result;
00066 }
00067 static dual_quaternion convert(const double* p)
00068 {
00069 dual_quaternion result;
00070 result.R = quaternion<double>::convert(p);
00071 result.tR_2 = quaternion<double>::convert(p+4);
00072 return result;
00073 }
00074
00075 dual_quaternion& normalize()
00076 {
00077 double n=norm(R)*sign(R.w);
00078 R*=1.0/n;
00079 tR_2*=1.0/n;
00080 double d=dot(R,tR_2);
00081
00082 quaternion<double> r2=R;
00083 r2 *= -d;
00084 tR_2 += r2;
00085 return *this;
00086 }
00087
00088 point3d get_translation()
00089 {
00090 quaternion<double> t = tR_2 * ~R;
00091 point3d result;
00092 result.x = 2*t.i;
00093 result.y = 2*t.j;
00094 result.z = 2*t.k;
00095 return result;
00096 }
00097
00098 void to_vector(double* p)
00099 { R.to_vector(p); tR_2.to_vector(p+4); }
00100
00101 dual_quaternion& operator += (const dual_quaternion& a)
00102 { R+=a.R; tR_2+=a.tR_2; return *this; }
00103
00104 dual_quaternion& operator *= (double a)
00105 {R*=a; tR_2*=a; return *this;}
00106
00107 dual_quaternion& log()
00108 {
00109 const double h0=std::acos(R.w);
00110 if ( h0*h0 < dq_epsilon )
00111 {
00112 R.w=0.0;
00113 R *= 0.5;
00114 tR_2.w=0.0;
00115 tR_2 *= 0.5;
00116 }
00117 else
00118 {
00119 R.w=0.0;
00120 const double ish0=1.0/norm(R);
00121
00122 math3d::normalize(R);
00123 const double he=-tR_2.w*ish0;
00124 tR_2.w=0.0;
00125
00126 quaternion<double> Rp(R);
00127 Rp *= -dot(R,tR_2)/dot(R,R);
00128 tR_2 += Rp;
00129 tR_2 *= ish0;
00130
00131 tR_2 *= h0;
00132 Rp=R;
00133 Rp*=he;
00134 tR_2 += Rp;
00135 tR_2 *= 0.5;
00136 R *= h0*0.5;
00137 }
00138
00139 return *this;
00140 }
00141
00142 dual_quaternion& exp()
00143 {
00144 const double h0=2.0*norm(R);
00145
00146 if (h0*h0 < dq_epsilon)
00147 {
00148 R *= 2.0;
00149 R.w = 1.0;
00150 tR_2 *= 2.0;
00151
00152 }
00153 else
00154 {
00155 const double he= 4.0*math3d::dot(tR_2,R)/h0;
00156 const double sh0=sin(h0), ch0=cos(h0);
00157 quaternion<double> Rp(R);
00158 Rp *= -dot(R,tR_2)/dot(R,R);
00159 tR_2 += Rp;
00160 tR_2 *=2.0/h0;
00161
00162
00163 tR_2 *= sh0;
00164 Rp=R;
00165 Rp *= he*ch0*2.0/h0;
00166 tR_2 += Rp;
00167 tR_2.w = -he*sh0;
00168
00169 R *= sh0*2.0/h0;
00170 R.w = ch0;
00171 }
00172 normalize();
00173 return *this;
00174 }
00175 };
00176
00177
00178 dual_quaternion operator * (const dual_quaternion&a, const dual_quaternion& b)
00179 {
00180 dual_quaternion result;
00181 result.R=a.R*b.R;
00182 result.tR_2=a.R*b.tR_2 + a.tR_2*b.R;
00183 return result;
00184 }
00185
00186 dual_quaternion operator ~(const dual_quaternion& a)
00187 { dual_quaternion result; result.R = ~a.R; result.tR_2 = ((~a.tR_2)*=-1); return result; }
00188
00189 dual_quaternion operator !(const dual_quaternion& a)
00190 { dual_quaternion result; result.R = ~a.R; result.tR_2 = ~a.tR_2; return result; }
00191
00192 double dot(const dual_quaternion& a, const dual_quaternion& b)
00193 { return dot(a.R,b.R) + dot(a.tR_2,b.tR_2); }
00194
00195 void set_dual_quaternion_matrix(matrix<double>& M, const dual_quaternion& dq, int i=0, int j=0, double w=1.0)
00196 {
00197 set_quaternion_matrix(M,dq.R,i,j,w);
00198 M(i,j+4)=M(i,j+5)=M(i,j+6)=M(i,j+7)=0;
00199 M(i+1,j+4)=M(i+1,j+5)=M(i+1,j+6)=M(i+1,j+7)=0;
00200 M(i+2,j+4)=M(i+2,j+5)=M(i+2,j+6)=M(i+2,j+7)=0;
00201 M(i+3,j+4)=M(i+3,j+5)=M(i+3,j+6)=M(i+3,j+7)=0;
00202 set_quaternion_matrix(M,dq.tR_2,i+4,j,w);set_quaternion_matrix(M,dq.R,i+4,j+4,w);
00203 }
00204
00205 dual_quaternion log(dual_quaternion a) { return a.log(); }
00206 dual_quaternion exp(dual_quaternion a) { return a.exp(); }
00207
00208
00209 std::ostream& operator << (std::ostream& out, const dual_quaternion& dq)
00210 {
00211 return out << "( " << dq.R.w << ", " << dq.R.i << ", " << dq.R.j << ", " << dq.R.k << ", "
00212 << dq.tR_2.w << ", " << dq.tR_2.i << ", " << dq.tR_2.j << ", " << dq.tR_2.k << " )";
00213 }
00214
00215 #endif