test_eigen.cpp
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  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: test_feature.cpp 3564 2011-12-16 06:11:13Z rusu $
00037  *
00038  */
00039 
00040 #include <gtest/gtest.h>
00041 #include <pcl/point_types.h>
00042 #include <pcl/common/eigen.h>
00043 #include "boost.h"
00044 
00045 using namespace pcl;
00046 using namespace std;
00047 
00048 boost::variate_generator< boost::mt19937, boost::uniform_real<double> > rand_double(boost::mt19937 (), boost::uniform_real<double> (0, 1));
00049 boost::variate_generator< boost::mt19937, boost::uniform_int<unsigned> > rand_uint(boost::mt19937 (), boost::uniform_int<unsigned> (0, 100));
00050 
00052 TEST (PCL, InverseGeneral3x3f)
00053 {
00054   typedef float Scalar;
00055   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor> RMatrix;
00056   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::ColMajor> CMatrix;
00057   RMatrix r_matrix = RMatrix::Zero ();
00058   RMatrix r_inverse = RMatrix::Zero ();
00059   CMatrix c_matrix = CMatrix::Zero ();
00060   CMatrix c_inverse = CMatrix::Zero ();
00061   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00062   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00063   Scalar determinant;
00064   const Scalar epsilon = 1e-5f;
00065   const unsigned iterations = 1000000;
00066 
00067   // test floating point row-major : row-major
00068   for (unsigned idx = 0; idx < iterations; ++idx)
00069   {
00070     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
00071       r_matrix.coeffRef (elIdx) = Scalar(rand_double ());
00072 
00073     c_matrix = r_matrix;
00074 
00075     // test row-major -> row-major
00076     determinant = invert3x3Matrix (r_matrix, r_inverse);
00077     if (fabs (determinant) > epsilon)
00078     {
00079       float eps = std::max (epsilon, epsilon / fabs(determinant));
00080 
00081       result = r_inverse * r_matrix;
00082       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00083       Scalar distance = error.cwiseAbs ().sum ();
00084       EXPECT_LE (distance, eps);
00085 
00086       result = r_matrix * r_inverse;
00087       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00088       distance = error.cwiseAbs ().sum ();
00089       EXPECT_LE (distance, eps);
00090     }
00091 
00092     // test row-major -> col-major
00093     determinant = invert3x3Matrix (c_matrix, c_inverse);
00094     if (fabs (determinant) > epsilon)
00095     {
00096       Scalar eps = std::max (epsilon, epsilon / fabs(determinant));
00097 
00098       result = c_inverse * c_matrix;
00099       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00100       Scalar distance = error.cwiseAbs ().sum ();
00101       EXPECT_LE (distance, eps);
00102 
00103       result = c_matrix * c_inverse;
00104       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00105       distance = error.cwiseAbs ().sum ();
00106       EXPECT_LE (distance, eps);
00107     }
00108   }
00109 }
00110 
00112 TEST (PCL, InverseGeneral3x3d)
00113 {
00114   typedef double Scalar;
00115   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor> RMatrix;
00116   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::ColMajor> CMatrix;
00117   RMatrix r_matrix = RMatrix::Zero ();
00118   RMatrix r_inverse = RMatrix::Zero ();
00119   CMatrix c_matrix = CMatrix::Zero ();
00120   CMatrix c_inverse = CMatrix::Zero ();
00121   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00122   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00123   Scalar determinant;
00124   const Scalar epsilon = 1e-13;
00125   const unsigned iterations = 1000000;
00126 
00127   // test floating point row-major : row-major
00128   for (unsigned idx = 0; idx < iterations; ++idx)
00129   {
00130     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
00131     {
00132       r_matrix.coeffRef (elIdx) = Scalar(rand_double ());
00133     }
00134     c_matrix = r_matrix;
00135     // test row-major -> row-major
00136     determinant = invert3x3Matrix (r_matrix, r_inverse);
00137     if (fabs (determinant) > epsilon)
00138     {
00139       Scalar eps = std::max (epsilon, epsilon / fabs (determinant));
00140 
00141       result = r_inverse * r_matrix;
00142       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00143       Scalar distance = error.cwiseAbs ().sum ();
00144       EXPECT_LE (distance, eps);
00145 
00146       result = r_matrix * r_inverse;
00147       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00148       distance = error.cwiseAbs ().sum ();
00149       EXPECT_LE (distance, eps);
00150     }
00151 
00152     // test row-major -> col-major
00153     determinant = invert3x3Matrix (c_matrix, c_inverse);
00154     if (fabs (determinant) > epsilon)
00155     {
00156       Scalar eps = std::max (epsilon, epsilon / fabs(determinant));
00157 
00158       result = c_inverse * c_matrix;
00159       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00160       Scalar distance = error.cwiseAbs ().sum ();
00161       EXPECT_LE (distance, eps);
00162 
00163       result = c_matrix * c_inverse;
00164       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00165       distance = error.cwiseAbs ().sum ();
00166       EXPECT_LE (distance, eps);
00167     }
00168   }
00169 }
00170 
00172 TEST (PCL, InverseSymmetric3x3f)
00173 {
00174   typedef float Scalar;
00175   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor> RMatrix;
00176   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::ColMajor> CMatrix;
00177   RMatrix r_matrix = RMatrix::Zero ();
00178   RMatrix r_inverse = RMatrix::Zero ();
00179   CMatrix c_matrix = CMatrix::Zero ();
00180   CMatrix c_inverse = CMatrix::Zero ();
00181   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00182   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00183   Scalar determinant;
00184   const Scalar epsilon = 1e-5f;
00185   const unsigned iterations = 1000000;
00186 
00187   // test floating point row-major : row-major
00188   for (unsigned idx = 0; idx < iterations; ++idx)
00189   {
00190     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
00191       r_matrix.coeffRef (elIdx) = Scalar(rand_double ());
00192 
00193     r_matrix.coeffRef (3) = r_matrix.coeffRef (1);
00194     r_matrix.coeffRef (6) = r_matrix.coeffRef (2);
00195     r_matrix.coeffRef (7) = r_matrix.coeffRef (5);
00196     c_matrix = r_matrix;
00197 //    c_matrix.coeffRef (3) = c_matrix.coeffRef (1);
00198 //    c_matrix.coeffRef (6) = c_matrix.coeffRef (2);
00199 //    c_matrix.coeffRef (7) = c_matrix.coeffRef (5);
00200 
00201     // test row-major -> row-major
00202     determinant = invert3x3SymMatrix (r_matrix, r_inverse);
00203     if (fabs (determinant) > epsilon)
00204     {
00205       float eps = std::max (epsilon, epsilon / fabs(determinant));
00206 
00207       result = r_inverse * r_matrix;
00208       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00209       Scalar distance = error.cwiseAbs ().sum ();
00210       EXPECT_LE (distance, eps);
00211 
00212       result = r_matrix * r_inverse;
00213       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00214       distance = error.cwiseAbs ().sum ();
00215       EXPECT_LE (distance, eps);
00216     }
00217 
00218     // test row-major -> col-major
00219     determinant = invert3x3SymMatrix (c_matrix, c_inverse);
00220     if (fabs (determinant) > epsilon)
00221     {
00222       Scalar eps = std::max (epsilon, epsilon / fabs(determinant));
00223 
00224       result = c_inverse * c_matrix;
00225       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00226       Scalar distance = error.cwiseAbs ().sum ();
00227       EXPECT_LE (distance, eps);
00228 
00229       result = c_matrix * c_inverse;
00230       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00231       distance = error.cwiseAbs ().sum ();
00232       EXPECT_LE (distance, eps);
00233     }
00234   }
00235 }
00236 
00238 TEST (PCL, InverseSymmetric3x3d)
00239 {
00240   typedef double Scalar;
00241   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor> RMatrix;
00242   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::ColMajor> CMatrix;
00243   RMatrix r_matrix = RMatrix::Zero ();
00244   RMatrix r_inverse = RMatrix::Zero ();
00245   CMatrix c_matrix = CMatrix::Zero ();
00246   CMatrix c_inverse = CMatrix::Zero ();
00247   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00248   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
00249   Scalar determinant;
00250   const Scalar epsilon = 1e-13;
00251   const unsigned iterations = 1000000;
00252 
00253   // test floating point row-major : row-major
00254   for (unsigned idx = 0; idx < iterations; ++idx)
00255   {
00256     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
00257       r_matrix.coeffRef (elIdx) = Scalar(rand_double ());
00258 
00259     r_matrix.coeffRef (3) = r_matrix.coeffRef (1);
00260     r_matrix.coeffRef (6) = r_matrix.coeffRef (2);
00261     r_matrix.coeffRef (7) = r_matrix.coeffRef (5);
00262     c_matrix = r_matrix;
00263 //    c_matrix.coeffRef (3) = c_matrix.coeffRef (1);
00264 //    c_matrix.coeffRef (6) = c_matrix.coeffRef (2);
00265 //    c_matrix.coeffRef (7) = c_matrix.coeffRef (5);
00266 
00267     // test row-major -> row-major
00268     determinant = invert3x3SymMatrix (r_matrix, r_inverse);
00269     if (fabs (determinant) > epsilon)
00270     {
00271       Scalar eps = std::max (epsilon, epsilon / fabs (determinant));
00272 
00273       result = r_inverse * r_matrix;
00274       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00275       Scalar distance = error.cwiseAbs ().sum ();
00276       EXPECT_LE (distance, eps);
00277 
00278       result = r_matrix * r_inverse;
00279       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00280       distance = error.cwiseAbs ().sum ();
00281       EXPECT_LE (distance, eps);
00282     }
00283 
00284     // test row-major -> col-major
00285     determinant = invert3x3SymMatrix (c_matrix, c_inverse);
00286     if (fabs (determinant) > epsilon)
00287     {
00288       Scalar eps = std::max (epsilon, epsilon / fabs(determinant));
00289 
00290       result = c_inverse * c_matrix;
00291       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00292       Scalar distance = error.cwiseAbs ().sum ();
00293       EXPECT_LE (distance, eps);
00294 
00295       result = c_matrix * c_inverse;
00296       error = result - Eigen::Matrix<Scalar, 3, 3>::Identity ();
00297       distance = error.cwiseAbs ().sum ();
00298       EXPECT_LE (distance, eps);
00299     }
00300   }
00301 }
00302 
00303 
00305 TEST (PCL, Inverse2x2f)
00306 {
00307   typedef float Scalar;
00308   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::RowMajor> RMatrix;
00309   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::ColMajor> CMatrix;
00310   RMatrix r_matrix = RMatrix::Zero ();
00311   RMatrix r_inverse = RMatrix::Zero ();
00312   CMatrix c_matrix = CMatrix::Zero ();
00313   CMatrix c_inverse = CMatrix::Zero ();
00314   Eigen::Matrix<Scalar, 2, 2> result = Eigen::Matrix<Scalar, 2, 2>::Zero ();
00315   Eigen::Matrix<Scalar, 2, 2> error = Eigen::Matrix<Scalar, 2, 2>::Zero ();
00316   Scalar determinant;
00317   const Scalar epsilon = 1e-6f;
00318   const unsigned iterations = 1000000;
00319 
00320   // test floating point row-major : row-major
00321   for (unsigned idx = 0; idx < iterations; ++idx)
00322   {
00323     for (unsigned elIdx = 0; elIdx < 4; ++elIdx)
00324       r_matrix.coeffRef (elIdx) = Scalar(rand_double ());
00325 
00326     c_matrix = r_matrix;
00327     // test row-major -> row-major
00328     determinant = invert2x2 (r_matrix, r_inverse);
00329     if (fabs (determinant) > epsilon)
00330     {
00331       float eps = std::max (epsilon, epsilon / fabs(determinant));
00332 
00333       result = r_inverse * r_matrix;
00334       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00335       Scalar distance = error.cwiseAbs ().sum ();
00336       EXPECT_LE (distance, eps);
00337 
00338       result = r_matrix * r_inverse;
00339       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00340       distance = error.cwiseAbs ().sum ();
00341       EXPECT_LE (distance, eps);
00342     }
00343 
00344     // test row-major -> col-major
00345     determinant = invert2x2 (c_matrix, c_inverse);
00346     if (fabs (determinant) > epsilon)
00347     {
00348       Scalar eps = std::max (epsilon, epsilon / fabs(determinant));
00349 
00350       result = c_inverse * c_matrix;
00351       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00352       Scalar distance = error.cwiseAbs ().sum ();
00353       EXPECT_LE (distance, eps);
00354 
00355       result = c_matrix * c_inverse;
00356       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00357       distance = error.cwiseAbs ().sum ();
00358       EXPECT_LE (distance, eps);
00359     }
00360   }
00361 }
00362 
00364 TEST (PCL, Inverse2x2d)
00365 {
00366   typedef double Scalar;
00367   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::RowMajor> RMatrix;
00368   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::ColMajor> CMatrix;
00369   RMatrix r_matrix = RMatrix::Zero ();
00370   RMatrix r_inverse = RMatrix::Zero ();
00371   CMatrix c_matrix = CMatrix::Zero ();
00372   CMatrix c_inverse = CMatrix::Zero ();
00373   Eigen::Matrix<Scalar, 2, 2> result;
00374   Eigen::Matrix<Scalar, 2, 2> error;
00375   Scalar determinant;
00376   const Scalar epsilon = 1e-15;
00377   const unsigned iterations = 1000000;
00378 
00379   // test floating point row-major : row-major
00380   for (unsigned idx = 0; idx < iterations; ++idx)
00381   {
00382     for (unsigned elIdx = 0; elIdx < 4; ++elIdx)
00383       r_matrix.coeffRef (elIdx) = Scalar(rand_double ());
00384 
00385     c_matrix = r_matrix;
00386     // test row-major -> row-major
00387     determinant = invert2x2 (r_matrix, r_inverse);
00388     if (fabs (determinant) > epsilon)
00389     {
00390       Scalar eps = std::max (epsilon, epsilon / fabs (determinant));
00391 
00392       result = r_inverse * r_matrix;
00393       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00394       Scalar distance = error.cwiseAbs ().sum ();
00395       EXPECT_LE (distance, eps);
00396 
00397       result = r_matrix * r_inverse;
00398       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00399       distance = error.cwiseAbs ().sum ();
00400       EXPECT_LE (distance, eps);
00401     }
00402 
00403     // test row-major -> col-major
00404     determinant = invert2x2 (c_matrix, c_inverse);
00405     if (fabs (determinant) > epsilon)
00406     {
00407       Scalar eps = std::max (epsilon, epsilon / fabs(determinant));
00408 
00409       result = c_inverse * c_matrix;
00410       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00411       Scalar distance = error.cwiseAbs ().sum ();
00412       EXPECT_LE (distance, eps);
00413 
00414       result = c_matrix * c_inverse;
00415       error = result - Eigen::Matrix<Scalar, 2, 2>::Identity ();
00416       distance = error.cwiseAbs ().sum ();
00417       EXPECT_LE (distance, eps);
00418     }
00419   }
00420 }
00421 
00422 template<class Matrix>
00423 inline void generateSymPosMatrix2x2 (Matrix& matrix)
00424 {
00425   typedef typename Matrix::Scalar Scalar;
00426 
00427   unsigned test_case = rand_uint () % 10;
00428 
00429         Scalar val1 = Scalar (rand_double ());
00430         Scalar val2 = Scalar (rand_double ());
00431 
00432   // 10% of test cases include equal eigenvalues
00433   if (test_case == 0)
00434     val2 = val1;
00435   // another 20% includes one zero eigenvalue
00436   else if (test_case == 1 && val1 != 0)
00437     val2 = 0.0;
00438   else if (test_case == 2 && val2 != 0)
00439     val1 = 0.0;
00440 
00441   Scalar sqrNorm;
00442   Matrix eigenvectors = Matrix::Identity ();
00443   Matrix eigenvalues = Matrix::Zero ();
00444 
00445   unsigned test_case2 = rand_uint () % 10;
00446   if (test_case2 != 0)
00447   {
00448     do
00449     {
00450       eigenvectors.col (0)[0] = Scalar (rand_double ());
00451       eigenvectors.col (0)[1] = Scalar (rand_double ());
00452       sqrNorm = eigenvectors.col (0).squaredNorm ();
00453     } while (sqrNorm == 0);
00454     eigenvectors.col (0) /= sqrt (sqrNorm);
00455 
00456     eigenvectors.col (1)[0] = -eigenvectors.col (1)[1];
00457     eigenvectors.col (1)[1] =  eigenvectors.col (1)[0];
00458   }
00459   eigenvalues (0, 0) = val1;
00460   eigenvalues (1, 1) = val2;
00461         matrix = eigenvectors * eigenvalues * eigenvectors.adjoint();
00462 }
00463 
00465 TEST (PCL, eigen22d)
00466 {
00467   typedef double Scalar;
00468   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::RowMajor> RMatrix;
00469   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::ColMajor> CMatrix;
00470   RMatrix r_matrix;
00471   RMatrix r_vectors;
00472   Eigen::Matrix<Scalar, 2, 1> r_eigenvalues;
00473   Eigen::Matrix<Scalar, 2, 1> c_eigenvalues;
00474   CMatrix c_matrix;
00475   CMatrix c_vectors;
00476   Eigen::Matrix<Scalar, 2, 2> r_result;
00477   Eigen::Matrix<Scalar, 2, 2> r_error;
00478   Eigen::Matrix<Scalar, 2, 2> g_result;
00479   Eigen::Matrix<Scalar, 2, 2> g_error;
00480   Eigen::Matrix<Scalar, 2, 2> c_result;
00481   Eigen::Matrix<Scalar, 2, 2> c_error;
00482   Scalar diff;
00483 
00484   const Scalar epsilon = 1.25e-14;
00485   const unsigned iterations = 1000000;
00486 
00487   // test floating point row-major : row-major
00488   for (unsigned idx = 0; idx < iterations; ++idx)
00489   {
00490     // generate test matrices
00491     generateSymPosMatrix2x2 (r_matrix);
00492     c_matrix = r_matrix;
00493 
00494     // calculate the eigenvalue decomposition
00495     eigen22 (r_matrix, r_vectors, r_eigenvalues);
00496 
00497     // test if U * V * U^T = M
00498     r_result = r_vectors * r_eigenvalues.asDiagonal () * r_vectors.transpose ();
00499     r_error = r_result - r_matrix;
00500     diff = r_error.cwiseAbs (). sum ();
00501     EXPECT_LE (diff, epsilon);
00502 
00503     // test if the eigenvalues are orthonormal
00504     g_result = r_vectors * r_vectors.transpose ();
00505     g_error = g_result - RMatrix::Identity ();
00506     diff = g_error.cwiseAbs (). sum ();
00507     EXPECT_LE (diff, epsilon);
00508 
00509     // test if column major matrices are also calculated correctly
00510     eigen22 (c_matrix, c_vectors, c_eigenvalues);
00511     c_result = c_vectors * c_eigenvalues.asDiagonal () * c_vectors.transpose ();
00512     c_error = c_result - c_matrix;
00513     diff = c_error.cwiseAbs (). sum ();
00514     EXPECT_LE (diff, epsilon);
00515 
00516     g_result = c_vectors * c_vectors.transpose ();
00517     g_error = g_result - CMatrix::Identity ();
00518     diff = g_error.cwiseAbs (). sum ();
00519     EXPECT_LE (diff, epsilon);
00520   }
00521 }
00522 
00524 TEST (PCL, eigen22f)
00525 {
00526   typedef float Scalar;
00527   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::RowMajor> RMatrix;
00528   typedef Eigen::Matrix<Scalar, 2, 2, Eigen::ColMajor> CMatrix;
00529   RMatrix r_matrix;
00530   RMatrix r_vectors;
00531   Eigen::Matrix<Scalar, 2, 1> r_eigenvalues;
00532   Eigen::Matrix<Scalar, 2, 1> c_eigenvalues;
00533   CMatrix c_matrix;
00534   CMatrix c_vectors;
00535   Eigen::Matrix<Scalar, 2, 2> r_result;
00536   Eigen::Matrix<Scalar, 2, 2> r_error;
00537   Eigen::Matrix<Scalar, 2, 2> g_result;
00538   Eigen::Matrix<Scalar, 2, 2> g_error;
00539   Eigen::Matrix<Scalar, 2, 2> c_result;
00540   Eigen::Matrix<Scalar, 2, 2> c_error;
00541   Scalar diff;
00542 
00543   const Scalar epsilon = 3.1e-5f;
00544   const unsigned iterations = 1000000;
00545 
00546   // test floating point row-major : row-major
00547   for (unsigned idx = 0; idx < iterations; ++idx)
00548   {
00549     // generate test matrices
00550     generateSymPosMatrix2x2 (r_matrix);
00551     c_matrix = r_matrix;
00552 
00553     // calculate the eigenvalue decomposition
00554     eigen22 (r_matrix, r_vectors, r_eigenvalues);
00555 
00556     // test if U * V * U^T = M
00557     r_result = r_vectors * r_eigenvalues.asDiagonal () * r_vectors.transpose ();
00558     r_error = r_result - r_matrix;
00559     diff = r_error.cwiseAbs (). sum ();
00560     EXPECT_LE (diff, epsilon);
00561 
00562     // test if the eigenvalues are orthonormal
00563     g_result = r_vectors * r_vectors.transpose ();
00564     g_error = g_result - RMatrix::Identity ();
00565     diff = g_error.cwiseAbs (). sum ();
00566     EXPECT_LE (diff, epsilon);
00567 
00568     // test if column major matrices are also calculated correctly
00569     eigen22 (c_matrix, c_vectors, c_eigenvalues);
00570     c_result = c_vectors * c_eigenvalues.asDiagonal () * c_vectors.transpose ();
00571     c_error = c_result - c_matrix;
00572     diff = c_error.cwiseAbs (). sum ();
00573     EXPECT_LE (diff, epsilon);
00574 
00575     g_result = c_vectors * c_vectors.transpose ();
00576     g_error = g_result - CMatrix::Identity ();
00577     diff = g_error.cwiseAbs (). sum ();
00578     EXPECT_LE (diff, epsilon);
00579   }
00580 }
00581 
00583 
00584 template<class Matrix>
00585 inline void generateSymPosMatrix3x3 (Matrix& matrix)
00586 {
00587   typedef typename Matrix::Scalar Scalar;
00588 
00589   // 3 equal elements != 0
00590   // 2 equal elements none 0
00591   // 2 equal elements 1 0
00592   // 2 x 0 and 1x non 0
00593   // 1 x 0
00594   // anything
00595 
00596   unsigned test_case = rand_uint ();
00597 
00598         Scalar val1 = Scalar (rand_double ());
00599         Scalar val2 = Scalar (rand_double ());
00600         Scalar val3 = Scalar (rand_double ());
00601 
00602   // 1%: all three values are equal and non-zero
00603   if (test_case == 0)
00604   {
00605     if (val1 ==0)
00606       val1 = 1.0;
00607     val2 = val1;
00608     val3 = val1;
00609   }
00610   // 1%: 2 values are equal but none is set explicitely to 0
00611   else if (test_case == 1)
00612   {
00613     val2 = val3;
00614   }
00615   // 1%: 2 values equal and the third = 0
00616   else if (test_case == 2)
00617   {
00618     if (val1 == 0)
00619       val1 = 1.0;
00620     val2 = val1;
00621     val3 = 0.0;
00622   }
00623   // 1% 2 x 0 and 1x not-0
00624   else if (test_case == 3)
00625   {
00626     if (val1 == 0)
00627       val1 = 1.0;
00628     val2 = val3 = 0.0;
00629   }
00630   else if (test_case == 4)
00631   {
00632     val1 = 0.0;
00633   }
00634 
00635   Scalar sqrNorm;
00636   Matrix eigenvectors = Matrix::Zero ();
00637   Matrix eigenvalues = Matrix::Zero ();
00638 
00639   do
00640   {
00641     eigenvectors.col (0)[0] = Scalar (rand_double ());
00642     eigenvectors.col (0)[1] = Scalar (rand_double ());
00643     eigenvectors.col (0)[2] = Scalar (rand_double ());
00644     eigenvectors.col (1)[0] = Scalar (rand_double ());
00645     eigenvectors.col (1)[1] = Scalar (rand_double ());
00646     eigenvectors.col (1)[2] = Scalar (rand_double ());
00647     eigenvectors.col (2) = eigenvectors.col (0).cross (eigenvectors.col (1));
00648 
00649     sqrNorm = eigenvectors.col (2).squaredNorm ();
00650   } while (sqrNorm == 0);
00651 
00652   eigenvectors.col (0).normalize ();
00653   eigenvectors.col (2).normalize ();
00654   eigenvectors.col (1) = eigenvectors.col (2).cross (eigenvectors.col (0));
00655 
00656   eigenvalues (0, 0) = val1;
00657   eigenvalues (1, 1) = val2;
00658   eigenvalues (2, 2) = val3;
00659 
00660         matrix = eigenvectors * eigenvalues * eigenvectors.adjoint();
00661 }
00662 
00664 TEST (PCL, eigen33d)
00665 {
00666   typedef double Scalar;
00667   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor> RMatrix;
00668   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::ColMajor> CMatrix;
00669   RMatrix r_matrix;
00670   RMatrix r_vectors;
00671   Eigen::Matrix<Scalar, 3, 1> r_eigenvalues;
00672   Eigen::Matrix<Scalar, 3, 1> c_eigenvalues;
00673   CMatrix c_matrix;
00674   CMatrix c_vectors;
00675   Eigen::Matrix<Scalar, 3, 3> r_result;
00676   Eigen::Matrix<Scalar, 3, 3> r_error;
00677   Eigen::Matrix<Scalar, 3, 3> g_result;
00678   Eigen::Matrix<Scalar, 3, 3> g_error;
00679   Eigen::Matrix<Scalar, 3, 3> c_result;
00680   Eigen::Matrix<Scalar, 3, 3> c_error;
00681   Scalar diff;
00682 
00683   const Scalar epsilon = 2e-5;
00684   const unsigned iterations = 1000000;
00685 
00686   // test floating point row-major : row-major
00687   for (unsigned idx = 0; idx < iterations; ++idx)
00688   {
00689     // generate test matrices
00690     generateSymPosMatrix3x3 (r_matrix);
00691     c_matrix = r_matrix;
00692 
00693     // calculate the eigenvalue decomposition
00694     eigen33 (r_matrix, r_vectors, r_eigenvalues);
00695 
00696     // test if U * V * U^T = M
00697     r_result = r_vectors * r_eigenvalues.asDiagonal () * r_vectors.transpose ();
00698     r_error = r_result - r_matrix;
00699     diff = r_error.cwiseAbs (). sum ();
00700     EXPECT_LE (diff, epsilon);
00701 
00702     // test if the eigenvalues are orthonormal
00703     g_result = r_vectors * r_vectors.transpose ();
00704     g_error = g_result - RMatrix::Identity ();
00705     diff = g_error.cwiseAbs (). sum ();
00706     EXPECT_LE (diff, epsilon);
00707 
00708     // test if column major matrices are also calculated correctly
00709     eigen33 (c_matrix, c_vectors, c_eigenvalues);
00710     c_result = c_vectors * c_eigenvalues.asDiagonal () * c_vectors.transpose ();
00711     c_error = c_result - c_matrix;
00712     diff = c_error.cwiseAbs (). sum ();
00713     EXPECT_LE (diff, epsilon);
00714 
00715     g_result = c_vectors * c_vectors.transpose ();
00716     g_error = g_result - CMatrix::Identity ();
00717     diff = g_error.cwiseAbs (). sum ();
00718     EXPECT_LE (diff, epsilon);
00719   }
00720 }
00721 
00723 // since we use float in this test and some matrices are bad conditioned for the eigenvalue decomposition, we will have
00724 // some errors > 0.2 but less than 1% is > 1e-3 -> we will just check whether the failure rate is below 1%
00725 TEST (PCL, eigen33f)
00726 {
00727   typedef float Scalar;
00728   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor> RMatrix;
00729   typedef Eigen::Matrix<Scalar, 3, 3, Eigen::ColMajor> CMatrix;
00730   RMatrix r_matrix;
00731   RMatrix r_vectors;
00732   Eigen::Matrix<Scalar, 3, 1> r_eigenvalues;
00733   Eigen::Matrix<Scalar, 3, 1> c_eigenvalues;
00734   CMatrix c_matrix;
00735   CMatrix c_vectors;
00736   Eigen::Matrix<Scalar, 3, 3> r_result;
00737   Eigen::Matrix<Scalar, 3, 3> r_error;
00738   Eigen::Matrix<Scalar, 3, 3> g_result;
00739   Eigen::Matrix<Scalar, 3, 3> g_error;
00740   Eigen::Matrix<Scalar, 3, 3> c_result;
00741   Eigen::Matrix<Scalar, 3, 3> c_error;
00742   Scalar diff;
00743 
00744   const Scalar epsilon = 1e-3f;
00745   const unsigned iterations = 1000000;
00746   bool r_failed;
00747   bool c_failed;
00748   unsigned r_fail_count = 0;
00749   unsigned c_fail_count = 0;
00750 
00751   // test floating point row-major : row-major
00752   for (unsigned idx = 0; idx < iterations; ++idx)
00753   {
00754     r_failed = c_failed = false;
00755     // generate test matrices
00756     generateSymPosMatrix3x3 (r_matrix);
00757     c_matrix = r_matrix;
00758 
00759     // calculate the eigenvalue decomposition
00760     eigen33 (r_matrix, r_vectors, r_eigenvalues);
00761 
00762     // test if U * V * U^T = M
00763     r_result = r_vectors * r_eigenvalues.asDiagonal () * r_vectors.transpose ();
00764     r_error = r_result - r_matrix;
00765     diff = r_error.cwiseAbs (). sum ();
00766     if (diff > epsilon)
00767       r_failed = true;
00768 
00769     // test if the eigenvalues are orthonormal
00770     g_result = r_vectors * r_vectors.transpose ();
00771     g_error = g_result - RMatrix::Identity ();
00772     diff = g_error.cwiseAbs (). sum ();
00773     if (diff > epsilon)
00774       r_failed = true;
00775 
00776     if(r_failed)
00777       ++r_fail_count;
00778 
00779     // test if column major matrices are also calculated correctly
00780     eigen33 (c_matrix, c_vectors, c_eigenvalues);
00781     c_result = c_vectors * c_eigenvalues.asDiagonal () * c_vectors.transpose ();
00782     c_error = c_result - c_matrix;
00783     diff = c_error.cwiseAbs (). sum ();
00784     if (diff > epsilon)
00785       c_failed = true;
00786 
00787     g_result = c_vectors * c_vectors.transpose ();
00788     g_error = g_result - CMatrix::Identity ();
00789     diff = g_error.cwiseAbs (). sum ();
00790     if (diff > epsilon)
00791       c_failed = true;
00792 
00793     if(c_failed)
00794       ++c_fail_count;
00795   }
00796 
00797   // less than 1% failure rate
00798   EXPECT_LE (float(r_fail_count) / float(iterations), 0.01);
00799   EXPECT_LE (float(r_fail_count) / float(iterations), 0.01);
00800 }
00801 
00802 /* ---[ */
00803 int
00804 main (int argc, char** argv)
00805 {
00806   testing::InitGoogleTest (&argc, argv);
00807   return (RUN_ALL_TESTS ());
00808 }
00809 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:34:46