SurfaceNormal.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 "SurfaceNormal.h"
00036 
00037 // Eigenvalues
00038 #include "Eigen/QR"
00039 #include "Eigen/Eigenvalues"
00040 
00041 #include "PointMatcherPrivate.h"
00042 #include "IO.h"
00043 #include "MatchersImpl.h"
00044 
00045 #include <boost/format.hpp>
00046 
00047 #include "utils.h"
00048 
00049 // SurfaceNormalDataPointsFilter
00050 // Constructor
00051 template<typename T>
00052 SurfaceNormalDataPointsFilter<T>::SurfaceNormalDataPointsFilter(const Parameters& params):
00053         PointMatcher<T>::DataPointsFilter("SurfaceNormalDataPointsFilter",
00054                 SurfaceNormalDataPointsFilter::availableParameters(), params),
00055         knn(Parametrizable::get<int>("knn")),
00056         maxDist(Parametrizable::get<T>("maxDist")),
00057         epsilon(Parametrizable::get<T>("epsilon")),
00058         keepNormals(Parametrizable::get<bool>("keepNormals")),
00059         keepDensities(Parametrizable::get<bool>("keepDensities")),
00060         keepEigenValues(Parametrizable::get<bool>("keepEigenValues")),
00061         keepEigenVectors(Parametrizable::get<bool>("keepEigenVectors")),
00062         keepMatchedIds(Parametrizable::get<bool>("keepMatchedIds")),
00063         keepMeanDist(Parametrizable::get<bool>("keepMeanDist")),
00064         sortEigen(Parametrizable::get<bool>("sortEigen")),
00065         smoothNormals(Parametrizable::get<bool>("smoothNormals"))
00066 {
00067 }
00068 
00069 // Compute
00070 template<typename T>
00071 typename PointMatcher<T>::DataPoints
00072 SurfaceNormalDataPointsFilter<T>::filter(
00073         const DataPoints& input)
00074 {
00075         DataPoints output(input);
00076         inPlaceFilter(output);
00077         return output;
00078 }
00079 
00080 // In-place filter
00081 template<typename T>
00082 void SurfaceNormalDataPointsFilter<T>::inPlaceFilter(
00083         DataPoints& cloud)
00084 {
00085         typedef typename DataPoints::View View;
00086         typedef typename DataPoints::Label Label;
00087         typedef typename DataPoints::Labels Labels;
00088         typedef typename MatchersImpl<T>::KDTreeMatcher KDTreeMatcher;
00089         typedef typename PointMatcher<T>::Matches Matches;
00090 
00091         using namespace PointMatcherSupport;
00092 
00093         const int pointsCount(cloud.features.cols());
00094         const int featDim(cloud.features.rows());
00095         const int descDim(cloud.descriptors.rows());
00096         const unsigned int labelDim(cloud.descriptorLabels.size());
00097 
00098         // Validate descriptors and labels
00099         int insertDim(0);
00100         for(unsigned int i = 0; i < labelDim ; ++i)
00101                 insertDim += cloud.descriptorLabels[i].span;
00102         if (insertDim != descDim)
00103                 throw InvalidField("SurfaceNormalDataPointsFilter: Error, descriptor labels do not match descriptor data");
00104 
00105         // Reserve memory for new descriptors
00106         const int dimNormals(featDim-1);
00107         const int dimDensities(1);
00108         const int dimEigValues(featDim-1);
00109         const int dimEigVectors((featDim-1)*(featDim-1));
00110         //const int dimMatchedIds(knn);
00111         const int dimMeanDist(1);
00112 
00113         boost::optional<View> normals;
00114         boost::optional<View> densities;
00115         boost::optional<View> eigenValues;
00116         boost::optional<View> eigenVectors;
00117         boost::optional<View> matchedValues;
00118         boost::optional<View> matchIds;
00119         boost::optional<View> meanDists;
00120 
00121         Labels cloudLabels;
00122         if (keepNormals)
00123                 cloudLabels.push_back(Label("normals", dimNormals));
00124         if (keepDensities)
00125                 cloudLabels.push_back(Label("densities", dimDensities));
00126         if (keepEigenValues)
00127                 cloudLabels.push_back(Label("eigValues", dimEigValues));
00128         if (keepEigenVectors)
00129                 cloudLabels.push_back(Label("eigVectors", dimEigVectors));
00130         if (keepMatchedIds)
00131                 cloudLabels.push_back(Label("matchedIds", knn));
00132         if (keepMeanDist)
00133                 cloudLabels.push_back(Label("meanDists", dimMeanDist));
00134 
00135         // Reserve memory
00136         cloud.allocateDescriptors(cloudLabels);
00137 
00138         if (keepNormals)
00139                 normals = cloud.getDescriptorViewByName("normals");
00140         if (keepDensities)
00141                 densities = cloud.getDescriptorViewByName("densities");
00142         if (keepEigenValues)
00143                 eigenValues = cloud.getDescriptorViewByName("eigValues");
00144         if (keepEigenVectors)
00145                 eigenVectors = cloud.getDescriptorViewByName("eigVectors");
00146         if (keepMatchedIds)
00147                 matchIds = cloud.getDescriptorViewByName("matchedIds");
00148         if (keepMeanDist)
00149                 meanDists = cloud.getDescriptorViewByName("meanDists");
00150 
00151         using namespace PointMatcherSupport;
00152         // Build kd-tree
00153         Parametrizable::Parameters param;
00154         boost::assign::insert(param) ( "knn", toParam(knn) );
00155         boost::assign::insert(param) ( "epsilon", toParam(epsilon) );
00156         boost::assign::insert(param) ( "maxDist", toParam(maxDist) );
00157 
00158         KDTreeMatcher matcher(param);
00159         matcher.init(cloud);
00160 
00161         Matches matches(typename Matches::Dists(knn, pointsCount), typename Matches::Ids(knn, pointsCount));
00162         matches = matcher.findClosests(cloud);
00163 
00164         // Search for surrounding points and compute descriptors
00165         int degenerateCount(0);
00166         for (int i = 0; i < pointsCount; ++i)
00167         {
00168                 bool isDegenerate = false;
00169                 // Mean of nearest neighbors (NN)
00170                 Matrix d(featDim-1, knn);
00171                 int realKnn = 0;
00172 
00173                 for(int j = 0; j < int(knn); ++j)
00174                 {
00175                         if (matches.dists(j,i) != Matches::InvalidDist)
00176                         {
00177                                 const int refIndex(matches.ids(j,i));
00178                                 d.col(realKnn) = cloud.features.block(0, refIndex, featDim-1, 1);
00179                                 ++realKnn;
00180                         }
00181                 }
00182                 d.conservativeResize(Eigen::NoChange, realKnn);
00183 
00184                 const Vector mean = d.rowwise().sum() / T(realKnn);
00185                 const Matrix NN = d.colwise() - mean;
00186 
00187                 const Matrix C(NN * NN.transpose());
00188                 Vector eigenVa = Vector::Zero(featDim-1, 1);
00189                 Matrix eigenVe = Matrix::Zero(featDim-1, featDim-1);
00190                 // Ensure that the matrix is suited for eigenvalues calculation
00191                 if(keepNormals || keepEigenValues || keepEigenVectors)
00192                 {
00193                         if(C.fullPivHouseholderQr().rank()+1 >= featDim-1)
00194                         {
00195                                 const Eigen::EigenSolver<Matrix> solver(C);
00196                                 eigenVa = solver.eigenvalues().real();
00197                                 eigenVe = solver.eigenvectors().real();
00198 
00199                                 if(sortEigen)
00200                                 {
00201                                         const std::vector<size_t> idx = sortIndexes<T>(eigenVa);
00202                                         const size_t idxSize = idx.size();
00203                                         Vector tmp_eigenVa = eigenVa;
00204                                         Matrix tmp_eigenVe = eigenVe;
00205                                         for(size_t i=0; i<idxSize; ++i)
00206                                         {
00207                                                 eigenVa(i,0) = tmp_eigenVa(idx[i], 0);
00208                                                 eigenVe.col(i) = tmp_eigenVe.col(idx[i]);
00209                                         }
00210                                 }
00211                         }
00212                         else
00213                         {
00214                                 //std::cout << "WARNING: Matrix C needed for eigen decomposition is degenerated. Expected cause: no noise in data" << std::endl;
00215                                 ++degenerateCount;
00216                                 isDegenerate = true;
00217                         }
00218                 }
00219 
00220                 if(keepNormals)
00221                 {
00222                         if(sortEigen)
00223                                 normals->col(i) = eigenVe.col(0);
00224                         else
00225                                 normals->col(i) = computeNormal<T>(eigenVa, eigenVe);
00226                         
00227                         // clamp normals to [-1,1] to handle approximation errors
00228                         normals->col(i) = normals->col(i).cwiseMax(-1.0).cwiseMin(1.0);
00229                 }
00230                 if(keepDensities)
00231                 {
00232                         if(isDegenerate)
00233                                 (*densities)(0, i) = 0.;
00234                         else
00235                                 (*densities)(0, i) = computeDensity<T>(NN);
00236                 }
00237                 if(keepEigenValues)
00238                         eigenValues->col(i) = eigenVa;
00239                 if(keepEigenVectors)
00240                         eigenVectors->col(i) = serializeEigVec<T>(eigenVe);
00241                 if(keepMeanDist)
00242                 {
00243                         if(isDegenerate)
00244                                 (*meanDists)(0, i) = std::numeric_limits<std::size_t>::max();
00245                         else
00246                         {
00247                                 const Vector point = cloud.features.block(0, i, featDim-1, 1);
00248                                 (*meanDists)(0, i) = (point - mean).norm();
00249                         }
00250                 }
00251 
00252         }
00253 
00254         if(keepMatchedIds)
00255         {
00256                 matchIds.get() = matches.ids.template cast<T>();
00257         }
00258 
00259         if(smoothNormals)
00260         {
00261                 for (int i = 0; i < pointsCount; ++i)
00262                 {
00263                         const Vector currentNormal = normals->col(i);
00264                         Vector mean = Vector::Zero(featDim-1);
00265                         int n=0;
00266                         for(int j = 0; j < int(knn); ++j)
00267                         {
00268                                 if (matches.dists(j,i) != Matches::InvalidDist)
00269                                 {
00270                                         const int refIndex(matches.ids(j,i));
00271                                         const Vector normal = normals->col(refIndex);
00272                                         if(currentNormal.dot(normal) > 0.)
00273                                                 mean += normal;
00274                                         else // flip normal vector
00275                                                 mean -= normal;
00276 
00277                                         ++n;
00278                                 }
00279                         }
00280 
00281                         normals->col(i) = mean / T(n);
00282                 }
00283         }
00284 
00285         if (degenerateCount)
00286         {
00287                 LOG_WARNING_STREAM("WARNING: Matrix C needed for eigen decomposition was degenerated in " << degenerateCount << " points over " << pointsCount << " (" << float(degenerateCount)*100.f/float(pointsCount) << " %)");
00288         }
00289 
00290 }
00291 
00292 template struct SurfaceNormalDataPointsFilter<float>;
00293 template struct SurfaceNormalDataPointsFilter<double>;
00294 


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