CovarianceSampling.cpp
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2018,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
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 copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 #include "CovarianceSampling.h"
00036 
00037 #include <vector>
00038 #include <list>
00039 #include <utility>
00040 #include <unordered_map>
00041 
00042 // Eigenvalues
00043 #include "Eigen/QR"
00044 #include "Eigen/Eigenvalues"
00045 
00046 // CovarianceSamplingDataPointsFilter
00047 template <typename T>
00048 CovarianceSamplingDataPointsFilter<T>::CovarianceSamplingDataPointsFilter(const Parameters& params) :
00049         PointMatcher<T>::DataPointsFilter("CovarianceSamplingDataPointsFilter", 
00050                 CovarianceSamplingDataPointsFilter::availableParameters(), params),
00051         nbSample{Parametrizable::get<std::size_t>("nbSample")}
00052 {
00053         try 
00054         {
00055                 const std::uint8_t tnm = this->template get<std::uint8_t>("torqueNorm");
00056                 normalizationMethod = TorqueNormMethod(tnm);
00057         }
00058         catch (const InvalidParameter& e) 
00059         {
00060                 normalizationMethod = TorqueNormMethod::Lavg;
00061         }
00062 }
00063 
00064 template <typename T>
00065 typename PointMatcher<T>::DataPoints
00066 CovarianceSamplingDataPointsFilter<T>::filter(const DataPoints& input)
00067 {
00068         DataPoints output(input);
00069         inPlaceFilter(output);
00070         return output;
00071 }
00072 
00073 template <typename T>
00074 void CovarianceSamplingDataPointsFilter<T>::inPlaceFilter(DataPoints& cloud)
00075 {       
00076         const std::size_t featDim(cloud.features.rows());
00077         assert(featDim == 4); //3D pts only
00078         
00079         //Check number of points
00080         const std::size_t nbPoints = cloud.getNbPoints();               
00081         if(nbSample >= nbPoints)
00082                 return;
00083         
00084         //Check if there is normals info
00085         if (!cloud.descriptorExists("normals"))
00086                 throw InvalidField("OrientNormalsDataPointsFilter: Error, cannot find normals in descriptors.");
00087 
00088         const auto& normals = cloud.getDescriptorViewByName("normals");
00089         
00090         std::vector<std::size_t> keepIndexes;
00091         keepIndexes.resize(nbSample);
00092         
00094         //A.1 and A.2 - Compute candidates
00095         std::vector<std::size_t> candidates ;
00096         candidates.resize(nbPoints);
00097         
00098         for (std::size_t i = 0; i < nbPoints; ++i) candidates[i] = i;
00099         
00100         const std::size_t nbCandidates = candidates.size();
00101         
00102         //Compute centroid
00103         Vector3 center;
00104         for(std::size_t i = 0; i < featDim - 1; ++i) center(i) = T(0.);
00105         
00106         for (std::size_t i = 0; i < nbCandidates; ++i)
00107                 for (std::size_t f = 0; f <= 3; ++f)
00108                         center(f) += cloud.features(f,candidates[i]);
00109         
00110         for(std::size_t i = 0; i <= 3; ++i) center(i) /= T(nbCandidates);
00111         
00112         //Compute torque normalization
00113         T Lnorm = 1.0;
00114         
00115         if(normalizationMethod == TorqueNormMethod::L1)
00116         {
00117                 Lnorm = 1.0;
00118         }
00119         else if(normalizationMethod == TorqueNormMethod::Lavg)
00120         {
00121                 Lnorm = 0.0;
00122                 for (std::size_t i = 0; i < nbCandidates; ++i)
00123                         Lnorm += (cloud.features.col(candidates[i]).head(3) - center).norm();
00124                 Lnorm /= nbCandidates;
00125         }
00126         else if(normalizationMethod == TorqueNormMethod::Lmax)  
00127         {       
00128                 const Vector minValues = cloud.features.rowwise().minCoeff();
00129                 const Vector maxValues = cloud.features.rowwise().maxCoeff();
00130                 const Vector3 radii = maxValues.head(3) - minValues.head(3);
00131 
00132                 Lnorm = radii.maxCoeff() / 2.; //radii.mean() / 2.; 
00133         }
00134         
00135         //A.3 - Compute 6x6 covariance matrix + EigenVectors
00136         auto computeCovariance = [Lnorm, nbCandidates, &cloud, &center, &normals, &candidates](Matrix66 & cov) -> void {
00137                         //Compute F matrix, see Eq. (4)
00138                         Eigen::Matrix<T, 6, Eigen::Dynamic> F(6, nbCandidates);
00139         
00140                         for(std::size_t i = 0; i < nbCandidates; ++i)
00141                         {
00142                                 const Vector3 p = cloud.features.col(candidates[i]).head(3) - center; // pi-c
00143                                 const Vector3 ni = normals.col(candidates[i]).head(3);
00144                                 
00145                                 //compute (1 / L) * (pi - c) x ni 
00146                                 F.template block<3, 1>(0, i) = (1. / Lnorm) * p.cross(ni);
00147                                 //set ni part
00148                                 F.template block<3, 1>(3, i) = ni;
00149                         }
00150 
00151                         // Compute the covariance matrix Cov = FF'
00152                         cov = F * F.transpose(); 
00153                 };
00154                 
00155         Matrix66 covariance;
00156         computeCovariance(covariance);
00157         
00158         Eigen::EigenSolver<Matrix66> solver(covariance);                
00159         const Matrix66  eigenVe = solver.eigenvectors().real();
00160         const Vector6   eigenVa = solver.eigenvalues().real();
00161         
00163         //B.1 - Compute the v-6 for each candidate
00164         std::vector<Vector6, Eigen::aligned_allocator<Vector6>> v; // v[i] = [(pi-c) x ni ; ni ]'
00165         v.resize(nbCandidates);
00166 
00167         for(std::size_t i = 0; i < nbCandidates; ++i)
00168         {
00169                 const Vector3 p = cloud.features.col(candidates[i]).head(3) - center; // pi-c
00170                 const Vector3 ni = normals.col(candidates[i]).head(3);
00171                 
00172                 v[i].template block<3, 1>(0, 0) = (1. / Lnorm) * p.cross(ni);
00173                 v[i].template block<3, 1>(3, 0) = ni;
00174         }
00175         
00176         //B.2 - Compute the 6 sorted list based on dot product (vi . Xk) = magnitude, with Xk the kth-EigenVector
00177         std::vector<std::list<std::pair<int, T>>> L; // contain list of pair (index, magnitude) contribution to the eigens vectors
00178         L.resize(6);
00179         
00180         //sort by decreasing magnitude
00181         auto comp = [](const std::pair<int, T>& p1, const std::pair<int, T>& p2) -> bool {
00182                         return p1.second > p2.second;
00183                 };
00184         
00185         for(std::size_t k = 0; k < 6; ++k)
00186         {               
00187                 for(std::size_t i = 0; i < nbCandidates; ++i )
00188                 {
00189                         L[k].push_back(std::make_pair(i, std::fabs( v[i].dot(eigenVe.template block<6,1>(0, k)) )));
00190                 }
00191                 
00192                 L[k].sort(comp);
00193         }       
00194         
00195         std::vector<T> t(6, T(0.)); //contains the sums of squared magnitudes
00196         std::vector<bool> sampledPoints(nbCandidates, false); //maintain flag to avoid resampling the same point in an other list 
00197         
00199         for(std::size_t i = 0; i < nbSample; ++i)
00200         {
00201                 //B.3 - Equally constrained all eigen vectors           
00202                 // magnitude contribute to t_i where i is the indice of th least contrained eigen vector
00203                 
00204                 //Find least constrained vector
00205                 std::size_t k = 0;
00206                 for (std::size_t i = 0; i < 6; ++i)
00207                 {
00208                         if (t[k] > t[i])
00209                                 k = i;
00210                 }
00211                 // Add the point from the top of the list corresponding to the dimension to the set of samples
00212                 while(sampledPoints[L[k].front().first])
00213                         L[k].pop_front(); //remove already sampled point
00214                 
00215                 //Get index to keep
00216                 const std::size_t idToKeep = static_cast<std::size_t>(L[k].front().first);
00217                 L[k].pop_front();
00218                         
00219                 sampledPoints[idToKeep] = true; //set flag to avoid resampling
00220                                 
00221                 //B.4 - Update the running total
00222                 for (std::size_t k = 0; k < 6; ++k)
00223                 {
00224                         const T magnitude = v[idToKeep].dot(eigenVe.template block<6, 1>(0, k));
00225                         t[k] += (magnitude * magnitude);
00226                 }
00227                 
00228                 keepIndexes[i] = candidates[idToKeep];
00229         }
00230 
00231         //TODO: evaluate performances between this solution and sorting the indexes
00232         // We build map of (old index to new index), in case we sample pts at the begining of the pointcloud
00233         std::unordered_map<std::size_t, std::size_t> mapidx;
00234         std::size_t idx = 0;
00235         
00237         for(std::size_t id : keepIndexes)
00238         {
00239                 //retrieve index from lookup table if sampling in already switched element
00240                 if(id<idx)
00241                         id = mapidx[id];
00242                 //Switch columns id and idx
00243                 cloud.swapCols(idx, id);        
00244                 //Maintain new index position   
00245                 mapidx[idx] = id;
00246                 //Update index
00247                 ++idx;
00248         }
00249         cloud.conservativeResize(nbSample);
00250 }
00251 
00252 // Compute c = Lambda_6 / Lambda_1, where Lambda_1 <= ... <= Lambda_6
00253 // Stability is obtained where c is as close as possible of 1.0
00254 template <typename T>
00255 T CovarianceSamplingDataPointsFilter<T>::computeConditionNumber(const Matrix66 &cov)
00256 {
00257         Vector eigenVa = Vector::Identity(6, 1);                
00258         
00259         Eigen::EigenSolver<Matrix66> solver(cov);               
00260         eigenVa = solver.eigenvalues().real();
00261 
00262         return eigenVa.maxCoeff() / eigenVa.minCoeff();
00263 }
00264 
00265 template struct CovarianceSamplingDataPointsFilter<float>;
00266 template struct CovarianceSamplingDataPointsFilter<double>;


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:29