eigen.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *  Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of Willow Garage, Inc. nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id: eigen.h 6126 2012-07-03 20:19:58Z aichim $
00038  *
00039  */
00040 // The computeRoots function included in this is based on materials
00041 // covered by the following copyright and license:
00042 //
00043 // Geometric Tools, LLC
00044 // Copyright (c) 1998-2010
00045 // Distributed under the Boost Software License, Version 1.0.
00046 //
00047 // Permission is hereby granted, free of charge, to any person or organization
00048 // obtaining a copy of the software and accompanying documentation covered by
00049 // this license (the "Software") to use, reproduce, display, distribute,
00050 // execute, and transmit the Software, and to prepare derivative works of the
00051 // Software, and to permit third-parties to whom the Software is furnished to
00052 // do so, all subject to the following:
00053 //
00054 // The copyright notices in the Software and this entire statement, including
00055 // the above license grant, this restriction and the following disclaimer,
00056 // must be included in all copies of the Software, in whole or in part, and
00057 // all derivative works of the Software, unless such copies or derivative
00058 // works are solely in the form of machine-executable object code generated by
00059 // a source language processor.
00060 //
00061 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00062 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00063 // FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT
00064 // SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE
00065 // FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,
00066 // ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
00067 // DEALINGS IN THE SOFTWARE.
00068 
00069 #ifndef PCL_EIGEN_H_
00070 #define PCL_EIGEN_H_
00071 
00072 #ifndef NOMINMAX
00073 #define NOMINMAX
00074 #endif
00075 
00076 #if defined __GNUC__
00077 #  pragma GCC system_header
00078 #elif defined __SUNPRO_CC
00079 #  pragma disable_warn
00080 #elif defined _MSC_VER
00081 #  pragma warning(push, 1)
00082 #endif
00083 
00084 #include <Eigen/StdVector>
00085 #include <Eigen/Core>
00086 #include <Eigen/Eigenvalues>
00087 #include <Eigen/Geometry>
00088 #include <Eigen/SVD>
00089 #include <Eigen/LU>
00090 #include <Eigen/Dense>
00091 #include <Eigen/Eigenvalues>
00092 
00093 namespace pcl
00094 {
00095   template <typename Scalar> inline Scalar
00096   sqrt (const Scalar &val)
00097   {
00098   }
00099 
00100   template<> inline double
00101   sqrt<double> (const double &val)
00102   {
00103     return (::sqrt (val));
00104   }
00105 
00106   template<> inline float
00107   sqrt<float> (const float &val)
00108   {
00109     return (::sqrtf (val));
00110   }
00111 
00112   template<> inline long double
00113   sqrt<long double> (const long double &val)
00114   {
00115     return (::sqrtl (val));
00116   }
00117 
00123   template<typename Scalar, typename Roots> inline void
00124   computeRoots2 (const Scalar& b, const Scalar& c, Roots& roots)
00125   {
00126     roots (0) = Scalar (0);
00127     Scalar d = Scalar (b * b - 4.0 * c);
00128     if (d < 0.0) // no real roots!!!! THIS SHOULD NOT HAPPEN!
00129       d = 0.0;
00130 
00131     Scalar sd = sqrt (d);
00132 
00133     roots (2) = 0.5f * (b + sd);
00134     roots (1) = 0.5f * (b - sd);
00135   }
00136 
00141   template<typename Matrix, typename Roots> inline void
00142   computeRoots (const Matrix& m, Roots& roots)
00143   {
00144     typedef typename Matrix::Scalar Scalar;
00145 
00146     // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0.  The
00147     // eigenvalues are the roots to this equation, all guaranteed to be
00148     // real-valued, because the matrix is symmetric.
00149     Scalar c0 =            m (0, 0) * m (1, 1) * m (2, 2)
00150             + Scalar (2) * m (0, 1) * m (0, 2) * m (1, 2)
00151                          - m (0, 0) * m (1, 2) * m (1, 2)
00152                          - m (1, 1) * m (0, 2) * m (0, 2)
00153                          - m (2, 2) * m (0, 1) * m (0, 1);
00154     Scalar c1 = m (0, 0) * m (1, 1) -
00155                 m (0, 1) * m (0, 1) +
00156                 m (0, 0) * m (2, 2) -
00157                 m (0, 2) * m (0, 2) +
00158                 m (1, 1) * m (2, 2) -
00159                 m (1, 2) * m (1, 2);
00160     Scalar c2 = m (0, 0) + m (1, 1) + m (2, 2);
00161 
00162 
00163     if (fabs (c0) < Eigen::NumTraits<Scalar>::epsilon ())// one root is 0 -> quadratic equation
00164       computeRoots2 (c2, c1, roots);
00165     else
00166     {
00167       const Scalar s_inv3 = Scalar (1.0 / 3.0);
00168       const Scalar s_sqrt3 = Eigen::internal::sqrt (Scalar (3.0));
00169       // Construct the parameters used in classifying the roots of the equation
00170       // and in solving the equation for the roots in closed form.
00171       Scalar c2_over_3 = c2*s_inv3;
00172       Scalar a_over_3 = (c1 - c2 * c2_over_3) * s_inv3;
00173       if (a_over_3 > Scalar (0))
00174         a_over_3 = Scalar (0);
00175 
00176       Scalar half_b = Scalar (0.5) * (c0 + c2_over_3 * (Scalar (2) * c2_over_3 * c2_over_3 - c1));
00177 
00178       Scalar q = half_b * half_b + a_over_3 * a_over_3*a_over_3;
00179       if (q > Scalar (0))
00180         q = Scalar (0);
00181 
00182       // Compute the eigenvalues by solving for the roots of the polynomial.
00183       Scalar rho = Eigen::internal::sqrt (-a_over_3);
00184       Scalar theta = std::atan2 (Eigen::internal::sqrt (-q), half_b) * s_inv3;
00185       Scalar cos_theta = Eigen::internal::cos (theta);
00186       Scalar sin_theta = Eigen::internal::sin (theta);
00187       roots (0) = c2_over_3 + Scalar (2) * rho * cos_theta;
00188       roots (1) = c2_over_3 - rho * (cos_theta + s_sqrt3 * sin_theta);
00189       roots (2) = c2_over_3 - rho * (cos_theta - s_sqrt3 * sin_theta);
00190 
00191       // Sort in increasing order.
00192       if (roots (0) >= roots (1))
00193         std::swap (roots (0), roots (1));
00194       if (roots (1) >= roots (2))
00195       {
00196         std::swap (roots (1), roots (2));
00197         if (roots (0) >= roots (1))
00198           std::swap (roots (0), roots (1));
00199       }
00200 
00201       if (roots (0) <= 0) // eigenval for symetric positive semi-definite matrix can not be negative! Set it to 0
00202         computeRoots2 (c2, c1, roots);
00203     }
00204   }
00205 
00212   template <typename Matrix, typename Vector> inline void
00213   eigen22 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenvector)
00214   {
00215     // if diagonal matrix, the eigenvalues are the diagonal elements
00216     // and the eigenvectors are not unique, thus set to Identity
00217     if (fabs(mat.coeff (1)) <= std::numeric_limits<typename Matrix::Scalar>::min ())
00218     {
00219       if (mat.coeff (0) < mat.coeff (2))
00220       {
00221         eigenvalue = mat.coeff (0);
00222         eigenvector [0] = 1.0;
00223         eigenvector [1] = 0.0;
00224       }
00225       else
00226       {
00227         eigenvalue = mat.coeff (2);
00228         eigenvector [0] = 0.0;
00229         eigenvector [1] = 1.0;
00230       }
00231       return;
00232     }
00233     
00234     // 0.5 to optimize further calculations
00235     typename Matrix::Scalar trace = static_cast<typename Matrix::Scalar> (0.5) * (mat.coeff (0) + mat.coeff (3));
00236     typename Matrix::Scalar determinant = mat.coeff (0) * mat.coeff (3) - mat.coeff (1) * mat.coeff (1);
00237 
00238     typename Matrix::Scalar temp = trace * trace - determinant;
00239 
00240     if (temp < 0)
00241       temp = 0;
00242 
00243     eigenvalue = trace - sqrt (temp);
00244     
00245     eigenvector [0] = - mat.coeff (1);
00246     eigenvector [1] = mat.coeff (0) - eigenvalue;
00247     eigenvector.normalize ();
00248   }
00249 
00256   template <typename Matrix, typename Vector> inline void
00257   eigen22 (const Matrix& mat, Matrix& eigenvectors, Vector& eigenvalues)
00258   {
00259     // if diagonal matrix, the eigenvalues are the diagonal elements
00260     // and the eigenvectors are not unique, thus set to Identity
00261     if (fabs(mat.coeff (1)) <= std::numeric_limits<typename Matrix::Scalar>::min ())
00262     {
00263       if (mat.coeff (0) < mat.coeff (3))
00264       {
00265         eigenvalues.coeffRef (0) = mat.coeff (0);
00266         eigenvalues.coeffRef (1) = mat.coeff (3);
00267         eigenvectors.coeffRef (0) = 1.0;
00268         eigenvectors.coeffRef (1) = 0.0;
00269         eigenvectors.coeffRef (2) = 0.0;
00270         eigenvectors.coeffRef (3) = 1.0;        
00271       }
00272       else
00273       {
00274         eigenvalues.coeffRef (0) = mat.coeff (3);
00275         eigenvalues.coeffRef (1) = mat.coeff (0);
00276         eigenvectors.coeffRef (0) = 0.0;
00277         eigenvectors.coeffRef (1) = 1.0;
00278         eigenvectors.coeffRef (2) = 1.0;
00279         eigenvectors.coeffRef (3) = 0.0;        
00280       }
00281       return;
00282     }
00283 
00284     // 0.5 to optimize further calculations
00285     typename Matrix::Scalar trace = static_cast<typename Matrix::Scalar> (0.5) * (mat.coeff (0) + mat.coeff (3));
00286     typename Matrix::Scalar determinant = mat.coeff (0) * mat.coeff (3) - mat.coeff (1) * mat.coeff (1);
00287 
00288     typename Matrix::Scalar temp = trace * trace - determinant;
00289 
00290     if (temp < 0)
00291       temp = 0;
00292     else
00293       temp = sqrt (temp);
00294 
00295     eigenvalues.coeffRef (0) = trace - temp;
00296     eigenvalues.coeffRef (1) = trace + temp;
00297 
00298     // either this is in a row or column depending on RowMajor or ColumnMajor
00299     eigenvectors.coeffRef (0) = - mat.coeff (1);
00300     eigenvectors.coeffRef (2) = mat.coeff (0) - eigenvalues.coeff (0);
00301     typename Matrix::Scalar norm = static_cast<typename Matrix::Scalar> (1.0) / 
00302                                    static_cast<typename Matrix::Scalar> (sqrt (eigenvectors.coeffRef (0) * eigenvectors.coeffRef (0) + eigenvectors.coeffRef (2) * eigenvectors.coeffRef (2)));
00303     eigenvectors.coeffRef (0) *= norm;
00304     eigenvectors.coeffRef (2) *= norm;
00305     eigenvectors.coeffRef (1) = eigenvectors.coeffRef (2);
00306     eigenvectors.coeffRef (3) = -eigenvectors.coeffRef (0);
00307   }
00308 
00315   template<typename Matrix, typename Vector> inline void
00316   computeCorrespondingEigenVector (const Matrix& mat, const typename Matrix::Scalar& eigenvalue, Vector& eigenvector)
00317   {
00318     typedef typename Matrix::Scalar Scalar;
00319     // Scale the matrix so its entries are in [-1,1].  The scaling is applied
00320     // only when at least one matrix entry has magnitude larger than 1.
00321 
00322     Scalar scale = mat.cwiseAbs ().maxCoeff ();
00323     if (scale <= std::numeric_limits<Scalar>::min ())
00324       scale = Scalar (1.0);
00325 
00326     Matrix scaledMat = mat / scale;
00327 
00328     scaledMat.diagonal ().array () -= eigenvalue / scale;
00329 
00330     Vector vec1 = scaledMat.row (0).cross (scaledMat.row (1));
00331     Vector vec2 = scaledMat.row (0).cross (scaledMat.row (2));
00332     Vector vec3 = scaledMat.row (1).cross (scaledMat.row (2));
00333 
00334     Scalar len1 = vec1.squaredNorm ();
00335     Scalar len2 = vec2.squaredNorm ();
00336     Scalar len3 = vec3.squaredNorm ();
00337 
00338     if (len1 >= len2 && len1 >= len3)
00339       eigenvector = vec1 / Eigen::internal::sqrt (len1);
00340     else if (len2 >= len1 && len2 >= len3)
00341       eigenvector = vec2 / Eigen::internal::sqrt (len2);
00342     else
00343       eigenvector = vec3 / Eigen::internal::sqrt (len3);
00344   }
00345   
00353   template<typename Matrix, typename Vector> inline void
00354   eigen33 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenvector)
00355   {
00356     typedef typename Matrix::Scalar Scalar;
00357     // Scale the matrix so its entries are in [-1,1].  The scaling is applied
00358     // only when at least one matrix entry has magnitude larger than 1.
00359 
00360     Scalar scale = mat.cwiseAbs ().maxCoeff ();
00361     if (scale <= std::numeric_limits<Scalar>::min ())
00362       scale = Scalar (1.0);
00363 
00364     Matrix scaledMat = mat / scale;
00365 
00366     Vector eigenvalues;
00367     computeRoots (scaledMat, eigenvalues);
00368 
00369     eigenvalue = eigenvalues (0) * scale;
00370 
00371     scaledMat.diagonal ().array () -= eigenvalues (0);
00372 
00373     Vector vec1 = scaledMat.row (0).cross (scaledMat.row (1));
00374     Vector vec2 = scaledMat.row (0).cross (scaledMat.row (2));
00375     Vector vec3 = scaledMat.row (1).cross (scaledMat.row (2));
00376 
00377     Scalar len1 = vec1.squaredNorm ();
00378     Scalar len2 = vec2.squaredNorm ();
00379     Scalar len3 = vec3.squaredNorm ();
00380 
00381     if (len1 >= len2 && len1 >= len3)
00382       eigenvector = vec1 / Eigen::internal::sqrt (len1);
00383     else if (len2 >= len1 && len2 >= len3)
00384       eigenvector = vec2 / Eigen::internal::sqrt (len2);
00385     else
00386       eigenvector = vec3 / Eigen::internal::sqrt (len3);
00387   }
00388 
00394   template<typename Matrix, typename Vector> inline void
00395   eigen33 (const Matrix& mat, Vector& evals)
00396   {
00397     typedef typename Matrix::Scalar Scalar;
00398     Scalar scale = mat.cwiseAbs ().maxCoeff ();
00399     if (scale <= std::numeric_limits<Scalar>::min ())
00400       scale = Scalar (1.0);
00401 
00402     Matrix scaledMat = mat / scale;
00403     computeRoots (scaledMat, evals);
00404     evals *= scale;
00405   }
00406 
00413   template<typename Matrix, typename Vector> inline void
00414   eigen33 (const Matrix& mat, Matrix& evecs, Vector& evals)
00415   {
00416     typedef typename Matrix::Scalar Scalar;
00417     // Scale the matrix so its entries are in [-1,1].  The scaling is applied
00418     // only when at least one matrix entry has magnitude larger than 1.
00419 
00420     Scalar scale = mat.cwiseAbs ().maxCoeff ();
00421     if (scale <= std::numeric_limits<Scalar>::min ())
00422       scale = Scalar (1.0);
00423 
00424     Matrix scaledMat = mat / scale;
00425 
00426     // Compute the eigenvalues
00427     computeRoots (scaledMat, evals);
00428 
00429     if ((evals (2) - evals (0)) <= Eigen::NumTraits<Scalar>::epsilon ())
00430     {
00431       // all three equal
00432       evecs.setIdentity ();
00433     }
00434     else if ((evals (1) - evals (0)) <= Eigen::NumTraits<Scalar>::epsilon () )
00435     {
00436       // first and second equal
00437       Matrix tmp;
00438       tmp = scaledMat;
00439       tmp.diagonal ().array () -= evals (2);
00440 
00441       Vector vec1 = tmp.row (0).cross (tmp.row (1));
00442       Vector vec2 = tmp.row (0).cross (tmp.row (2));
00443       Vector vec3 = tmp.row (1).cross (tmp.row (2));
00444 
00445       Scalar len1 = vec1.squaredNorm ();
00446       Scalar len2 = vec2.squaredNorm ();
00447       Scalar len3 = vec3.squaredNorm ();
00448 
00449       if (len1 >= len2 && len1 >= len3)
00450         evecs.col (2) = vec1 / Eigen::internal::sqrt (len1);
00451       else if (len2 >= len1 && len2 >= len3)
00452         evecs.col (2) = vec2 / Eigen::internal::sqrt (len2);
00453       else
00454         evecs.col (2) = vec3 / Eigen::internal::sqrt (len3);
00455 
00456       evecs.col (1) = evecs.col (2).unitOrthogonal ();
00457       evecs.col (0) = evecs.col (1).cross (evecs.col (2));
00458     }
00459     else if ((evals (2) - evals (1)) <= Eigen::NumTraits<Scalar>::epsilon () )
00460     {
00461       // second and third equal
00462       Matrix tmp;
00463       tmp = scaledMat;
00464       tmp.diagonal ().array () -= evals (0);
00465 
00466       Vector vec1 = tmp.row (0).cross (tmp.row (1));
00467       Vector vec2 = tmp.row (0).cross (tmp.row (2));
00468       Vector vec3 = tmp.row (1).cross (tmp.row (2));
00469 
00470       Scalar len1 = vec1.squaredNorm ();
00471       Scalar len2 = vec2.squaredNorm ();
00472       Scalar len3 = vec3.squaredNorm ();
00473 
00474       if (len1 >= len2 && len1 >= len3)
00475         evecs.col (0) = vec1 / Eigen::internal::sqrt (len1);
00476       else if (len2 >= len1 && len2 >= len3)
00477         evecs.col (0) = vec2 / Eigen::internal::sqrt (len2);
00478       else
00479         evecs.col (0) = vec3 / Eigen::internal::sqrt (len3);
00480 
00481       evecs.col (1) = evecs.col (0).unitOrthogonal ();
00482       evecs.col (2) = evecs.col (0).cross (evecs.col (1));
00483     }
00484     else
00485     {
00486       Matrix tmp;
00487       tmp = scaledMat;
00488       tmp.diagonal ().array () -= evals (2);
00489 
00490       Vector vec1 = tmp.row (0).cross (tmp.row (1));
00491       Vector vec2 = tmp.row (0).cross (tmp.row (2));
00492       Vector vec3 = tmp.row (1).cross (tmp.row (2));
00493 
00494       Scalar len1 = vec1.squaredNorm ();
00495       Scalar len2 = vec2.squaredNorm ();
00496       Scalar len3 = vec3.squaredNorm ();
00497 #ifdef _WIN32
00498       Scalar *mmax = new Scalar[3];
00499 #else
00500       Scalar mmax[3];
00501 #endif
00502       unsigned int min_el = 2;
00503       unsigned int max_el = 2;
00504       if (len1 >= len2 && len1 >= len3)
00505       {
00506         mmax[2] = len1;
00507         evecs.col (2) = vec1 / Eigen::internal::sqrt (len1);
00508       }
00509       else if (len2 >= len1 && len2 >= len3)
00510       {
00511         mmax[2] = len2;
00512         evecs.col (2) = vec2 / Eigen::internal::sqrt (len2);
00513       }
00514       else
00515       {
00516         mmax[2] = len3;
00517         evecs.col (2) = vec3 / Eigen::internal::sqrt (len3);
00518       }
00519 
00520       tmp = scaledMat;
00521       tmp.diagonal ().array () -= evals (1);
00522 
00523       vec1 = tmp.row (0).cross (tmp.row (1));
00524       vec2 = tmp.row (0).cross (tmp.row (2));
00525       vec3 = tmp.row (1).cross (tmp.row (2));
00526 
00527       len1 = vec1.squaredNorm ();
00528       len2 = vec2.squaredNorm ();
00529       len3 = vec3.squaredNorm ();
00530       if (len1 >= len2 && len1 >= len3)
00531       {
00532         mmax[1] = len1;
00533         evecs.col (1) = vec1 / Eigen::internal::sqrt (len1);
00534         min_el = len1 <= mmax[min_el] ? 1 : min_el;
00535         max_el = len1 > mmax[max_el] ? 1 : max_el;
00536       }
00537       else if (len2 >= len1 && len2 >= len3)
00538       {
00539         mmax[1] = len2;
00540         evecs.col (1) = vec2 / Eigen::internal::sqrt (len2);
00541         min_el = len2 <= mmax[min_el] ? 1 : min_el;
00542         max_el = len2 > mmax[max_el] ? 1 : max_el;
00543       }
00544       else
00545       {
00546         mmax[1] = len3;
00547         evecs.col (1) = vec3 / Eigen::internal::sqrt (len3);
00548         min_el = len3 <= mmax[min_el] ? 1 : min_el;
00549         max_el = len3 > mmax[max_el] ? 1 : max_el;
00550       }
00551 
00552       tmp = scaledMat;
00553       tmp.diagonal ().array () -= evals (0);
00554 
00555       vec1 = tmp.row (0).cross (tmp.row (1));
00556       vec2 = tmp.row (0).cross (tmp.row (2));
00557       vec3 = tmp.row (1).cross (tmp.row (2));
00558 
00559       len1 = vec1.squaredNorm ();
00560       len2 = vec2.squaredNorm ();
00561       len3 = vec3.squaredNorm ();
00562       if (len1 >= len2 && len1 >= len3)
00563       {
00564         mmax[0] = len1;
00565         evecs.col (0) = vec1 / Eigen::internal::sqrt (len1);
00566         min_el = len3 <= mmax[min_el] ? 0 : min_el;
00567         max_el = len3 > mmax[max_el] ? 0 : max_el;
00568       }
00569       else if (len2 >= len1 && len2 >= len3)
00570       {
00571         mmax[0] = len2;
00572         evecs.col (0) = vec2 / Eigen::internal::sqrt (len2);
00573         min_el = len3 <= mmax[min_el] ? 0 : min_el;
00574         max_el = len3 > mmax[max_el] ? 0 : max_el;
00575       }
00576       else
00577       {
00578         mmax[0] = len3;
00579         evecs.col (0) = vec3 / Eigen::internal::sqrt (len3);
00580         min_el = len3 <= mmax[min_el] ? 0 : min_el;
00581         max_el = len3 > mmax[max_el] ? 0 : max_el;
00582       }
00583 
00584       unsigned mid_el = 3 - min_el - max_el;
00585       evecs.col (min_el) = evecs.col ((min_el + 1) % 3).cross ( evecs.col ((min_el + 2) % 3) ).normalized ();
00586       evecs.col (mid_el) = evecs.col ((mid_el + 1) % 3).cross ( evecs.col ((mid_el + 2) % 3) ).normalized ();
00587 #ifdef _WIN32
00588       delete [] mmax;
00589 #endif
00590     }
00591     // Rescale back to the original size.
00592     evals *= scale;
00593   }
00594 
00602   template<typename Matrix> inline typename Matrix::Scalar
00603   invert2x2 (const Matrix& matrix, Matrix& inverse)
00604   {
00605     typedef typename Matrix::Scalar Scalar;
00606     Scalar det = matrix.coeff (0) * matrix.coeff (3) - matrix.coeff (1) * matrix.coeff (2) ;
00607 
00608     if (det != 0)
00609     {
00610       //Scalar inv_det = Scalar (1.0) / det;
00611       inverse.coeffRef (0) =   matrix.coeff (3);
00612       inverse.coeffRef (1) = - matrix.coeff (1);
00613       inverse.coeffRef (2) = - matrix.coeff (2);
00614       inverse.coeffRef (3) =   matrix.coeff (0);
00615       inverse /= det;
00616     }
00617     return det;
00618   }
00619 
00627   template<typename Matrix> inline typename Matrix::Scalar
00628   invert3x3SymMatrix (const Matrix& matrix, Matrix& inverse)
00629   {
00630     typedef typename Matrix::Scalar Scalar;
00631     // elements
00632     // a b c
00633     // b d e
00634     // c e f
00635     //| a b c |-1             |   fd-ee    ce-bf   be-cd  |
00636     //| b d e |    =  1/det * |   ce-bf    af-cc   bc-ae  |
00637     //| c e f |               |   be-cd    bc-ae   ad-bb  |
00638 
00639     //det = a(fd-ee) + b(ec-fb) + c(eb-dc)
00640 
00641     Scalar fd_ee = matrix.coeff (4) * matrix.coeff (8) - matrix.coeff (7) * matrix.coeff (5);
00642     Scalar ce_bf = matrix.coeff (2) * matrix.coeff (5) - matrix.coeff (1) * matrix.coeff (8);
00643     Scalar be_cd = matrix.coeff (1) * matrix.coeff (5) - matrix.coeff (2) * matrix.coeff (4);
00644 
00645     Scalar det = matrix.coeff (0) * fd_ee + matrix.coeff (1) * ce_bf + matrix.coeff (2) * be_cd;
00646 
00647     if (det != 0)
00648     {
00649       //Scalar inv_det = Scalar (1.0) / det;
00650       inverse.coeffRef (0) = fd_ee;
00651       inverse.coeffRef (1) = inverse.coeffRef (3) = ce_bf;
00652       inverse.coeffRef (2) = inverse.coeffRef (6) = be_cd;
00653       inverse.coeffRef (4) = (matrix.coeff (0) * matrix.coeff (8) - matrix.coeff (2) * matrix.coeff (2));
00654       inverse.coeffRef (5) = inverse.coeffRef (7) = (matrix.coeff (1) * matrix.coeff (2) - matrix.coeff (0) * matrix.coeff (5));
00655       inverse.coeffRef (8) = (matrix.coeff (0) * matrix.coeff (4) - matrix.coeff (1) * matrix.coeff (1));
00656       inverse /= det;
00657     }
00658     return det;
00659   }
00660 
00667   template<typename Matrix> inline typename Matrix::Scalar
00668   invert3x3Matrix (const Matrix& matrix, Matrix& inverse)
00669   {
00670     typedef typename Matrix::Scalar Scalar;
00671 
00672     //| a b c |-1             |   ie-hf    hc-ib   fb-ec  |
00673     //| d e f |    =  1/det * |   gf-id    ia-gc   dc-fa  |
00674     //| g h i |               |   hd-ge    gb-ha   ea-db  |
00675     //det = a(ie-hf) + d(hc-ib) + g(fb-ec)
00676 
00677     Scalar ie_hf = matrix.coeff (8) * matrix.coeff (4) - matrix.coeff (7) * matrix.coeff (5);
00678     Scalar hc_ib = matrix.coeff (7) * matrix.coeff (2) - matrix.coeff (8) * matrix.coeff (1);
00679     Scalar fb_ec = matrix.coeff (5) * matrix.coeff (1) - matrix.coeff (4) * matrix.coeff (2);
00680     Scalar det = matrix.coeff (0) * (ie_hf) + matrix.coeff (3) * (hc_ib) + matrix.coeff (6) * (fb_ec) ;
00681 
00682     if (det != 0)
00683     {
00684       inverse.coeffRef (0) = ie_hf;
00685       inverse.coeffRef (1) = hc_ib;
00686       inverse.coeffRef (2) = fb_ec;
00687       inverse.coeffRef (3) = matrix.coeff (6) * matrix.coeff (5) - matrix.coeff (8) * matrix.coeff (3);
00688       inverse.coeffRef (4) = matrix.coeff (8) * matrix.coeff (0) - matrix.coeff (6) * matrix.coeff (2);
00689       inverse.coeffRef (5) = matrix.coeff (3) * matrix.coeff (2) - matrix.coeff (5) * matrix.coeff (0);
00690       inverse.coeffRef (6) = matrix.coeff (7) * matrix.coeff (3) - matrix.coeff (6) * matrix.coeff (4);
00691       inverse.coeffRef (7) = matrix.coeff (6) * matrix.coeff (1) - matrix.coeff (7) * matrix.coeff (0);
00692       inverse.coeffRef (8) = matrix.coeff (4) * matrix.coeff (0) - matrix.coeff (3) * matrix.coeff (1);
00693 
00694       inverse /= det;
00695     }
00696     return det;
00697   }
00698 
00699   template<typename Matrix> inline typename Matrix::Scalar
00700   determinant3x3Matrix (const Matrix& matrix)
00701   {
00702     // result is independent of Row/Col Major storage!
00703     return matrix.coeff (0) * (matrix.coeff (4) * matrix.coeff (8) - matrix.coeff (5) * matrix.coeff (7)) +
00704            matrix.coeff (1) * (matrix.coeff (5) * matrix.coeff (6) - matrix.coeff (3) * matrix.coeff (8)) +
00705            matrix.coeff (2) * (matrix.coeff (3) * matrix.coeff (7) - matrix.coeff (4) * matrix.coeff (6)) ;
00706   }
00707   
00715   inline void
00716   getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, const Eigen::Vector3f& y_direction,
00717                              Eigen::Affine3f& transformation);
00718 
00726   inline Eigen::Affine3f
00727   getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, const Eigen::Vector3f& y_direction);
00728 
00736   inline void
00737   getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, const Eigen::Vector3f& y_direction,
00738                              Eigen::Affine3f& transformation);
00739 
00747   inline Eigen::Affine3f
00748   getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, const Eigen::Vector3f& y_direction);
00749 
00757   inline void
00758   getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis,
00759                                        Eigen::Affine3f& transformation);
00760 
00768   inline Eigen::Affine3f
00769   getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis);
00770 
00779   inline void
00780   getTransformationFromTwoUnitVectorsAndOrigin (const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis,
00781                                                 const Eigen::Vector3f& origin, Eigen::Affine3f& transformation);
00782 
00790   inline void
00791   getEulerAngles (const Eigen::Affine3f& t, float& roll, float& pitch, float& yaw);
00792 
00803   inline void
00804   getTranslationAndEulerAngles (const Eigen::Affine3f& t, float& x, float& y, float& z,
00805                                 float& roll, float& pitch, float& yaw);
00806 
00817   inline void
00818   getTransformation (float x, float y, float z, float roll, float pitch, float yaw, Eigen::Affine3f& t);
00819 
00830   inline Eigen::Affine3f
00831   getTransformation (float x, float y, float z, float roll, float pitch, float yaw);
00832 
00838   template <typename Derived> void
00839   saveBinary (const Eigen::MatrixBase<Derived>& matrix, std::ostream& file);
00840 
00846   template <typename Derived> void
00847   loadBinary (Eigen::MatrixBase<Derived> const& matrix, std::istream& file);
00848 }
00849 
00850 #include <pcl/common/impl/eigen.hpp>
00851 
00852 #if defined __SUNPRO_CC
00853 #  pragma enable_warn
00854 #elif defined _MSC_VER
00855 #  pragma warning(pop)
00856 #endif
00857 
00858 #endif  //#ifndef PCL_EIGEN_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:49