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