Elipsoids.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 "Elipsoids.h"
00036 
00037 #include "utils.h"
00038 // Eigenvalues
00039 #include "Eigen/QR"
00040 #include "Eigen/Eigenvalues"
00041 
00042 #include "PointMatcherPrivate.h"
00043 
00044 // ElipsoidsDataPointsFilter
00045 
00046 // Constructor
00047 template<typename T>
00048 ElipsoidsDataPointsFilter<T>::ElipsoidsDataPointsFilter(const Parameters& params):
00049         PointMatcher<T>::DataPointsFilter("ElipsoidsDataPointsFilter", 
00050                 ElipsoidsDataPointsFilter::availableParameters(), params),
00051         ratio(Parametrizable::get<T>("ratio")),
00052         knn(Parametrizable::get<int>("knn")),
00053         samplingMethod(Parametrizable::get<int>("samplingMethod")),
00054         maxBoxDim(Parametrizable::get<T>("maxBoxDim")),
00055         maxTimeWindow(Parametrizable::get<T>("maxTimeWindow")),
00056         minPlanarity(Parametrizable::get<T>("minPlanarity")),
00057         averageExistingDescriptors(Parametrizable::get<bool>("averageExistingDescriptors")),
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         keepCovariances(Parametrizable::get<bool>("keepCovariances")),
00063         keepWeights(Parametrizable::get<bool>("keepWeights")),
00064         keepMeans(Parametrizable::get<bool>("keepMeans")),
00065         keepShapes(Parametrizable::get<bool>("keepShapes")),
00066         keepIndices(Parametrizable::get<bool>("keepIndices"))
00067 {
00068 }
00069 
00070 // Compute
00071 template<typename T>
00072 typename PointMatcher<T>::DataPoints
00073 ElipsoidsDataPointsFilter<T>::filter(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 ElipsoidsDataPointsFilter<T>::inPlaceFilter(DataPoints& cloud)
00083 {
00084   typedef typename DataPoints::View View;
00085   typedef typename DataPoints::Label Label;
00086   typedef typename DataPoints::Labels Labels;
00087   typedef typename DataPoints::TimeView TimeView;
00088 
00089   const int pointsCount(cloud.features.cols());
00090   const int featDim(cloud.features.rows());
00091   const int descDim(cloud.descriptors.rows());
00092         const unsigned int labelDim(cloud.descriptorLabels.size());
00093 
00094   int insertDim(0);
00095   if (averageExistingDescriptors)
00096   {
00097     // TODO: this should be in the form of an assert
00098     // Validate descriptors and labels
00099     for(unsigned int i = 0; i < labelDim; ++i)
00100       insertDim += cloud.descriptorLabels[i].span;
00101     if (insertDim != descDim)
00102       throw InvalidField("ElipsoidsDataPointsFilter: Error, descriptor labels do not match descriptor data");
00103   }
00104 
00105   // Compute space requirement 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 dimWeights(1);
00111   const int dimMeans(featDim-1);
00112   const int dimCovariances((featDim-1)*(featDim-1));
00113   const int dimShapes(featDim-1);
00114   const int dimPointIds(knn);
00115 
00116   // Allocate space for new descriptors
00117   Labels cloudLabels, timeLabels;
00118   if (keepIndices) 
00119   {
00120     cloudLabels.push_back(Label("pointIds", dimPointIds));
00121     cloudLabels.push_back(Label("pointX", dimPointIds));
00122     cloudLabels.push_back(Label("pointY", dimPointIds));
00123     cloudLabels.push_back(Label("pointZ", dimPointIds));
00124     cloudLabels.push_back(Label("numOfNN", 1));
00125   }
00126   if (keepNormals)
00127     cloudLabels.push_back(Label("normals", dimNormals));
00128   if (keepDensities)
00129     cloudLabels.push_back(Label("densities", dimDensities));
00130   if (keepEigenValues)
00131     cloudLabels.push_back(Label("eigValues", dimEigValues));
00132   if (keepEigenVectors)
00133     cloudLabels.push_back(Label("eigVectors", dimEigVectors));
00134   if (keepCovariances)
00135     cloudLabels.push_back(Label("covariance", dimCovariances));
00136   if (keepWeights)
00137     cloudLabels.push_back(Label("weights", dimWeights));
00138   if (keepMeans)
00139     cloudLabels.push_back(Label("means", dimMeans));
00140   if (keepShapes) 
00141   {
00142     assert(featDim == 3);
00143     cloudLabels.push_back(Label("shapes", dimShapes)); // Planarity, Cylindricality, Sphericality
00144   }
00145   timeLabels.push_back(Label("time", 2));
00146 
00147   cloud.allocateDescriptors(cloudLabels);
00148   cloud.allocateTimes(timeLabels);
00149 
00150   // we keep build data on stack for reentrant behaviour
00151   View cloudExistingDescriptors(cloud.descriptors.block(0,0,cloud.descriptors.rows(),cloud.descriptors.cols()));
00152   TimeView cloudExistingTimes(cloud.times.block(0,0,cloud.times.rows(),cloud.times.cols()));
00153   BuildData buildData(cloud.features, cloud.descriptors, cloud.times);
00154 
00155   // get views
00156   if (keepIndices) 
00157   {
00158     buildData.pointIds = cloud.getDescriptorViewByName("pointIds");
00159     buildData.pointX = cloud.getDescriptorViewByName("pointX");
00160     buildData.pointY = cloud.getDescriptorViewByName("pointY");
00161     buildData.pointZ = cloud.getDescriptorViewByName("pointZ");
00162     buildData.numOfNN = cloud.getDescriptorViewByName("numOfNN");
00163   }
00164   if (keepNormals)
00165     buildData.normals = cloud.getDescriptorViewByName("normals");
00166   if (keepDensities)
00167     buildData.densities = cloud.getDescriptorViewByName("densities");
00168   if (keepEigenValues)
00169     buildData.eigenValues = cloud.getDescriptorViewByName("eigValues");
00170   if (keepEigenVectors)
00171     buildData.eigenVectors = cloud.getDescriptorViewByName("eigVectors");
00172   if (keepCovariances)
00173     buildData.covariance = cloud.getDescriptorViewByName("covariance");
00174   if (keepWeights)
00175     buildData.weights = cloud.getDescriptorViewByName("weights");
00176   if (keepMeans)
00177     buildData.means = cloud.getDescriptorViewByName("means");
00178   if (keepShapes)
00179     buildData.shapes = cloud.getDescriptorViewByName("shapes");
00180 
00181   // build the new point cloud
00182   buildNew(
00183       buildData,
00184       0,
00185       pointsCount,
00186       cloud.features.rowwise().minCoeff(),
00187       cloud.features.rowwise().maxCoeff()
00188   );
00189 
00190   // Bring the data we keep to the front of the arrays then
00191   // wipe the leftover unused space.
00192   std::sort(buildData.indicesToKeep.begin(), buildData.indicesToKeep.end());
00193   const int ptsOut = buildData.indicesToKeep.size();
00194   for (int i = 0; i < ptsOut; ++i)
00195   {
00196     const int k = buildData.indicesToKeep[i];
00197     assert(i <= k);
00198     cloud.features.col(i) = cloud.features.col(k);
00199     cloud.times.col(i) = cloud.times.col(k);
00200     if (cloud.descriptors.rows() != 0)
00201       cloud.descriptors.col(i) = cloud.descriptors.col(k);
00202     if(keepIndices) 
00203     {
00204       buildData.pointIds->col(i) = buildData.pointIds->col(k);
00205       buildData.pointX->col(i) = buildData.pointX->col(k);
00206       buildData.pointY->col(i) = buildData.pointY->col(k);
00207       buildData.pointZ->col(i) = buildData.pointZ->col(k);
00208       buildData.numOfNN->col(i) = buildData.numOfNN->col(k);
00209     }
00210     if(keepNormals)
00211       buildData.normals->col(i) = buildData.normals->col(k);
00212     if(keepDensities)
00213       (*buildData.densities)(0,i) = (*buildData.densities)(0,k);
00214     if(keepEigenValues)
00215       buildData.eigenValues->col(i) = buildData.eigenValues->col(k);
00216     if(keepEigenVectors)
00217       buildData.eigenVectors->col(i) = buildData.eigenVectors->col(k);
00218     if(keepWeights)
00219       buildData.weights->col(i) = buildData.weights->col(k);
00220     if(keepCovariances)
00221       buildData.covariance->col(i) = buildData.covariance->col(k);
00222     if(keepMeans)
00223       buildData.means->col(i) = buildData.means->col(k);
00224     if(keepShapes)
00225       buildData.shapes->col(i) = buildData.shapes->col(k);
00226   }
00227   cloud.features.conservativeResize(Eigen::NoChange, ptsOut);
00228   cloud.descriptors.conservativeResize(Eigen::NoChange, ptsOut);
00229   cloud.times.conservativeResize(Eigen::NoChange, ptsOut);
00230 
00231   // warning if some points were dropped
00232   if(buildData.unfitPointsCount != 0)
00233     LOG_INFO_STREAM("  ElipsoidsDataPointsFilter - Could not compute normal for " << buildData.unfitPointsCount << " pts.");
00234 }
00235 
00236 template<typename T>
00237 void ElipsoidsDataPointsFilter<T>::buildNew(
00238         BuildData& data, const int first, const int last, 
00239         Vector&& minValues, Vector&& maxValues) const
00240 {
00241   using namespace PointMatcherSupport;
00242   
00243   const int count(last - first);
00244   if (count <= int(knn))
00245   {
00246     // compute for this range
00247     fuseRange(data, first, last);
00248     // typically by stopping recursion after the median of the bounding cuboid
00249     // is below a threshold, or that the number of points falls under a threshold
00250     return;
00251   }
00252   // find the largest dimension of the box
00253   const int cutDim = argMax<T>(maxValues - minValues);
00254 
00255   // compute number of elements
00256   const int rightCount(count/2);
00257   const int leftCount(count - rightCount);
00258   assert(last - rightCount == first + leftCount);
00259 
00260   // sort, hack std::nth_element
00261   std::nth_element(
00262       data.indices.begin() + first,
00263       data.indices.begin() + first + leftCount,
00264       data.indices.begin() + last,
00265       CompareDim(cutDim, data)
00266   );
00267 
00268   // get value
00269   const int cutIndex(data.indices[first+leftCount]);
00270   const T cutVal(data.features(cutDim, cutIndex));
00271 
00272   // update bounds for left
00273   Vector leftMaxValues(maxValues);
00274   leftMaxValues[cutDim] = cutVal;
00275   // update bounds for right
00276   Vector rightMinValues(minValues);
00277   rightMinValues[cutDim] = cutVal;
00278 
00279   // recurse
00280   buildNew(data, first, first + leftCount, std::forward<Vector>(minValues), std::move(leftMaxValues));
00281   buildNew(data, first + leftCount, last, std::move(rightMinValues), std::forward<Vector>(maxValues));
00282 }
00283 
00284 template<typename T>
00285 void ElipsoidsDataPointsFilter<T>::fuseRange(
00286         BuildData& data, const int first, const int last) const
00287 {
00288   using namespace PointMatcherSupport;
00289   
00290   typedef typename Eigen::Matrix<std::int64_t, Eigen::Dynamic, Eigen::Dynamic> Int64Matrix;
00291 
00292   const int colCount(last-first);
00293   const int featDim(data.features.rows());
00294 
00295   // build nearest neighbors list
00296   Matrix d(featDim-1, colCount);
00297   Int64Matrix t(1, colCount);
00298   for (int i = 0; i < colCount; ++i) 
00299   {
00300     d.col(i) = data.features.block(0,data.indices[first+i],featDim-1, 1);
00301     t.col(i) = data.times.col(data.indices[first + i]); //, 0);
00302   }
00303   const Vector box = d.rowwise().maxCoeff() - d.rowwise().minCoeff();
00304   const std::int64_t timeBox = t.maxCoeff() - t.minCoeff();
00305 
00306   const T boxDim(box.maxCoeff());
00307   // drop box if it is too large or max timeframe is exceeded
00308   if (boxDim > maxBoxDim || timeBox > maxTimeWindow)
00309   {
00310     data.unfitPointsCount += colCount;
00311     return;
00312   }
00313   const Vector mean = d.rowwise().sum() / T(colCount);
00314   const Matrix NN = (d.colwise() - mean);
00315 
00316   const std::int64_t minTime = t.minCoeff();
00317   const std::int64_t maxTime = t.maxCoeff();
00318   const std::int64_t meanTime = t.sum() / T(colCount);
00319 
00320   // compute covariance
00321   const Matrix C(NN * NN.transpose());
00322   Vector eigenVa = Vector::Identity(featDim-1, 1);
00323   Matrix eigenVe = Matrix::Identity(featDim-1, featDim-1);
00324   // Ensure that the matrix is suited for eigenvalues calculation
00325   if(keepNormals || keepEigenValues || keepEigenVectors || keepCovariances || keepShapes || minPlanarity > 0)
00326   {
00327     if(C.fullPivHouseholderQr().rank()+1 >= featDim-1)
00328     {
00329       const Eigen::EigenSolver<Matrix> solver(C);
00330       eigenVa = solver.eigenvalues().real();
00331       eigenVe = solver.eigenvectors().real();
00332     }
00333     else
00334     {
00335       data.unfitPointsCount += colCount;
00336       return;
00337     }
00338     if(minPlanarity > 0) 
00339     {
00340       Eigen::Matrix<T, 3, 1> vals;
00341       (vals << eigenVa(0),eigenVa(1),eigenVa(2));
00342       vals = vals/eigenVa.sum();
00343       const T planarity = 2 * vals(1)-2*vals(2);
00344       // throw out surfel if it does not meet planarity criteria
00345       if (planarity < minPlanarity)
00346       {
00347         data.unfitPointsCount += colCount;
00348         return;
00349       }
00350     }
00351   }
00352 
00353   // keep the indices of each ellipsoid
00354   Vector pointIds(1,colCount);
00355   Matrix points(3,colCount);
00356 
00357   if(keepIndices) 
00358   {
00359     for (int i = 0; i < colCount; ++i) 
00360     {
00361       pointIds(i) = data.indices[first+i];
00362       points.col(i) = data.features.block(0,data.indices[first+i],2, 1);
00363     }
00364   }
00365 
00366   Vector normal;
00367   if(keepNormals)
00368     normal = computeNormal<T>(eigenVa, eigenVe);
00369 
00370   T density = 0;
00371   if(keepDensities)
00372     density = computeDensity<T>(NN);
00373   Vector serialEigVector;
00374   if(keepEigenVectors)
00375     serialEigVector = serializeEigVec<T>(eigenVe);
00376   Vector serialCovVector;
00377   if(keepCovariances)
00378     serialCovVector = serializeEigVec<T>(C);
00379 
00380   // some safety check
00381   if(data.descriptors.rows() != 0)
00382     assert(data.descriptors.cols() != 0);
00383 
00384   // Filter points randomly
00385   if(samplingMethod == 0)
00386   {
00387     for(int i=0; i<colCount; ++i)
00388     {
00389       const float r = (float)std::rand()/(float)RAND_MAX;
00390       if(r < ratio)
00391       {
00392         // Keep points with their descriptors
00393         const int k = data.indices[first+i];
00394         // Mark the indices which will be part of the final data
00395         data.indicesToKeep.push_back(k);
00396 
00397         // write the updated times: min, max, mean
00398         data.times(0, k) = minTime;
00399         data.times(1, k) = maxTime;
00400         data.times(2, k) = meanTime;
00401 
00402         // Build new descriptors
00403         if(keepIndices) 
00404         {
00405           data.pointIds->col(k) = pointIds;
00406           data.pointX->col(k) = points.row(0);
00407           data.pointY->col(k) = points.row(1);
00408           data.pointZ->col(k) = points.row(2);
00409           (*data.numOfNN)(0,k) = NN.cols();
00410         }
00411         if(keepNormals)
00412           data.normals->col(k) = normal;
00413         if(keepDensities)
00414           (*data.densities)(0,k) = density;
00415         if(keepEigenValues)
00416           data.eigenValues->col(k) = eigenVa;
00417         if(keepEigenVectors)
00418           data.eigenVectors->col(k) = serialEigVector;
00419         if(keepCovariances)
00420           data.covariance->col(k) = serialCovVector;
00421         if(keepMeans)
00422           data.means->col(k) = mean;    
00423         // a 3d vecetor of shape parameters: planarity (P), cylindricality (C), sphericality (S)
00424         if(keepShapes) 
00425         {
00426           Eigen::Matrix<T, 3, 3> shapeMat;
00427           (shapeMat << 0, 2, -2, 1, -1, 0, 0, 0, 3);
00428           Eigen::Matrix<T, 3, 1> vals;
00429           (vals << eigenVa(0),eigenVa(1),eigenVa(2));
00430           vals = vals/eigenVa.sum();
00431           data.shapes->col(k) = shapeMat * vals;
00432 
00433         }
00434         if(keepWeights) 
00435         {
00436           (*data.weights)(0,k) = colCount;
00437         }
00438       }
00439     }
00440   }
00441   else
00442   {
00443     const int k = data.indices[first];
00444     // Mark the indices which will be part of the final data
00445     data.indicesToKeep.push_back(k);
00446     data.features.col(k).topRows(featDim-1) = mean;
00447     // write the updated times: min, max, mean
00448     data.times(0, k) = minTime;
00449     data.times(1, k) = maxTime;
00450     data.times(2, k) = meanTime;
00451 
00452     data.features(featDim-1, k) = 1;
00453 
00454     if(data.descriptors.rows() != 0)
00455     {
00456       // average the existing descriptors
00457       if (averageExistingDescriptors)
00458       {
00459         Vector mergedDesc(Vector::Zero(data.descriptors.rows()));
00460         for (int i = 0; i < colCount; ++i)
00461           mergedDesc += data.descriptors.col(data.indices[first+i]);
00462         mergedDesc /= T(colCount);
00463         data.descriptors.col(k) = mergedDesc;
00464       }
00465       // else just keep the first one
00466     }
00467 
00468     // Build new descriptors
00469     if(keepIndices) 
00470     {
00471       data.pointIds->col(k) = pointIds;
00472       data.pointX->col(k) = points.row(0);
00473       data.pointY->col(k) = points.row(1);
00474       data.pointZ->col(k) = points.row(2);
00475     }
00476     if(keepNormals)
00477       data.normals->col(k) = normal;
00478     if(keepDensities)
00479       (*data.densities)(0,k) = density;
00480     if(keepEigenValues)
00481       data.eigenValues->col(k) = eigenVa;
00482     if(keepEigenVectors)
00483       data.eigenVectors->col(k) = serialEigVector;
00484     if(keepCovariances)
00485       data.covariance->col(k) = serialCovVector;
00486     if(keepMeans)
00487       data.means->col(k) = mean;
00488     if(keepShapes) 
00489     {
00490       Eigen::Matrix<T, 3, 3> shapeMat;
00491       (shapeMat << 0, 2, -2, 1, -1, 0, 0, 0, 3);
00492       Eigen::Matrix<T, 3, 1> vals;
00493       (vals << eigenVa(0),eigenVa(1),eigenVa(2));
00494       vals = vals/eigenVa.sum();
00495       data.shapes->col(k) = shapeMat * vals; //eigenVa;
00496     }
00497     if(keepWeights)
00498       (*data.weights)(0,k) = colCount;
00499   }
00500 
00501 }
00502 
00503 template struct ElipsoidsDataPointsFilter<float>;
00504 template struct ElipsoidsDataPointsFilter<double>;
00505 


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