math3d.h
Go to the documentation of this file.
00001 /********************************************************************************
00002 Copyright (c) 2015, TRACLabs, Inc.
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006  are permitted provided that the following conditions are met:
00007 
00008     1. Redistributions of source code must retain the above copyright notice,
00009        this list of conditions and the following disclaimer.
00010 
00011     2. Redistributions in binary form must reproduce the above copyright notice,
00012        this list of conditions and the following disclaimer in the documentation
00013        and/or other materials provided with the distribution.
00014 
00015     3. Neither the name of the copyright holder nor the names of its contributors
00016        may be used to endorse or promote products derived from this software
00017        without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
00023 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00025 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00027 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
00028 OF THE POSSIBILITY OF SUCH DAMAGE.
00029 ********************************************************************************/
00030 
00031 #ifndef MATH3D_H
00032 #define MATH3D_H
00033 
00034 #include <string>
00035 #include <iostream>
00036 #include <cmath>
00037 #include <vector>
00038 #include <stdexcept>
00039 #include <cstdlib>
00040 
00041 #ifndef M_PI
00042 #define M_PI (3.14159265358979323846)
00043 #endif
00044 
00045 typedef unsigned char uint8_t;
00046 typedef unsigned int uint32_t;
00047 
00048 namespace math3d
00049 {
00050 
00051 static const double pi = M_PI;
00052 static const double rad_on_deg = pi / 180.;
00053 static const double deg_on_rad = 180. / pi;
00054 
00055 template <typename T>
00056 inline bool almost_zero(T a, double e)
00057 {
00058   return (a == T(0)) || (a > 0 && a < e) || (a < 0 && a > -e);
00059 }
00060 
00061 struct color_rgb24
00062 {
00063   uint8_t r, g, b;
00064   color_rgb24(uint8_t R, uint8_t G, uint8_t B) : r(R), g(G), b(B) {}
00065 };
00066 
00067 template <typename T>
00068 struct vec3d
00069 {
00070   T x, y, z;
00071 
00072   explicit vec3d() : x(0), y(0), z(0) {}
00073   vec3d(T x_, T y_, T z_) : x(x_), y(y_), z(z_) {}
00074 
00075   template <typename S>
00076   vec3d(const vec3d<S>& s) : x(T(s.x)), y(T(s.y)), z(T(s.z)) {}
00077 
00078   template <typename S>
00079   vec3d(const S* s) : x(T(s[0])), y(T(s[1])), z(T(s[2])) {}
00080 
00081   vec3d<T> operator+(const vec3d<T>& p) const
00082   {
00083     return vec3d<T>(x + p.x, y + p.y, z + p.z);
00084   }
00085 
00086   vec3d<T> operator-(const vec3d<T>& p) const
00087   {
00088     return vec3d<T>(x - p.x, y - p.y, z - p.z);
00089   }
00090 
00091   vec3d<T> operator-() const
00092   {
00093     return vec3d<T>(-x, -y, -z);
00094   }
00095 
00096   template <typename S>
00097   vec3d<T>& operator+=(const vec3d<S>& p)
00098   {
00099     x += T(p.x);
00100     y += T(p.y);
00101     z += T(p.z);
00102     return *this;
00103   }
00104 
00105   // rules for partial ordering of function templates say that the new overload
00106   // is a better match, when it matches
00107 
00108   vec3d<T>& operator+=(const vec3d<T>& p)
00109   {
00110     x += p.x;
00111     y += p.y;
00112     z += p.z;
00113     return *this;
00114   }
00115 
00116   template <typename S>
00117   vec3d<T>& operator-=(const vec3d<S>& p)
00118   {
00119     x -= T(p.x);
00120     y -= T(p.y);
00121     z -= T(p.z);
00122     return *this;
00123   }
00124 
00125   vec3d<T>& operator-=(const vec3d<T>& p)
00126   {
00127     x -= p.x;
00128     y -= p.y;
00129     z -= p.z;
00130     return *this;
00131   }
00132 
00133   template <typename Scalar>
00134   vec3d<T>& operator/=(const Scalar& s)
00135   {
00136     const T i = T(1) / T(s);
00137     x *= i;
00138     y *= i;
00139     z *= i;
00140     return *this;
00141   }
00142 
00143   template <typename Scalar>
00144   vec3d<T>& operator*=(const Scalar& s)
00145   {
00146     x *= T(s);
00147     y *= T(s);
00148     z *= T(s);
00149     return *this;
00150   }
00151 
00152   bool operator==(const vec3d& o) const
00153   {
00154     return (x == o.x) && (y == o.y) && (z == o.z);
00155   }
00156 
00157   template <typename S>
00158   bool operator==(const vec3d<S>& o) const
00159   {
00160     return (x == T(o.x) && y == T(o.y) && z == T(o.z));
00161   }
00162 
00163   bool operator!=(const vec3d& o) const
00164   {
00165     return !(*this == o);
00166   }
00167 
00168   template <typename S>
00169   bool operator!=(const vec3d<S>& o) const
00170   {
00171     return !(*this == o);
00172   }
00173 
00174   template <typename Scalar>
00175   friend vec3d<T> operator*(const vec3d<T>& p, const Scalar& s)
00176   {
00177     return vec3d<T>(s * p.x, s * p.y, s * p.z);
00178   }
00179 
00180   template <typename Scalar>
00181   friend vec3d<T> operator*(const Scalar& s, const vec3d<T>& p)
00182   {
00183     return p * s;
00184   }
00185 
00186   template <typename Scalar>
00187   friend vec3d<T> operator/(const vec3d<T>& p, const Scalar& s)
00188   {
00189     return vec3d<T>(p.x / T(s), p.y / T(s), p.z / T(s));
00190   }
00191 
00192   friend std::ostream& operator<<(std::ostream& os, const vec3d<T>& p)
00193   {
00194     return (os << p.x << " " << p.y << " " << p.z);
00195   }
00196 
00197   friend std::istream& operator>>(std::istream& is, vec3d<T>& p)
00198   {
00199     return (is >> p.x >> p.y >> p.z);
00200   }
00201 
00202 };
00203 
00204 typedef vec3d<double> normal3d;
00205 typedef vec3d<double> point3d;
00206 
00207 class oriented_point3d : public point3d
00208 {
00209 public:
00210   normal3d n;
00211 
00212   explicit oriented_point3d() : point3d() {}
00213   oriented_point3d(const point3d& p) : point3d(p) {}
00214   oriented_point3d(double xx, double yy, double zz) : point3d(xx, yy, zz) {}
00215   oriented_point3d(const oriented_point3d& p) : point3d(p), n(p.n) {}
00216   oriented_point3d(const point3d& p, const normal3d& nn) : point3d(p), n(nn) {}
00217 };
00218 
00219 
00220 struct triangle
00221 {
00222   oriented_point3d p0, p1, p2;
00223   int id0, id1, id2; // indices to vertices p0, p1, p2
00224   normal3d n;
00225   triangle() : id0(-1), id1(-1), id2(-1) {}
00226   triangle(int id0, int id1, int id2) : id0(id0), id1(id1), id2(id2) {}
00227   triangle(const oriented_point3d& p0_, const oriented_point3d& p1_, const oriented_point3d& p2_, const normal3d& n_)
00228     : p0(p0_), p1(p1_), p2(p2_), n(n_) {}
00229   triangle(const oriented_point3d& p0_, const oriented_point3d& p1_, const oriented_point3d& p2_, const normal3d& n_, int id0_, int id1_, int id2_)
00230     : p0(p0_), p1(p1_), p2(p2_), id0(id0_), id1(id1_), id2(id2_), n(n_) {}
00231   triangle(const point3d& p0_, const point3d& p1_, const point3d& p2_, const normal3d& n_)
00232     : p0(p0_), p1(p1_), p2(p2_), n(n_) {}
00233   friend std::ostream& operator<<(std::ostream& o, const triangle& t)
00234   {
00235     o << t.p0 << " " << t.p1 << " " << t.p2;
00236     return o;
00237   }
00238 };
00239 
00240 
00241 class invalid_vector : public std::logic_error
00242 {
00243 public:
00244   explicit invalid_vector() : std::logic_error("Exception invalid_vector caught.") {}
00245   invalid_vector(const std::string& msg) : std::logic_error("Exception invalid_vector caught: " + msg) {}
00246 };
00247 
00248 
00249 // ==============================================================
00250 //                         Rotations
00251 // ==============================================================
00252 
00253 // NOTE: this is a std::vector derivation, thus a matrix<bool> will
00254 // take 1 bit per element.
00255 
00256 template<class T>
00257 class matrix : private std::vector<T> // row-major order
00258 {
00259 private:
00260   typedef std::vector<T> super;
00261   int width_;
00262   int height_;
00263 
00264 public:
00265 
00266   const int& width;
00267   const int& height;
00268 
00269   typedef typename super::iterator iterator;
00270   typedef typename super::const_iterator const_iterator;
00271 
00272   explicit matrix() : super(), width_(0), height_(0), width(width_), height(height_) {}
00273 
00274   matrix(int w, int h) : super(w * h), width_(w), height_(h), width(width_), height(height_) {}
00275 
00276   matrix(int w, int h, const T& v) : super(w * h, v), width_(w), height_(h), width(width_), height(height_) {}
00277 
00278   matrix(const matrix<T>& m) : super(), width(width_), height(height_)
00279   {
00280     resize(m.width_, m.height_);
00281     super::assign(m.begin(), m.end());
00282   }
00283 
00284   typename super::reference operator()(size_t r, size_t c)
00285   {
00286     return super::operator[](r * width_ + c);
00287   }
00288   typename super::const_reference operator()(size_t r, size_t c) const
00289   {
00290     return super::operator[](r * width_ + c);
00291   }
00292 
00293   typename super::reference at(const size_t r, const size_t c)
00294   {
00295     return super::at(r * width_ + c);
00296   }
00297   typename super::const_reference at(size_t r, size_t c) const
00298   {
00299     return super::at(r * width_ + c);
00300   }
00301 
00302   const T* to_ptr() const
00303   {
00304     return &(super::operator[](0)); // ok since std::vector is guaranteed to be contiguous
00305   }
00306 
00307   T* to_ptr()
00308   {
00309     return &(super::operator[](0));
00310   }
00311 
00312   void resize(int w, int h)
00313   {
00314     super::resize(w * h);
00315     width_ = w;
00316     height_ = h;
00317   }
00318 
00319   size_t size() const
00320   {
00321     return super::size();
00322   }
00323 
00324   iterator begin()
00325   {
00326     return super::begin();
00327   }
00328   const_iterator begin() const
00329   {
00330     return super::begin();
00331   }
00332   iterator end()
00333   {
00334     return super::end();
00335   }
00336   const_iterator end() const
00337   {
00338     return super::end();
00339   }
00340 
00341   bool operator==(const matrix<T>& m) const
00342   {
00343     if ((width_ != m.width_) || (height != m.height_))
00344       return false;
00345 
00346     const_iterator it1(begin()), it2(m.begin()), it1_end(end());
00347 
00348     for (; it1 != it1_end; ++it1, ++it2)
00349       if (*it1 != *it2) return false;
00350 
00351     return true;
00352   }
00353 
00354   bool operator!=(const matrix<T>& m) const
00355   {
00356     return !(*this == m);
00357   }
00358 
00359   matrix& operator=(const matrix<T>& m)
00360   {
00361     if (&m == this)
00362       return *this;
00363 
00364     if (width != m.width || height != m.height)
00365       throw invalid_vector("Cannot assign matrices with different sizes.");
00366 
00367     super::assign(m.begin(), m.end());
00368     return *this;
00369   }
00370 
00371   template <typename S>
00372   matrix<T>& operator*=(const S& s)
00373   {
00374     for (size_t i = 0; i < size(); ++i)
00375       super::operator[](i) *= T(s);
00376     return *this;
00377   }
00378 
00379   template <typename S>
00380   matrix<T>& operator/=(const S& s)
00381   {
00382     for (size_t i = 0; i < size(); ++i)
00383       super::operator[](i) /= T(s);
00384     return *this;
00385   }
00386 
00387   friend std::ostream& operator<<(std::ostream& s, const matrix<T>& m)
00388   {
00389     for (int y = 0; y < m.height_; ++y)
00390     {
00391       for (int x = 0; x < m.width_; ++x)
00392       {
00393         s << m[y * m.width_ + x] << " ";
00394       }
00395       s << std::endl;
00396     }
00397     return s;
00398   }
00399 };
00400 
00401 
00402 template<typename T>
00403 struct matrix3x3
00404 {
00405   T r00, r01, r02,
00406   r10, r11, r12,
00407   r20, r21, r22;
00408 
00409   int width, height;
00410 
00411   explicit matrix3x3()
00412     : r00(0), r01(0), r02(0)
00413     , r10(0), r11(0), r12(0)
00414     , r20(0), r21(0), r22(0)
00415     , width(3), height(3)
00416   {}
00417 
00418   template <typename S>
00419   explicit matrix3x3(const S* v)
00420     : r00(v[0]), r01(v[1]), r02(v[2])
00421     , r10(v[3]), r11(v[4]), r12(v[5])
00422     , r20(v[6]), r21(v[7]), r22(v[8])
00423     , width(3), height(3)
00424   {}
00425 
00426   void set_column(size_t c, const vec3d<T>& v)
00427   {
00428     T x = v.x;
00429     T y = v.y;
00430     T z = v.z;
00431 
00432     if (c == 0)
00433     {
00434       r00 = x;
00435       r10 = y;
00436       r20 = z;
00437     }
00438     else if (c == 1)
00439     {
00440       r01 = x;
00441       r11 = y;
00442       r21 = z;
00443     }
00444     else if (c == 2)
00445     {
00446       r02 = x;
00447       r12 = y;
00448       r22 = z;
00449     }
00450     else
00451       throw std::logic_error("Cannot set column for 3x3 matrix.");
00452   }
00453 
00454   T& operator()(size_t row, size_t col)
00455   {
00456     switch (row)
00457     {
00458     case 0:
00459       if (col == 0) return r00;
00460       if (col == 1) return r01;
00461       if (col == 2) return r02;
00462       else throw std::out_of_range("Cannot access element in 3x3 matrix");
00463     case 1:
00464       if (col == 0) return r10;
00465       if (col == 1) return r11;
00466       if (col == 2) return r12;
00467       else throw std::out_of_range("Cannot access element in 3x3 matrix");
00468     case 2:
00469       if (col == 0) return r20;
00470       if (col == 1) return r21;
00471       if (col == 2) return r22;
00472       else throw std::out_of_range("Cannot access element in 3x3 matrix");
00473     default:
00474       throw std::out_of_range("Cannot access element in 3x3 matrix");
00475     }
00476   }
00477 
00478   const T& operator()(size_t row, size_t col) const
00479   {
00480     switch (row)
00481     {
00482     case 0:
00483       if (col == 0) return r00;
00484       if (col == 1) return r01;
00485       if (col == 2) return r02;
00486       else throw std::out_of_range("Cannot access element in 3x3 matrix");
00487     case 1:
00488       if (col == 0) return r10;
00489       if (col == 1) return r11;
00490       if (col == 2) return r12;
00491       else throw std::out_of_range("Cannot access element in 3x3 matrix");
00492     case 2:
00493       if (col == 0) return r20;
00494       if (col == 1) return r21;
00495       if (col == 2) return r22;
00496       else throw std::out_of_range("Cannot access element in 3x3 matrix");
00497     default:
00498       throw std::out_of_range("Cannot access element in 3x3 matrix");
00499     }
00500   }
00501 
00502   friend std::ostream& operator<<(std::ostream& s, const matrix3x3<T>& m)
00503   {
00504     s << m.r00 << " " << m.r01 << " " << m.r02 << std::endl;
00505     s << m.r10 << " " << m.r11 << " " << m.r12 << std::endl;
00506     s << m.r20 << " " << m.r21 << " " << m.r22 << std::endl;
00507     return s;
00508   }
00509 };
00510 
00511 
00512 template <typename T>
00513 inline matrix3x3<T> identity3x3()
00514 {
00515   matrix3x3<T> m;
00516   set_identity(m);
00517   return m;
00518 }
00519 
00520 
00521 template <typename T>
00522 inline void mult_matrix_inplace(const matrix3x3<T>& m1, const matrix3x3<T>& m2, matrix3x3<T>& r)
00523 {
00524   const double r00 = m1.r00 * m2.r00 + m1.r01 * m2.r10 + m1.r02 * m2.r20;
00525   const double r01 = m1.r00 * m2.r01 + m1.r01 * m2.r11 + m1.r02 * m2.r21;
00526   const double r02 = m1.r00 * m2.r02 + m1.r01 * m2.r12 + m1.r02 * m2.r22;
00527 
00528   const double r10 = m1.r10 * m2.r00 + m1.r11 * m2.r10 + m1.r12 * m2.r20;
00529   const double r11 = m1.r10 * m2.r01 + m1.r11 * m2.r11 + m1.r12 * m2.r21;
00530   const double r12 = m1.r10 * m2.r02 + m1.r11 * m2.r12 + m1.r12 * m2.r22;
00531 
00532   const double r20 = m1.r20 * m2.r00 + m1.r21 * m2.r10 + m1.r22 * m2.r20;
00533   const double r21 = m1.r20 * m2.r01 + m1.r21 * m2.r11 + m1.r22 * m2.r21;
00534   const double r22 = m1.r20 * m2.r02 + m1.r21 * m2.r12 + m1.r22 * m2.r22;
00535 
00536   r.r00 = r00;
00537   r.r01 = r01;
00538   r.r02 = r02;
00539   r.r10 = r10;
00540   r.r11 = r11;
00541   r.r12 = r12;
00542   r.r20 = r20;
00543   r.r21 = r21;
00544   r.r22 = r22;
00545 }
00546 
00547 template <typename T>
00548 inline void mult_matrix(const matrix3x3<T>& m1, const matrix3x3<T>& m2, matrix3x3<T>& r)
00549 {
00550   if (&r == &m1 || &r == &m2) throw std::logic_error("math3d::mult_matrix() argument alias");
00551   return mult_matrix_inplace<T>(m1, m2, r);
00552 }
00553 
00554 // NO in-place!
00555 template <typename Rot1, typename Rot2, typename Rot3>
00556 void mult_matrix(const Rot1& m1, const Rot2& m2, Rot3& r)
00557 {
00558   if ((char*)&r == (char*)&m1 || (char*)&r == (char*)&m2)
00559     throw std::logic_error("math3d::mult_matrix() argument alias");
00560 
00561   if (m1.width != m2.height || r.height != m1.height || r.width != m2.width)
00562     throw std::logic_error("Incompatible size matrices");
00563 
00564   double sum;
00565 
00566   for (int is = 0; is < m1.height; ++is)
00567   {
00568     for (int jd = 0; jd < m2.width; ++jd)
00569     {
00570       sum = 0.;
00571       for (int js = 0; js < m1.width; ++js)
00572       {
00573         sum += m1(is, js) * m2(js, jd);
00574       }
00575       r(is, jd) = sum;
00576     }
00577   }
00578 }
00579 
00580 // ==============================================================
00581 //                         Quaternions
00582 // ==============================================================
00583 
00584 template <typename T>
00585 struct quaternion
00586 {
00587   T w, i, j, k;
00588 
00589   explicit quaternion(T v = 0) : w(v), i(0), j(0), k(0) {}
00590   //explicit quaternion(const T* p) : w(p[0]), i(p[1]), j(p[2]), k(p[3]) {}
00591   quaternion(T ww, T ii, T jj, T kk) : w(ww), i(ii), j(jj), k(kk) {}
00592 
00593   static quaternion<T> convert(const vec3d<T>& p)
00594   {
00595     return quaternion<T>(0, p.x, p.y, p.z);
00596   }
00597 
00598   static quaternion<T> convert(const T* p)
00599   {
00600     return quaternion<T>(p[0], p[1], p[2], p[3]);
00601   }
00602 
00603   quaternion<T>& operator+= (const quaternion<T>& a)
00604   {
00605     w += a.w;
00606     i += a.i;
00607     j += a.j;
00608     k += a.k;
00609     return *this;
00610   }
00611 
00612   quaternion<T>& operator*= (T a)
00613   {
00614     w *= a;
00615     i *= a;
00616     j *= a;
00617     k *= a;
00618     return *this;
00619   }
00620 
00621   void to_vector(T* p) const
00622   {
00623     p[0] = w;
00624     p[1] = i;
00625     p[2] = j;
00626     p[3] = k;
00627   }
00628 
00629   friend std::ostream& operator<<(std::ostream& os, const quaternion<T>& q)
00630   {
00631     return os << "[ " << q.w << " " << q.i << " " << q.j << " " << q.k << " ]";
00632   }
00633 
00634   friend std::istream& operator>>(std::istream& is, quaternion<T>& q)
00635   {
00636     std::string dump;
00637     return (is >> dump >> q.w >> q.i >> q.j >> q.k >> dump);
00638   }
00639 };
00640 
00641 template <typename T>
00642 quaternion<T> operator+ (const quaternion<T>& a, const quaternion<T>& b)
00643 {
00644   quaternion<T> result(a);
00645   result += b;
00646   return result;
00647 }
00648 
00649 template <typename T>
00650 T dot(const quaternion<T>& a, const quaternion<T>& b)
00651 {
00652   return a.w * b.w + a.i * b.i + a.j * b.j + a.k * b.k;
00653 }
00654 
00655 template <typename T>
00656 T norm(const quaternion<T>& a)
00657 {
00658   return std::sqrt(dot(a, a));
00659 }
00660 
00661 template <typename T>
00662 quaternion<T> operator* (const quaternion<T>& a, const quaternion<T>& b)
00663 {
00664   quaternion<T> result;
00665 
00666   result.w = a.w * b.w - a.i * b.i - a.j * b.j - a.k * b.k;
00667   result.i = a.i * b.w + a.w * b.i - a.k * b.j + a.j * b.k;
00668   result.j = a.j * b.w + a.k * b.i + a.w * b.j - a.i * b.k;
00669   result.k = a.k * b.w - a.j * b.i + a.i * b.j + a.w * b.k;
00670 
00671   return result;
00672 }
00673 
00674 template <typename T>
00675 quaternion<T> operator~(const quaternion<T>& a)
00676 {
00677   return quaternion<T>(a.w, -a.i, -a.j, -a.k);
00678 }
00679 
00680 template <typename T>
00681 inline void conjugate(quaternion<T>& q)
00682 {
00683   q.i = -q.i;
00684   q.j = -q.j;
00685   q.k = -q.k;
00686 }
00687 
00688 template <typename T>
00689 inline void normalize(quaternion<T>& q)
00690 {
00691   T mag = q.w * q.w + q.i * q.i + q.j * q.j + q.k * q.k;
00692   if (!almost_zero(mag - T(1), 1e-10))
00693   {
00694     mag = std::sqrt(mag);
00695     q.w /= mag;
00696     q.i /= mag;
00697     q.j /= mag;
00698     q.k /= mag;
00699   }
00700 }
00701 
00702 template <typename T>
00703 inline void set_identity(quaternion<T>& q)
00704 {
00705   q.w = T(1);
00706   q.i = q.j = q.k = T(0);
00707 }
00708 
00709 // returns a normalized unit quaternion
00710 template<typename T>
00711 quaternion<T> rot_matrix_to_quaternion(const matrix3x3<T>& m)
00712 {
00713   const T m00 = m(0, 0);
00714   const T m11 = m(1, 1);
00715   const T m22 = m(2, 2);
00716   const T m01 = m(0, 1);
00717   const T m02 = m(0, 2);
00718   const T m10 = m(1, 0);
00719   const T m12 = m(1, 2);
00720   const T m20 = m(2, 0);
00721   const T m21 = m(2, 1);
00722   const T tr = m00 + m11 + m22;
00723 
00724   quaternion<T> ret;
00725 
00726   if (tr > 0)
00727   {
00728     T s = std::sqrt(tr + T(1)) * 2; // S=4*qw
00729     ret.w = 0.25 * s;
00730     ret.i = (m21 - m12) / s;
00731     ret.j = (m02 - m20) / s;
00732     ret.k = (m10 - m01) / s;
00733   }
00734   else if ((m00 > m11) & (m00 > m22))
00735   {
00736     const T s = std::sqrt(T(1) + m00 - m11 - m22) * 2; // S=4*qx
00737     ret.w = (m21 - m12) / s;
00738     ret.i = 0.25 * s;
00739     ret.j = (m01 + m10) / s;
00740     ret.k = (m02 + m20) / s;
00741   }
00742   else if (m11 > m22)
00743   {
00744     const T s = std::sqrt(T(1) + m11 - m00 - m22) * 2; // S=4*qy
00745     ret.w = (m02 - m20) / s;
00746     ret.i = (m01 + m10) / s;
00747     ret.j = 0.25 * s;
00748     ret.k = (m12 + m21) / s;
00749   }
00750   else
00751   {
00752     const T s = std::sqrt(T(1) + m22 - m00 - m11) * 2; // S=4*qz
00753     ret.w = (m10 - m01) / s;
00754     ret.i = (m02 + m20) / s;
00755     ret.j = (m12 + m21) / s;
00756     ret.k = 0.25 * s;
00757   }
00758 
00759   return ret;
00760 }
00761 
00762 // assumes a normalized unit quaternion
00763 template <typename T>
00764 matrix3x3<T> quaternion_to_rot_matrix(const quaternion<T>& q)
00765 {
00766   matrix3x3<T> m;
00767   const T w = q.w, i = q.i, j = q.j, k = q.k;
00768 
00769   m(0, 0) = 1 - 2 * j * j - 2 * k * k;
00770   m(0, 1) = 2 * i * j - 2 * k * w;
00771   m(0, 2) = 2 * i * k + 2 * j * w;
00772 
00773   m(1, 0) = 2 * i * j + 2 * k * w;
00774   m(1, 1) = 1 - 2 * i * i - 2 * k * k;
00775   m(1, 2) = 2 * j * k - 2 * i * w;
00776 
00777   m(2, 0) = 2 * i * k - 2 * j * w;
00778   m(2, 1) = 2 * j * k + 2 * i * w;
00779   m(2, 2) = 1 - 2 * i * i - 2 * j * j;
00780 
00781   return m;
00782 }
00783 
00784 template <typename T>
00785 inline void mult_quaternion(const quaternion<T>& a, const quaternion<T>& b, quaternion<T>& r)
00786 {
00787   r.w = a.w * b.w - (a.i * b.i + a.j * b.j + a.k * b.k);
00788   r.i = a.w * b.i + b.w * a.i + a.j * b.k - a.k * b.j;
00789   r.j = a.w * b.j + b.w * a.j + a.k * b.i - a.i * b.k;
00790   r.k = a.w * b.k + b.w * a.k + a.i * b.j - a.j * b.i;
00791 }
00792 
00793 // ==============================================================
00794 //
00795 // ==============================================================
00796 
00797 template <typename T>
00798 void transpose(matrix<T>& m)
00799 {
00800   matrix<T> old(m);
00801   const int w = m.width;
00802   const int h = m.height;
00803   m.resize(h, w);
00804 
00805   for (int row = 0; row < h; ++row)
00806   {
00807     for (int col = 0; col < w; ++col)
00808     {
00809       m(col, row) = old(row, col);
00810     }
00811   }
00812 }
00813 
00814 template <typename T>
00815 inline void transpose(matrix3x3<T>& m)
00816 {
00817   const T m01 = m.r01, m02 = m.r02, m12 = m.r12, m10 = m.r10, m21 = m.r21, m20 = m.r20;
00818   m.r01 = m10;
00819   m.r02 = m20;
00820   m.r10 = m01;
00821   m.r20 = m02;
00822   m.r12 = m21;
00823   m.r21 = m12;
00824 }
00825 
00826 template <typename T>
00827 inline matrix3x3<T> get_transpose(const matrix3x3<T>& m)
00828 {
00829   matrix3x3<T> ret;
00830   ret.r00 = m.r00;
00831   ret.r01 = m.r10;
00832   ret.r02 = m.r20;
00833   ret.r10 = m.r01;
00834   ret.r11 = m.r11;
00835   ret.r20 = m.r02;
00836   ret.r12 = m.r21;
00837   ret.r21 = m.r12;
00838   ret.r22 = m.r22;
00839   return ret;
00840 }
00841 
00842 // dest matrix must already be of the right size
00843 template <typename T>
00844 void transpose(const matrix<T>& src, matrix<T>& dest)
00845 {
00846   if (src.width != dest.height || src.height != dest.width)
00847     throw math3d::invalid_vector("math3d::transpose(): Destination matrix must be of the right size.");
00848 
00849   const int w = src.width;
00850   const int h = src.height;
00851 
00852   for (int row = 0; row < h; ++row)
00853   {
00854     for (int col = 0; col < w; ++col)
00855     {
00856       dest(col, row) = src(row, col);
00857     }
00858   }
00859 }
00860 
00861 template <typename T>
00862 inline void transpose(const matrix3x3<T>& src, matrix3x3<T>& dest)
00863 {
00864   dest.r00 = src.r00;
00865   dest.r11 = src.r11;
00866   dest.r22 = src.r22;
00867   dest.r01 = src.r10;
00868   dest.r02 = src.r20;
00869   dest.r10 = src.r01;
00870   dest.r12 = src.r21;
00871   dest.r21 = src.r12;
00872   dest.r20 = src.r02;
00873 }
00874 
00875 template <typename T>
00876 void set_identity(matrix<T>& m, T val = 1)
00877 {
00878   if (m.width != m.height)
00879     throw invalid_vector("Cannot set identity on a rectangular matrix.");
00880 
00881   if (m.width == 0)
00882     return;
00883 
00884   const int n = m.width * m.height;
00885   const int w = m.width;
00886 
00887   int one = 0;
00888   for (int k = 0; k < n; ++k)
00889   {
00890     if (k == one)
00891     {
00892       m(k / w, k % w) = val;
00893       one += w + 1;
00894     }
00895     else
00896       m(k / w, k % w) = 0;
00897   }
00898 }
00899 
00900 template <typename T>
00901 void set_identity(matrix3x3<T>& m, T val = 1)
00902 {
00903   m.r00 = val;
00904   m.r01 = 0;
00905   m.r02 = 0;
00906   m.r10 = 0;
00907   m.r11 = val;
00908   m.r12 = 0;
00909   m.r20 = 0;
00910   m.r21 = 0;
00911   m.r22 = val;
00912 }
00913 
00914 
00915 // ==============================================================
00916 //                         Rigid Motion
00917 // ==============================================================
00918 
00919 typedef std::pair<matrix3x3<double>, point3d> rigid_motion_t;
00920 
00921 template <typename T>
00922 void rotate(vec3d<T>& p, const matrix<T>& rot)
00923 {
00924   if (rot.height != 3 || rot.width != 3)
00925     throw std::logic_error("Rotation matrix must be 3x3");
00926 
00927   T oldx = p.x, oldy = p.y, oldz = p.z;
00928   p.x = oldx * rot(0, 0) + oldy * rot(0, 1) + oldz * rot(0, 2);
00929   p.y = oldx * rot(1, 0) + oldy * rot(1, 1) + oldz * rot(1, 2);
00930   p.z = oldx * rot(2, 0) + oldy * rot(2, 1) + oldz * rot(2, 2);
00931 }
00932 
00933 template <typename T>
00934 void rotate(vec3d<T>& p, const matrix3x3<T>& rot)
00935 {
00936   T oldx = p.x, oldy = p.y, oldz = p.z;
00937   p.x = oldx * rot.r00 + oldy * rot.r01 + oldz * rot.r02;
00938   p.y = oldx * rot.r10 + oldy * rot.r11 + oldz * rot.r12;
00939   p.z = oldx * rot.r20 + oldy * rot.r21 + oldz * rot.r22;
00940 }
00941 
00942 template <typename T, typename S>
00943 void rotate(vec3d<T>& p, const matrix<S>& rot)
00944 {
00945   if (rot.height != 3 || rot.width != 3)
00946     throw std::logic_error("Rotation matrix must be 3x3");
00947 
00948   T oldx = p.x, oldy = p.y, oldz = p.z;
00949   p.x = T(oldx * rot(0, 0) + oldy * rot(0, 1) + oldz * rot(0, 2));
00950   p.y = T(oldx * rot(1, 0) + oldy * rot(1, 1) + oldz * rot(1, 2));
00951   p.z = T(oldx * rot(2, 0) + oldy * rot(2, 1) + oldz * rot(2, 2));
00952 }
00953 
00954 template <typename T, typename S>
00955 inline void rotate(vec3d<T>& p, const matrix3x3<S>& rot)
00956 {
00957   T oldx = p.x, oldy = p.y, oldz = p.z;
00958   p.x = T(oldx * rot.r00 + oldy * rot.r01 + oldz * rot.r02);
00959   p.y = T(oldx * rot.r10 + oldy * rot.r11 + oldz * rot.r12);
00960   p.z = T(oldx * rot.r20 + oldy * rot.r21 + oldz * rot.r22);
00961 }
00962 
00963 template <typename T>
00964 inline void rotate(vec3d<T>& p, const quaternion<T>& rot)
00965 {
00966   rotate(p, quaternion_to_rot_matrix(rot));
00967 }
00968 
00969 
00970 template <typename T>
00971 inline vec3d<T> get_rotate(const vec3d<T>& v, const quaternion<T>& q)
00972 {
00973   return get_rotate(v, quaternion_to_rot_matrix(q));
00974   /*
00975     const T
00976     a = q.w, b = q.i, c = q.j, d = q.k,
00977     t2 = a*b, t3 = a*c, t4 = a*d, t5 = -b*b, t6 = b*c,
00978     t7 = b*d, t8 = -c*c, t9 = c*d, t10 = -d*d,
00979     v1 = v.x, v2 = v.y, v3 = v.z;
00980     return vec3d<T>(
00981     2*( (t8 + t10)*v1 + (t6 -  t4)*v2 + (t3 + t7)*v3 ) + v1,
00982     2*( (t4 +  t6)*v1 + (t5 + t10)*v2 + (t9 - t2)*v3 ) + v2,
00983     2*( (t7 -  t3)*v1 + (t2 +  t9)*v2 + (t5 + t8)*v3 ) + v3);
00984   */
00985 }
00986 
00987 template <typename T>
00988 inline vec3d<T> get_rotate(const vec3d<T>& p, const matrix3x3<T>& rot)
00989 {
00990   return vec3d<T>(p.x * rot.r00 + p.y * rot.r01 + p.z * rot.r02,
00991                   p.x * rot.r10 + p.y * rot.r11 + p.z * rot.r12,
00992                   p.x * rot.r20 + p.y * rot.r21 + p.z * rot.r22);
00993 }
00994 
00995 
00996 template <typename T, typename RotationType>
00997 inline void rotate_translate(vec3d<T>& v, const RotationType& rot, const point3d& trans)
00998 {
00999   rotate(v, rot);
01000   v += trans;
01001 }
01002 
01003 template <typename T>
01004 inline vec3d<T> get_rotate_translate(const vec3d<T>& p, const matrix3x3<T>& rot, const point3d& t)
01005 {
01006   return vec3d<T>(p.x * rot.r00 + p.y * rot.r01 + p.z * rot.r02 + t.x,
01007                   p.x * rot.r10 + p.y * rot.r11 + p.z * rot.r12 + t.y,
01008                   p.x * rot.r20 + p.y * rot.r21 + p.z * rot.r22 + t.z);
01009 }
01010 
01011 template <typename T>
01012 inline vec3d<T> get_rotate_translate(const vec3d<T>& p, const matrix<T>& rot, const point3d& t)
01013 {
01014   if (rot.height != 3 || rot.width != 3)
01015     throw std::logic_error("Rotation matrix must be 3x3");
01016 
01017   return vec3d<T>(p.x * rot(0, 0) + p.y * rot(0, 1) + p.z * rot(0, 2) + t.x,
01018                   p.x * rot(1, 0) + p.y * rot(1, 1) + p.z * rot(1, 2) + t.y,
01019                   p.x * rot(2, 0) + p.y * rot(2, 1) + p.z * rot(2, 2) + t.z);
01020 }
01021 
01022 template <typename T>
01023 inline vec3d<T> get_rotate_translate(const vec3d<T>& p, const T* rot, const T* t)
01024 {
01025   return get_rotate_translate(p, matrix3x3<T>(rot), vec3d<T>(t[0], t[1], t[2]));
01026 }
01027 
01028 template <typename T>
01029 inline vec3d<T> get_rotate_translate(const vec3d<T>& v, const quaternion<T>& rot, const point3d& t)
01030 {
01031   return (get_rotate(v, rot) + t);
01032 }
01033 
01034 
01038 template <typename R, typename T>
01039 inline void invert(R& r, T& t)
01040 {
01041   transpose(r);
01042   rotate(t, r);
01043   t.x = -t.x;
01044   t.y = -t.y;
01045   t.z = -t.z;
01046 }
01047 
01048 
01053 template <typename T>
01054 void relative_motion(
01055 
01056   const matrix3x3<T>& Ri, const point3d& Ti,
01057   const matrix3x3<T>& Rj, const point3d& Tj,
01058   matrix3x3<T>& Rij, point3d& Tij
01059 
01060 )
01061 {
01062   matrix3x3<T> Ri_inv = Ri;
01063   point3d Ti_inv = Ti;
01064   invert(Ri_inv, Ti_inv);
01065 
01066   mult_matrix(Ri_inv, Rj, Rij);
01067   Tij = get_rotate_translate(Tj, Ri_inv, Ti_inv);
01068 }
01069 
01070 
01071 // ==============================================================
01072 //                      Vector Operations
01073 // ==============================================================
01074 
01075 template <typename T>
01076 inline double normalize(vec3d<T>& p)
01077 {
01078   const double n = magnitude(p);
01079   if (n == 0.)
01080   {
01081     p.x = 0;
01082     p.y = 0;
01083     p.z = 0;
01084   }
01085   else
01086   {
01087     p.x /= n;
01088     p.y /= n;
01089     p.z /= n;
01090   }
01091   return n;
01092 }
01093 
01094 template <typename T>
01095 inline vec3d<T> get_normalize(const vec3d<T>& p)
01096 {
01097   vec3d<T> q(p);
01098   normalize(q);
01099   return q;
01100 }
01101 
01102 template <typename T>
01103 inline double dist(const T& p1, const T& p2)
01104 {
01105   const double sqdist = squared_dist(p1, p2);
01106   return (sqdist == 0. ? 0. : std::sqrt(sqdist));
01107 }
01108 
01109 // ||p1 - p2||^2
01110 template <typename T>
01111 inline double squared_dist(const vec3d<T>& p1, const vec3d<T>& p2)
01112 {
01113   T x = p1.x - p2.x;
01114   T y = p1.y - p2.y;
01115   T z = p1.z - p2.z;
01116   return ((x * x) + (y * y) + (z * z));
01117 }
01118 
01119 template <typename T>
01120 inline T dot_product(const vec3d<T>& v1, const vec3d<T>& v2)
01121 {
01122   return (v1.x * v2.x) + (v1.y * v2.y) + (v1.z * v2.z);
01123 }
01124 
01125 template <typename T, typename S>
01126 inline double dot_product(const vec3d<T>& v1, const vec3d<S>& v2)
01127 {
01128   return (v1.x * v2.x) + (v1.y * v2.y) + (v1.z * v2.z);
01129 }
01130 
01131 template <typename T>
01132 inline T dot_product(const quaternion<T>& p, const quaternion<T>& q)
01133 {
01134   return (p.w * q.w + p.i * q.i + p.j * q.j + p.k * q.k);
01135 }
01136 
01137 template <typename T>
01138 inline double norm2(const T& v)
01139 {
01140   return dot_product(v, v);
01141 }
01142 
01143 template <typename T>
01144 inline double magnitude(const T& p)
01145 {
01146   return std::sqrt(dot_product(p, p));
01147 }
01148 
01149 template <typename T>
01150 inline vec3d<T> cross_product(const vec3d<T>& v1, const vec3d<T>& v2)
01151 {
01152   return vec3d<T>(
01153            (v1.y * v2.z) - (v1.z * v2.y),
01154            (v1.z * v2.x) - (v1.x * v2.z),
01155            (v1.x * v2.y) - (v1.y * v2.x)
01156          );
01157 }
01158 
01159 
01160 template <typename Iterator>
01161 inline double median(Iterator start, Iterator end)
01162 {
01163   const typename Iterator::difference_type n = end - start;
01164   if (n <= 0) return 0.;
01165 
01166   if (n % 2 == 0)
01167     return (*(start + (n / 2)) + * (start + (n / 2 - 1))) / 2.;
01168   else
01169     return *(start + ((n - 1) / 2));
01170 }
01171 
01172 }
01173 
01174 #endif


trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Thu Apr 25 2019 03:39:22