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 
00034 
00037 #ifndef FCL_MATRIX_3F_H
00038 #define FCL_MATRIX_3F_H
00039 
00040 #include "fcl/math/vec_3f.h"
00041 
00042 namespace fcl
00043 {
00044 
00046 template<typename T>
00047 class Matrix3fX
00048 {
00049 public:
00050   typedef typename T::meta_type U;
00051   typedef typename T::vector_type S;
00052   T data;
00053   
00054   Matrix3fX() {}
00055   Matrix3fX(U xx, U xy, U xz,
00056             U yx, U yy, U yz,
00057             U zx, U zy, U zz) : data(xx, xy, xz, yx, yy, yz, zx, zy, zz)
00058   {}
00059 
00060   Matrix3fX(const Vec3fX<S>& v1, const Vec3fX<S>& v2, const Vec3fX<S>& v3)
00061     : data(v1.data, v2.data, v3.data) {}
00062   
00063   Matrix3fX(const Matrix3fX<T>& other) : data(other.data) {}
00064 
00065   Matrix3fX(const T& data_) : data(data_) {}
00066   
00067   inline Vec3fX<S> getColumn(size_t i) const
00068   {
00069     return Vec3fX<S>(data.getColumn(i));
00070   }
00071 
00072   inline Vec3fX<S> getRow(size_t i) const
00073   {
00074     return Vec3fX<S>(data.getRow(i));
00075   }
00076 
00077   inline U operator () (size_t i, size_t j) const
00078   {
00079     return data(i, j);
00080   }
00081 
00082   inline U& operator () (size_t i, size_t j)
00083   {
00084     return data(i, j);
00085   }
00086 
00087   inline Vec3fX<S> operator * (const Vec3fX<S>& v) const
00088   {
00089     return Vec3fX<S>(data * v.data);
00090   }
00091 
00092   inline Matrix3fX<T> operator * (const Matrix3fX<T>& m) const
00093   {
00094     return Matrix3fX<T>(data * m.data);
00095   }
00096 
00097   inline Matrix3fX<T> operator + (const Matrix3fX<T>& other) const
00098   {
00099     return Matrix3fX<T>(data + other.data);
00100   }
00101 
00102   inline Matrix3fX<T> operator - (const Matrix3fX<T>& other) const
00103   {
00104     return Matrix3fX<T>(data - other.data);
00105   }
00106 
00107   inline Matrix3fX<T> operator + (U c) const
00108   {
00109     return Matrix3fX<T>(data + c);
00110   }
00111 
00112   inline Matrix3fX<T> operator - (U c) const
00113   {
00114     return Matrix3fX<T>(data - c);
00115   }
00116 
00117   inline Matrix3fX<T> operator * (U c) const
00118   {
00119     return Matrix3fX<T>(data * c);
00120   }
00121 
00122   inline Matrix3fX<T> operator / (U c) const
00123   {
00124     return Matrix3fX<T>(data / c);
00125   }
00126 
00127   inline Matrix3fX<T>& operator *= (const Matrix3fX<T>& other)
00128   {
00129     data *= other.data;
00130     return *this;
00131   }
00132 
00133   inline Matrix3fX<T>& operator += (const Matrix3fX<T>& other)
00134   {
00135     data += other.data;
00136     return *this;
00137   }
00138 
00139   inline Matrix3fX<T>& operator -= (const Matrix3fX<T>& other)
00140   {
00141     data -= other.data;
00142     return *this;
00143   }
00144 
00145   inline Matrix3fX<T>& operator += (U c) 
00146   {
00147     data += c;
00148     return *this;
00149   }
00150 
00151   inline Matrix3fX<T>& operator -= (U c)
00152   {
00153     data -= c;
00154     return *this;
00155   }
00156 
00157   inline Matrix3fX<T>& operator *= (U c)
00158   {
00159     data *= c;
00160     return *this;
00161   }
00162 
00163   inline Matrix3fX<T>& operator /= (U c)
00164   {
00165     data /= c;
00166     return *this;
00167   }
00168 
00169   inline void setIdentity()
00170   {
00171     data.setIdentity();
00172   }
00173 
00174   inline void setZero()
00175   {
00176     data.setZero();
00177   }
00178 
00187   inline void setEulerZYX(FCL_REAL eulerX, FCL_REAL eulerY, FCL_REAL eulerZ)
00188   {
00189     FCL_REAL ci(cos(eulerX));
00190     FCL_REAL cj(cos(eulerY));
00191     FCL_REAL ch(cos(eulerZ));
00192     FCL_REAL si(sin(eulerX));
00193     FCL_REAL sj(sin(eulerY));
00194     FCL_REAL sh(sin(eulerZ));
00195     FCL_REAL cc = ci * ch;
00196     FCL_REAL cs = ci * sh;
00197     FCL_REAL sc = si * ch;
00198     FCL_REAL ss = si * sh;
00199 
00200     setValue(cj * ch, sj * sc - cs, sj * cc + ss,
00201              cj * sh, sj * ss + cc, sj * cs - sc, 
00202              -sj,     cj * si,      cj * ci);
00203 
00204   }
00205 
00210   void setEulerYPR(FCL_REAL yaw, FCL_REAL pitch, FCL_REAL roll)
00211   {
00212     setEulerZYX(roll, pitch, yaw);
00213   }
00214 
00215   inline U determinant() const
00216   {
00217     return data.determinant();
00218   }
00219 
00220   Matrix3fX<T>& transpose() 
00221   {
00222     data.transpose();
00223     return *this;
00224   }
00225 
00226   Matrix3fX<T>& inverse()
00227   {
00228     data.inverse();
00229     return *this;
00230   }
00231 
00232   Matrix3fX<T>& abs()
00233   {
00234     data.abs();
00235     return *this;
00236   }
00237 
00238   static const Matrix3fX<T>& getIdentity()
00239   {
00240     static const Matrix3fX<T> I((U)1, (U)0, (U)0,
00241                                 (U)0, (U)1, (U)0,
00242                                 (U)0, (U)0, (U)1);
00243     return I;
00244   }
00245 
00246   Matrix3fX<T> transposeTimes(const Matrix3fX<T>& other) const
00247   {
00248     return Matrix3fX<T>(data.transposeTimes(other.data));
00249   }
00250 
00251   Matrix3fX<T> timesTranspose(const Matrix3fX<T>& other) const
00252   {
00253     return Matrix3fX<T>(data.timesTranspose(other.data));
00254   }
00255 
00256   Vec3fX<S> transposeTimes(const Vec3fX<S>& v) const
00257   {
00258     return Vec3fX<S>(data.transposeTimes(v.data));
00259   }
00260 
00261   Matrix3fX<T> tensorTransform(const Matrix3fX<T>& m) const
00262   {
00263     Matrix3fX<T> res(*this);
00264     res *= m;
00265     return res.timesTranspose(*this);
00266   }
00267 
00268   inline U transposeDotX(const Vec3fX<S>& v) const
00269   {
00270     return data.transposeDot(0, v.data);
00271   }
00272 
00273   inline U transposeDotY(const Vec3fX<S>& v) const
00274   {
00275     return data.transposeDot(1, v.data);
00276   }
00277 
00278   inline U transposeDotZ(const Vec3fX<S>& v) const
00279   {
00280     return data.transposeDot(2, v.data);
00281   }
00282 
00283   inline U transposeDot(size_t i, const Vec3fX<S>& v) const
00284   {
00285     return data.transposeDot(i, v.data);
00286   }
00287 
00288   inline U dotX(const Vec3fX<S>& v) const
00289   {
00290     return data.dot(0, v.data);
00291   }
00292 
00293   inline U dotY(const Vec3fX<S>& v) const
00294   {
00295     return data.dot(1, v.data);
00296   }
00297 
00298   inline U dotZ(const Vec3fX<S>& v) const
00299   {
00300     return data.dot(2, v.data);
00301   }
00302 
00303   inline U dot(size_t i, const Vec3fX<S>& v) const
00304   {
00305     return data.dot(i, v.data);
00306   }
00307 
00308   inline void setValue(U xx, U xy, U xz,
00309                        U yx, U yy, U yz,
00310                        U zx, U zy, U zz)
00311   {
00312     data.setValue(xx, xy, xz, 
00313                   yx, yy, yz,
00314                   zx, zy, zz);
00315   }
00316 
00317   inline void setValue(U x)
00318   {
00319     data.setValue(x);
00320   }
00321 };
00322 
00323 template<typename T>
00324 void relativeTransform(const Matrix3fX<T>& R1, const Vec3fX<typename T::vector_type>& t1,
00325                        const Matrix3fX<T>& R2, const Vec3fX<typename T::vector_type>& t2,
00326                        Matrix3fX<T>& R, Vec3fX<typename T::vector_type>& t)
00327 {
00328   R = R1.transposeTimes(R2);
00329   t = R1.transposeTimes(t2 - t1);
00330 }
00331 
00333 template<typename T>
00334 void eigen(const Matrix3fX<T>& m, typename T::meta_type dout[3], Vec3fX<typename T::vector_type> vout[3])
00335 {
00336   Matrix3fX<T> R(m);
00337   int n = 3;
00338   int j, iq, ip, i;
00339   typename T::meta_type tresh, theta, tau, t, sm, s, h, g, c;
00340   int nrot;
00341   typename T::meta_type b[3];
00342   typename T::meta_type z[3];
00343   typename T::meta_type v[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}};
00344   typename T::meta_type d[3];
00345 
00346   for(ip = 0; ip < n; ++ip)
00347   {
00348     b[ip] = d[ip] = R(ip, ip);
00349     z[ip] = 0;
00350   }
00351 
00352   nrot = 0;
00353 
00354   for(i = 0; i < 50; ++i)
00355   {
00356     sm = 0;
00357     for(ip = 0; ip < n; ++ip)
00358       for(iq = ip + 1; iq < n; ++iq)
00359         sm += std::abs(R(ip, iq));
00360     if(sm == 0.0)
00361     {
00362       vout[0].setValue(v[0][0], v[0][1], v[0][2]);
00363       vout[1].setValue(v[1][0], v[1][1], v[1][2]);
00364       vout[2].setValue(v[2][0], v[2][1], v[2][2]);
00365       dout[0] = d[0]; dout[1] = d[1]; dout[2] = d[2];
00366       return;
00367     }
00368 
00369     if(i < 3) tresh = 0.2 * sm / (n * n);
00370     else tresh = 0.0;
00371 
00372     for(ip = 0; ip < n; ++ip)
00373     {
00374       for(iq= ip + 1; iq < n; ++iq)
00375       {
00376         g = 100.0 * std::abs(R(ip, iq));
00377         if(i > 3 &&
00378            std::abs(d[ip]) + g == std::abs(d[ip]) &&
00379            std::abs(d[iq]) + g == std::abs(d[iq]))
00380           R(ip, iq) = 0.0;
00381         else if(std::abs(R(ip, iq)) > tresh)
00382         {
00383           h = d[iq] - d[ip];
00384           if(std::abs(h) + g == std::abs(h)) t = (R(ip, iq)) / h;
00385           else
00386           {
00387             theta = 0.5 * h / (R(ip, iq));
00388             t = 1.0 /(std::abs(theta) + std::sqrt(1.0 + theta * theta));
00389             if(theta < 0.0) t = -t;
00390           }
00391           c = 1.0 / std::sqrt(1 + t * t);
00392           s = t * c;
00393           tau = s / (1.0 + c);
00394           h = t * R(ip, iq);
00395           z[ip] -= h;
00396           z[iq] += h;
00397           d[ip] -= h;
00398           d[iq] += h;
00399           R(ip, iq) = 0.0;
00400           for(j = 0; j < ip; ++j) { g = R(j, ip); h = R(j, iq); R(j, ip) = g - s * (h + g * tau); R(j, iq) = h + s * (g - h * tau); }
00401           for(j = ip + 1; j < iq; ++j) { g = R(ip, j); h = R(j, iq); R(ip, j) = g - s * (h + g * tau); R(j, iq) = h + s * (g - h * tau); }
00402           for(j = iq + 1; j < n; ++j) { g = R(ip, j); h = R(iq, j); R(ip, j) = g - s * (h + g * tau); R(iq, j) = h + s * (g - h * tau); }
00403           for(j = 0; j < n; ++j) { g = v[j][ip]; h = v[j][iq]; v[j][ip] = g - s * (h + g * tau); v[j][iq] = h + s * (g - h * tau); }
00404           nrot++;
00405         }
00406       }
00407     }
00408     for(ip = 0; ip < n; ++ip)
00409     {
00410       b[ip] += z[ip];
00411       d[ip] = b[ip];
00412       z[ip] = 0.0;
00413     }
00414   }
00415 
00416   std::cerr << "eigen: too many iterations in Jacobi transform." << std::endl;
00417 
00418   return;
00419 }
00420 
00421 template<typename T>
00422 Matrix3fX<T> abs(const Matrix3fX<T>& R) 
00423 {
00424   return Matrix3fX<T>(abs(R.data));
00425 }
00426 
00427 template<typename T>
00428 Matrix3fX<T> transpose(const Matrix3fX<T>& R)
00429 {
00430   return Matrix3fX<T>(transpose(R.data));
00431 }
00432 
00433 template<typename T>
00434 Matrix3fX<T> inverse(const Matrix3fX<T>& R)
00435 {
00436   return Matrix3fX<T>(inverse(R.data));
00437 }
00438 
00439 template<typename T>
00440 typename T::meta_type quadraticForm(const Matrix3fX<T>& R, const Vec3fX<typename T::vector_type>& v)
00441 {
00442   return v.dot(R * v);
00443 }
00444 
00445 
00446 #if FCL_HAVE_SSE
00447 typedef Matrix3fX<details::sse_meta_f12> Matrix3f;
00448 #else
00449 typedef Matrix3fX<details::Matrix3Data<FCL_REAL> > Matrix3f;
00450 #endif
00451 
00452 static inline std::ostream& operator << (std::ostream& o, const Matrix3f& m)
00453 {
00454   o << "[(" << m(0, 0) << " " << m(0, 1) << " " << m(0, 2) << ")("
00455     << m(1, 0) << " " << m(1, 1) << " " << m(1, 2) << ")(" 
00456     << m(2, 0) << " " << m(2, 1) << " " << m(2, 2) << ")]";
00457   return o;
00458 }
00459 
00460 
00461 
00463 class Variance3f
00464 {
00465 public:
00467   Matrix3f Sigma;
00468 
00470   Matrix3f::U sigma[3];
00471 
00473   Vec3f axis[3];
00474 
00475   Variance3f() {}
00476 
00477   Variance3f(const Matrix3f& S) : Sigma(S)
00478   {
00479     init();
00480   }
00481 
00483   void init() 
00484   {
00485     eigen(Sigma, sigma, axis);
00486   }
00487 
00489   Variance3f& sqrt()
00490   {
00491     for(std::size_t i = 0; i < 3; ++i)
00492     {
00493       if(sigma[i] < 0) sigma[i] = 0;
00494       sigma[i] = std::sqrt(sigma[i]);
00495     }
00496 
00497 
00498     Sigma.setZero();
00499     for(std::size_t i = 0; i < 3; ++i)
00500     {
00501       for(std::size_t j = 0; j < 3; ++j)
00502       {
00503         Sigma(i, j) += sigma[0] * axis[0][i] * axis[0][j];
00504         Sigma(i, j) += sigma[1] * axis[1][i] * axis[1][j];
00505         Sigma(i, j) += sigma[2] * axis[2][i] * axis[2][j];
00506       }
00507     }
00508 
00509     return *this;
00510   }
00511 };
00512 
00513 }
00514 
00515 
00516 
00517 #endif