DataPointsFiltersImpl.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--2012,
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 
00036 #include "DataPointsFiltersImpl.h"
00037 #include "PointMatcherPrivate.h"
00038 #include "MatchersImpl.h"
00039 #include "Functions.h"
00040 
00041 #include <algorithm>
00042 #include <boost/format.hpp>
00043 
00044 // Eigenvalues
00045 #include "Eigen/QR"
00046 
00047 using namespace std;
00048 using namespace PointMatcherSupport;
00049 
00050 // IdentityDataPointsFilter
00051 template<typename T>
00052 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::IdentityDataPointsFilter::filter(
00053         const DataPoints& input)
00054 {
00055         DataPoints output(input);
00056         inPlaceFilter(output);
00057         return output;
00058 }
00059 
00060 // In-place filter
00061 template<typename T>
00062 void DataPointsFiltersImpl<T>::IdentityDataPointsFilter::inPlaceFilter(
00063         DataPoints& cloud)
00064 {
00065 }
00066 
00067 template struct DataPointsFiltersImpl<float>::IdentityDataPointsFilter;
00068 template struct DataPointsFiltersImpl<double>::IdentityDataPointsFilter;
00069 
00070 
00071 // RemoveNaNDataPointsFilter
00072 template<typename T>
00073 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::RemoveNaNDataPointsFilter::filter(
00074         const DataPoints& input)
00075 {
00076         DataPoints output(input);
00077         inPlaceFilter(output);
00078         return output;
00079 }
00080 
00081 // In-place filter
00082 template<typename T>
00083 void DataPointsFiltersImpl<T>::RemoveNaNDataPointsFilter::inPlaceFilter(
00084         DataPoints& cloud)
00085 {
00086         const int nbPointsIn = cloud.features.cols();
00087 
00088         int j = 0;
00089         for (int i = 0; i < nbPointsIn; ++i)
00090         {
00091                 const BOOST_AUTO(colArray, cloud.features.col(i).array());
00092                 const BOOST_AUTO(hasNaN, !(colArray == colArray).all());
00093                 if (!hasNaN)
00094                 {
00095                         cloud.setColFrom(j, cloud, i);
00096                         j++;
00097                 }
00098         }
00099 
00100         cloud.conservativeResize(j);
00101 }
00102 
00103 template struct DataPointsFiltersImpl<float>::RemoveNaNDataPointsFilter;
00104 template struct DataPointsFiltersImpl<double>::RemoveNaNDataPointsFilter;
00105 
00106 
00107 // MaxDistDataPointsFilter
00108 // Constructor
00109 template<typename T>
00110 DataPointsFiltersImpl<T>::MaxDistDataPointsFilter::MaxDistDataPointsFilter(const Parameters& params):
00111         DataPointsFilter("MaxDistDataPointsFilter", MaxDistDataPointsFilter::availableParameters(), params),
00112         dim(Parametrizable::get<unsigned>("dim")),
00113         maxDist(Parametrizable::get<T>("maxDist"))
00114 {
00115 }
00116 
00117 // Compute
00118 template<typename T>
00119 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::MaxDistDataPointsFilter::filter(
00120         const DataPoints& input)
00121 {
00122         DataPoints output(input);
00123         inPlaceFilter(output);
00124         return output;
00125 }
00126 
00127 // In-place filter
00128 template<typename T>
00129 void DataPointsFiltersImpl<T>::MaxDistDataPointsFilter::inPlaceFilter(
00130         DataPoints& cloud)
00131 {
00132         if (dim >= cloud.features.rows() - 1)
00133         {
00134                 throw InvalidParameter(
00135                         (boost::format("MaxDistDataPointsFilter: Error, filtering on dimension number %1%, larger than authorized axis id %2%") % dim % (cloud.features.rows() - 2)).str());
00136         }
00137 
00138         const int nbPointsIn = cloud.features.cols();
00139         const int nbRows = cloud.features.rows();
00140 
00141         int j = 0;
00142         if(dim == -1) // Euclidean distance
00143         {
00144                 for (int i = 0; i < nbPointsIn; i++)
00145                 {
00146                         const T absMaxDist = anyabs(maxDist);
00147                         if (cloud.features.col(i).head(nbRows-1).norm() < absMaxDist)
00148                         {
00149                                 cloud.setColFrom(j, cloud, i);
00150                                 j++;
00151                         }
00152                 }
00153         }
00154         else // Single-axis distance
00155         {
00156                 for (int i = 0; i < nbPointsIn; i++)
00157                 {
00158                         if ((cloud.features(dim, i)) < maxDist)
00159                         {
00160                                 cloud.setColFrom(j, cloud, i);
00161                                 j++;
00162                         }
00163                 }
00164         }
00165 
00166         cloud.conservativeResize(j);
00167 }
00168 
00169 template struct DataPointsFiltersImpl<float>::MaxDistDataPointsFilter;
00170 template struct DataPointsFiltersImpl<double>::MaxDistDataPointsFilter;
00171 
00172 
00173 // MinDistDataPointsFilter
00174 // Constructor
00175 template<typename T>
00176 DataPointsFiltersImpl<T>::MinDistDataPointsFilter::MinDistDataPointsFilter(const Parameters& params):
00177         DataPointsFilter("MinDistDataPointsFilter", MinDistDataPointsFilter::availableParameters(), params),
00178         dim(Parametrizable::get<unsigned>("dim")),
00179         minDist(Parametrizable::get<T>("minDist"))
00180 {
00181 }
00182 
00183 // Compute
00184 template<typename T>
00185 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::MinDistDataPointsFilter::filter(
00186         const DataPoints& input)
00187 {
00188         DataPoints output(input);
00189         inPlaceFilter(output);
00190         return output;
00191 }
00192 
00193 // In-place filter
00194 template<typename T>
00195 void DataPointsFiltersImpl<T>::MinDistDataPointsFilter::inPlaceFilter(
00196         DataPoints& cloud)
00197 {
00198         if (dim >= cloud.features.rows() - 1)
00199                 throw InvalidParameter((boost::format("MinDistDataPointsFilter: Error, filtering on dimension number %1%, larger than feature dimensionality %2%") % dim % (cloud.features.rows() - 2)).str());
00200 
00201         const int nbPointsIn = cloud.features.cols();
00202         const int nbRows = cloud.features.rows();
00203 
00204         int j = 0;
00205         if(dim == -1) // Euclidean distance
00206         {
00207                 const T absMinDist = anyabs(minDist);
00208                 for (int i = 0; i < nbPointsIn; i++)
00209                 {
00210                         if (cloud.features.col(i).head(nbRows-1).norm() > absMinDist)
00211                         {
00212                                 cloud.setColFrom(j, cloud, i);
00213                                 j++;
00214                         }
00215                 }
00216         }
00217         else // Single axis distance
00218         {
00219                 for (int i = 0; i < nbPointsIn; i++)
00220                 {
00221                         if ((cloud.features(dim, i)) > minDist)
00222                         {
00223                                 cloud.setColFrom(j, cloud, i);
00224                                 j++;
00225                         }
00226                 }
00227         }
00228 
00229         cloud.conservativeResize(j);
00230 
00231 }
00232 
00233 template struct DataPointsFiltersImpl<float>::MinDistDataPointsFilter;
00234 template struct DataPointsFiltersImpl<double>::MinDistDataPointsFilter;
00235 
00236 
00237 // BoundingBoxDataPointsFilter
00238 // Constructor
00239 template<typename T>
00240 DataPointsFiltersImpl<T>::BoundingBoxDataPointsFilter::BoundingBoxDataPointsFilter(const Parameters& params):
00241         DataPointsFilter("BoundingBoxDataPointsFilter", BoundingBoxDataPointsFilter::availableParameters(), params),
00242         xMin(Parametrizable::get<T>("xMin")),
00243         xMax(Parametrizable::get<T>("xMax")),
00244         yMin(Parametrizable::get<T>("yMin")),
00245         yMax(Parametrizable::get<T>("yMax")),
00246         zMin(Parametrizable::get<T>("zMin")),
00247         zMax(Parametrizable::get<T>("zMax")),
00248         removeInside(Parametrizable::get<bool>("removeInside"))
00249 {
00250 }
00251 
00252 // Compute
00253 template<typename T>
00254 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::BoundingBoxDataPointsFilter::filter(
00255         const DataPoints& input)
00256 {
00257         DataPoints output(input);
00258         inPlaceFilter(output);
00259         return output;
00260 }
00261 
00262 // In-place filter
00263 template<typename T>
00264 void DataPointsFiltersImpl<T>::BoundingBoxDataPointsFilter::inPlaceFilter(
00265         DataPoints& cloud)
00266 {
00267         const int nbPointsIn = cloud.features.cols();
00268         const int nbRows = cloud.features.rows();
00269 
00270         int j = 0;
00271         for (int i = 0; i < nbPointsIn; i++)
00272         {
00273                 bool keepPt = false;
00274                 const Vector point = cloud.features.col(i);
00275 
00276                 // FIXME: improve performance by using Eigen array operations
00277                 const bool x_in = (point(0) > xMin && point(0) < xMax);
00278                 const bool y_in = (point(1) > yMin && point(1) < yMax);
00279                 const bool z_in = (point(2) > zMin && point(2) < zMax) || nbRows == 3;
00280                 const bool in_box = x_in && y_in && z_in;
00281 
00282                 if(removeInside)
00283                         keepPt = !in_box;
00284                 else
00285                         keepPt = in_box;
00286 
00287                 if(keepPt)
00288                 {
00289                         cloud.setColFrom(j, cloud, i);
00290                         j++;
00291                 }
00292         }
00293 
00294         cloud.conservativeResize(j);
00295 }
00296 
00297 template struct DataPointsFiltersImpl<float>::BoundingBoxDataPointsFilter;
00298 template struct DataPointsFiltersImpl<double>::BoundingBoxDataPointsFilter;
00299 
00300 
00301 // MaxQuantileOnAxisDataPointsFilter
00302 // Constructor
00303 template<typename T>
00304 DataPointsFiltersImpl<T>::MaxQuantileOnAxisDataPointsFilter::MaxQuantileOnAxisDataPointsFilter(const Parameters& params):
00305         DataPointsFilter("MaxQuantileOnAxisDataPointsFilter", MaxQuantileOnAxisDataPointsFilter::availableParameters(), params),
00306         dim(Parametrizable::get<unsigned>("dim")),
00307         ratio(Parametrizable::get<T>("ratio"))
00308 {
00309 }
00310 
00311 // Compute
00312 template<typename T>
00313 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::MaxQuantileOnAxisDataPointsFilter::filter(
00314         const DataPoints& input)
00315 {
00316         DataPoints output(input);
00317         inPlaceFilter(output);
00318         return output;
00319 }
00320 
00321 // In-place filter
00322 template<typename T>
00323 void DataPointsFiltersImpl<T>::MaxQuantileOnAxisDataPointsFilter::inPlaceFilter(
00324         DataPoints& cloud)
00325 {
00326         if (int(dim) >= cloud.features.rows())
00327                 throw InvalidParameter((boost::format("MaxQuantileOnAxisDataPointsFilter: Error, filtering on dimension number %1%, larger than feature dimensionality %2%") % dim % cloud.features.rows()).str());
00328 
00329         const int nbPointsIn = cloud.features.cols();
00330         const int nbPointsOut = nbPointsIn * ratio;
00331 
00332         // build array
00333         vector<T> values;
00334         values.reserve(cloud.features.cols());
00335         for (int x = 0; x < cloud.features.cols(); ++x)
00336                 values.push_back(cloud.features(dim, x));
00337 
00338         // get quartiles value
00339         nth_element(values.begin(), values.begin() + (values.size() * ratio), values.end());
00340         const T limit = values[nbPointsOut];
00341 
00342         // copy towards beginning the elements we keep
00343         int j = 0;
00344         for (int i = 0; i < nbPointsIn; i++)
00345         {
00346                 if (cloud.features(dim, i) < limit)
00347                 {
00348                         assert(j <= i);
00349                         cloud.setColFrom(j, cloud, i);
00350                         j++;
00351                 }
00352         }
00353         assert(j <= nbPointsOut);
00354 
00355         cloud.conservativeResize(j);
00356 
00357 }
00358 
00359 template struct DataPointsFiltersImpl<float>::MaxQuantileOnAxisDataPointsFilter;
00360 template struct DataPointsFiltersImpl<double>::MaxQuantileOnAxisDataPointsFilter;
00361 
00362 
00363 // MaxDensityDataPointsFilter
00364 // Constructor
00365 template<typename T>
00366 DataPointsFiltersImpl<T>::MaxDensityDataPointsFilter::MaxDensityDataPointsFilter(const Parameters& params):
00367         DataPointsFilter("MaxDensityDataPointsFilter", MaxDensityDataPointsFilter::availableParameters(), params),
00368         maxDensity(Parametrizable::get<T>("maxDensity"))
00369 {
00370 }
00371 
00372 // Compute
00373 template<typename T>
00374 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::MaxDensityDataPointsFilter::filter(
00375         const DataPoints& input)
00376 {
00377         DataPoints output(input);
00378         inPlaceFilter(output);
00379         return output;
00380 }
00381 
00382 // In-place filter
00383 template<typename T>
00384 void DataPointsFiltersImpl<T>::MaxDensityDataPointsFilter::inPlaceFilter(
00385         DataPoints& cloud)
00386 {
00387         typedef typename DataPoints::View View;
00388         typedef typename DataPoints::ConstView ConstView;
00389 
00390         // Force densities to be computed
00391         if (!cloud.descriptorExists("densities"))
00392         {
00393                 throw InvalidField("MaxDensityDataPointsFilter: Error, no densities found in descriptors.");
00394         }
00395 
00396         const int nbPointsIn = cloud.features.cols();
00397         View densities = cloud.getDescriptorViewByName("densities");
00398         const T lastDensity = densities.maxCoeff();
00399         const int nbSaturatedPts = (densities.cwise() == lastDensity).count();
00400 
00401         // fill cloud values
00402         int j = 0;
00403         for (int i = 0; i < nbPointsIn; i++)
00404         {
00405                 const T density(densities(0,i));
00406                 if (density > maxDensity)
00407                 {
00408                         const float r = (float)std::rand()/(float)RAND_MAX;
00409                         float acceptRatio = maxDensity/density;
00410 
00411                         // Handle saturation value of density
00412                         if (density == lastDensity)
00413                         {
00414                                 acceptRatio = acceptRatio * (1-nbSaturatedPts/nbPointsIn);
00415                         }
00416 
00417                         if (r < acceptRatio)
00418                         {
00419                                 cloud.setColFrom(j, cloud, i);
00420                                 j++;
00421                         }
00422                 }
00423                 else
00424                 {
00425                         cloud.setColFrom(j, cloud, i);
00426                         j++;
00427                 }
00428         }
00429 
00430         cloud.conservativeResize(j);
00431 }
00432 
00433 template struct DataPointsFiltersImpl<float>::MaxDensityDataPointsFilter;
00434 template struct DataPointsFiltersImpl<double>::MaxDensityDataPointsFilter;
00435 
00436 
00437 // SurfaceNormalDataPointsFilter
00438 // Constructor
00439 template<typename T>
00440 DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter::SurfaceNormalDataPointsFilter(const Parameters& params):
00441         DataPointsFilter("SurfaceNormalDataPointsFilter", SurfaceNormalDataPointsFilter::availableParameters(), params),
00442         knn(Parametrizable::get<int>("knn")),
00443         epsilon(Parametrizable::get<T>("epsilon")),
00444         keepNormals(Parametrizable::get<bool>("keepNormals")),
00445         keepDensities(Parametrizable::get<bool>("keepDensities")),
00446         keepEigenValues(Parametrizable::get<bool>("keepEigenValues")),
00447         keepEigenVectors(Parametrizable::get<bool>("keepEigenVectors")),
00448         keepMatchedIds(Parametrizable::get<bool>("keepMatchedIds"))
00449 {
00450 }
00451 
00452 // Compute
00453 template<typename T>
00454 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter::filter(
00455         const DataPoints& input)
00456 {
00457         DataPoints output(input);
00458         inPlaceFilter(output);
00459         return output;
00460 }
00461 
00462 // In-place filter
00463 template<typename T>
00464 void DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter::inPlaceFilter(
00465         DataPoints& cloud)
00466 {
00467         typedef typename DataPoints::View View;
00468         typedef typename DataPoints::Label Label;
00469         typedef typename DataPoints::Labels Labels;
00470         typedef typename MatchersImpl<T>::KDTreeMatcher KDTreeMatcher;
00471         typedef typename PointMatcher<T>::Matches Matches;
00472 
00473         const int pointsCount(cloud.features.cols());
00474         const int featDim(cloud.features.rows());
00475         const int descDim(cloud.descriptors.rows());
00476 
00477         // Validate descriptors and labels
00478         int insertDim(0);
00479         for(unsigned int i = 0; i < cloud.descriptorLabels.size(); i++)
00480                 insertDim += cloud.descriptorLabels[i].span;
00481         if (insertDim != descDim)
00482                 throw InvalidField("SurfaceNormalDataPointsFilter: Error, descriptor labels do not match descriptor data");
00483 
00484         // Reserve memory for new descriptors
00485         const int dimNormals(featDim-1);
00486         const int dimDensities(1);
00487         const int dimEigValues(featDim-1);
00488         const int dimEigVectors((featDim-1)*(featDim-1));
00489         //const int dimMatchedIds(knn);
00490 
00491         boost::optional<View> normals;
00492         boost::optional<View> densities;
00493         boost::optional<View> eigenValues;
00494         boost::optional<View> eigenVectors;
00495         boost::optional<View> matchedValues;
00496 
00497         Labels cloudLabels;
00498         if (keepNormals)
00499                 cloudLabels.push_back(Label("normals", dimNormals));
00500         if (keepDensities)
00501                 cloudLabels.push_back(Label("densities", dimDensities));
00502         if (keepEigenValues)
00503                 cloudLabels.push_back(Label("eigValues", dimEigValues));
00504         if (keepEigenVectors)
00505                 cloudLabels.push_back(Label("eigVectors", dimEigVectors));
00506         cloud.allocateDescriptors(cloudLabels);
00507 
00508         if (keepNormals)
00509                 normals = cloud.getDescriptorViewByName("normals");
00510         if (keepDensities)
00511                 densities = cloud.getDescriptorViewByName("densities");
00512         if (keepEigenValues)
00513                 eigenValues = cloud.getDescriptorViewByName("eigValues");
00514         if (keepEigenVectors)
00515                 eigenVectors = cloud.getDescriptorViewByName("eigVectors");
00516         // TODO: implement keepMatchedIds
00517 //      if (keepMatchedIds)
00518 //      {
00519 //              cloud.allocateDescriptor("normals", dimMatchedIds);
00520 //              matchedValues = cloud.getDescriptorViewByName("normals");
00521 //      }
00522 
00523         // Build kd-tree
00524         Parametrizable::Parameters param;
00525         boost::assign::insert(param) ( "knn", toParam(knn) );
00526         boost::assign::insert(param) ( "epsilon", toParam(epsilon) );
00527         KDTreeMatcher matcher(param);
00528         matcher.init(cloud);
00529 
00530         Matches matches(typename Matches::Dists(knn, pointsCount), typename Matches::Ids(knn, pointsCount));
00531         matches = matcher.findClosests(cloud);
00532 
00533         // Search for surrounding points and compute descriptors
00534         int degenerateCount(0);
00535         for (int i = 0; i < pointsCount; ++i)
00536         {
00537                 // Mean of nearest neighbors (NN)
00538                 Matrix d(featDim-1, knn);
00539                 for(int j = 0; j < int(knn); j++)
00540                 {
00541                         const int refIndex(matches.ids(j,i));
00542                         d.col(j) = cloud.features.block(0, refIndex, featDim-1, 1);
00543                 }
00544 
00545                 const Vector mean = d.rowwise().sum() / T(knn);
00546                 const Matrix NN = d.colwise() - mean;
00547 
00548                 const Matrix C(NN * NN.transpose());
00549                 Vector eigenVa = Vector::Identity(featDim-1, 1);
00550                 Matrix eigenVe = Matrix::Identity(featDim-1, featDim-1);
00551                 // Ensure that the matrix is suited for eigenvalues calculation
00552                 if(keepNormals || keepEigenValues || keepEigenVectors)
00553                 {
00554                         if(C.fullPivHouseholderQr().rank()+1 >= featDim-1)
00555                         {
00556                                 const Eigen::EigenSolver<Matrix> solver(C);
00557                                 eigenVa = solver.eigenvalues().real();
00558                                 eigenVe = solver.eigenvectors().real();
00559                         }
00560                         else
00561                         {
00562                                 //std::cout << "WARNING: Matrix C needed for eigen decomposition is degenerated. Expected cause: no noise in data" << std::endl;
00563                                 ++degenerateCount;
00564                         }
00565                 }
00566 
00567                 if(keepNormals)
00568                         normals->col(i) = computeNormal(eigenVa, eigenVe);
00569                 if(keepDensities)
00570                         (*densities)(0, i) = computeDensity(NN);
00571                 if(keepEigenValues)
00572                         eigenValues->col(i) = eigenVa;
00573                 if(keepEigenVectors)
00574                         eigenVectors->col(i) = serializeEigVec(eigenVe);
00575         }
00576         if (degenerateCount)
00577         {
00578                 LOG_WARNING_STREAM("WARNING: Matrix C needed for eigen decomposition was degenerated in " << degenerateCount << " points over " << pointsCount << " (" << float(degenerateCount)*100.f/float(pointsCount) << " %)");
00579         }
00580 
00581 }
00582 
00583 template<typename T>
00584 typename PointMatcher<T>::Vector DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter::computeNormal(const Vector eigenVa, const Matrix eigenVe)
00585 {
00586         // Keep the smallest eigenvector as surface normal
00587         int smallestId(0);
00588         T smallestValue(numeric_limits<T>::max());
00589         for(int j = 0; j < eigenVe.cols(); j++)
00590         {
00591                 if (eigenVa(j) < smallestValue)
00592                 {
00593                         smallestId = j;
00594                         smallestValue = eigenVa(j);
00595                 }
00596         }
00597 
00598         return eigenVe.col(smallestId);
00599 }
00600 
00601 template<typename T>
00602 typename PointMatcher<T>::Vector DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter::serializeEigVec(const Matrix eigenVe)
00603 {
00604         // serialize row major
00605         const int eigenVeDim = eigenVe.cols();
00606         Vector output(eigenVeDim*eigenVeDim);
00607         for(int k=0; k < eigenVe.cols(); k++)
00608         {
00609                 output.segment(k*eigenVeDim, eigenVeDim) = 
00610                         eigenVe.row(k).transpose();
00611         }
00612 
00613         return output;
00614 }
00615 
00616 template<typename T>
00617 T DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter::computeDensity(const Matrix NN)
00618 {
00619         //volume in meter
00620         T volume = (4./3.)*M_PI*std::pow(NN.colwise().norm().maxCoeff(), 3);
00621 
00622         //volume in decimeter
00623         //T volume = (4./3.)*M_PI*std::pow(NN.colwise().norm().maxCoeff()*10.0, 3);
00624         //const T minVolume = 4.18e-9; // minimum of volume of one millimeter radius
00625         //const T minVolume = 0.42; // minimum of volume of one centimeter radius (in dm^3)
00626 
00627         //if(volume < minVolume)
00628         //      volume = minVolume;
00629 
00630         return T(NN.cols())/(volume);
00631 }
00632 
00633 template struct DataPointsFiltersImpl<float>::SurfaceNormalDataPointsFilter;
00634 template struct DataPointsFiltersImpl<double>::SurfaceNormalDataPointsFilter;
00635 
00636 
00637 // SamplingSurfaceNormalDataPointsFilter
00638 
00639 // Constructor
00640 template<typename T>
00641 DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter::SamplingSurfaceNormalDataPointsFilter(const Parameters& params):
00642         DataPointsFilter("SamplingSurfaceNormalDataPointsFilter", SamplingSurfaceNormalDataPointsFilter::availableParameters(), params),
00643         ratio(Parametrizable::get<T>("ratio")),
00644         knn(Parametrizable::get<int>("knn")),
00645         samplingMethod(Parametrizable::get<int>("samplingMethod")),
00646         maxBoxDim(Parametrizable::get<T>("maxBoxDim")),
00647         averageExistingDescriptors(Parametrizable::get<bool>("averageExistingDescriptors")),
00648         keepNormals(Parametrizable::get<bool>("keepNormals")),
00649         keepDensities(Parametrizable::get<bool>("keepDensities")),
00650         keepEigenValues(Parametrizable::get<bool>("keepEigenValues")),
00651         keepEigenVectors(Parametrizable::get<bool>("keepEigenVectors"))
00652 {
00653 }
00654 
00655 // Compute
00656 template<typename T>
00657 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter::filter(
00658         const DataPoints& input)
00659 {
00660         DataPoints output(input);
00661         inPlaceFilter(output);
00662         return output;
00663 }
00664 
00665 // In-place filter
00666 template<typename T>
00667 void DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter::inPlaceFilter(
00668         DataPoints& cloud)
00669 {
00670         typedef Matrix Features;
00671         typedef typename DataPoints::View View;
00672         typedef typename DataPoints::Label Label;
00673         typedef typename DataPoints::Labels Labels;
00674 
00675         const int pointsCount(cloud.features.cols());
00676         const int featDim(cloud.features.rows());
00677         const int descDim(cloud.descriptors.rows());
00678 
00679         int insertDim(0);
00680         if (averageExistingDescriptors)
00681         {
00682                 // TODO: this should be in the form of an assert
00683                 // Validate descriptors and labels
00684                 for(unsigned int i = 0; i < cloud.descriptorLabels.size(); i++)
00685                         insertDim += cloud.descriptorLabels[i].span;
00686                 if (insertDim != descDim)
00687                         throw InvalidField("SamplingSurfaceNormalDataPointsFilter: Error, descriptor labels do not match descriptor data");
00688         }
00689 
00690         // Compute space requirement for new descriptors
00691         const int dimNormals(featDim-1);
00692         const int dimDensities(1);
00693         const int dimEigValues(featDim-1);
00694         const int dimEigVectors((featDim-1)*(featDim-1));
00695 
00696         // Allocate space for new descriptors
00697         Labels cloudLabels;
00698         if (keepNormals)
00699                 cloudLabels.push_back(Label("normals", dimNormals));
00700         if (keepDensities)
00701                 cloudLabels.push_back(Label("densities", dimDensities));
00702         if (keepEigenValues)
00703                 cloudLabels.push_back(Label("eigValues", dimEigValues));
00704         if (keepEigenVectors)
00705                 cloudLabels.push_back(Label("eigVectors", dimEigVectors));
00706         cloud.allocateDescriptors(cloudLabels);
00707 
00708         // we keep build data on stack for reentrant behaviour
00709         View cloudExistingDescriptors(cloud.descriptors.block(0,0,cloud.descriptors.rows(),cloud.descriptors.cols()));
00710         BuildData buildData(cloud.features, cloud.descriptors);
00711 
00712         // get views
00713         if (keepNormals)
00714                 buildData.normals = cloud.getDescriptorViewByName("normals");
00715         if (keepDensities)
00716                 buildData.densities = cloud.getDescriptorViewByName("densities");
00717         if (keepEigenValues)
00718                 buildData.eigenValues = cloud.getDescriptorViewByName("eigValues");
00719         if (keepEigenVectors)
00720                 buildData.eigenVectors = cloud.getDescriptorViewByName("eigVectors");
00721         // build the new point cloud
00722         buildNew(
00723                 buildData,
00724                 0,
00725                 pointsCount,
00726                 cloud.features.rowwise().minCoeff(),
00727                 cloud.features.rowwise().maxCoeff()
00728         );
00729 
00730         // Bring the data we keep to the front of the arrays then
00731         // wipe the leftover unused space.
00732         std::sort(buildData.indicesToKeep.begin(), buildData.indicesToKeep.end());
00733         int ptsOut = buildData.indicesToKeep.size();
00734         for (int i = 0; i < ptsOut; i++){
00735                 int k = buildData.indicesToKeep[i];
00736                 assert(i <= k);
00737                 cloud.features.col(i) = cloud.features.col(k);
00738                 if (cloud.descriptors.rows() != 0)
00739                         cloud.descriptors.col(i) = cloud.descriptors.col(k);
00740                 if(keepNormals)
00741                         buildData.normals->col(i) = buildData.normals->col(k);
00742                 if(keepDensities)
00743                         (*buildData.densities)(0,i) = (*buildData.densities)(0,k);
00744                 if(keepEigenValues)
00745                         buildData.eigenValues->col(i) = buildData.eigenValues->col(k);
00746                 if(keepEigenVectors)
00747                         buildData.eigenVectors->col(i) = buildData.eigenVectors->col(k);
00748         }
00749         cloud.features.conservativeResize(Eigen::NoChange, ptsOut);
00750         cloud.descriptors.conservativeResize(Eigen::NoChange, ptsOut);
00751 
00752         // warning if some points were dropped
00753         if(buildData.unfitPointsCount != 0)
00754                 LOG_INFO_STREAM("  SamplingSurfaceNormalDataPointsFilter - Could not compute normal for " << buildData.unfitPointsCount << " pts.");
00755 }
00756 
00757 template<typename T>
00758 size_t argMax(const typename PointMatcher<T>::Vector& v)
00759 {
00760         T maxVal(0);
00761         size_t maxIdx(0);
00762         for (int i = 0; i < v.size(); ++i)
00763         {
00764                 if (v[i] > maxVal)
00765                 {
00766                         maxVal = v[i];
00767                         maxIdx = i;
00768                 }
00769         }
00770         return maxIdx;
00771 }
00772 
00773 template<typename T>
00774 void DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter::buildNew(BuildData& data, const int first, const int last, const Vector minValues, const Vector maxValues) const
00775 {
00776         const int count(last - first);
00777         if (count <= int(knn))
00778         {
00779                 // compute for this range
00780                 fuseRange(data, first, last);
00781                 // TODO: make another filter that creates constant-density clouds,
00782                 // typically by stopping recursion after the median of the bounding cuboid
00783                 // is below a threshold, or that the number of points falls under a threshold
00784                 return;
00785         }
00786 
00787         // find the largest dimension of the box
00788         const int cutDim = argMax<T>(maxValues - minValues);
00789 
00790         // compute number of elements
00791         const int rightCount(count/2);
00792         const int leftCount(count - rightCount);
00793         assert(last - rightCount == first + leftCount);
00794 
00795         // sort, hack std::nth_element
00796         std::nth_element(
00797                 data.indices.begin() + first,
00798                 data.indices.begin() + first + leftCount,
00799                 data.indices.begin() + last,
00800                 CompareDim(cutDim, data)
00801         );
00802 
00803         // get value
00804         const int cutIndex(data.indices[first+leftCount]);
00805         const T cutVal(data.features(cutDim, cutIndex));
00806 
00807         // update bounds for left
00808         Vector leftMaxValues(maxValues);
00809         leftMaxValues[cutDim] = cutVal;
00810         // update bounds for right
00811         Vector rightMinValues(minValues);
00812         rightMinValues[cutDim] = cutVal;
00813 
00814         // recurse
00815         buildNew(data, first, first + leftCount, minValues, leftMaxValues);
00816         buildNew(data, first + leftCount, last, rightMinValues, maxValues);
00817 }
00818 
00819 template<typename T>
00820 void DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter::fuseRange(BuildData& data, const int first, const int last) const
00821 {
00822         const int colCount(last-first);
00823         const int featDim(data.features.rows());
00824 
00825         // build nearest neighbors list
00826         Matrix d(featDim-1, colCount);
00827         for (int i = 0; i < colCount; ++i)
00828                 d.col(i) = data.features.block(0,data.indices[first+i],featDim-1, 1);
00829         const Vector box = d.rowwise().maxCoeff() - d.rowwise().minCoeff();
00830         const T boxDim(box.maxCoeff());
00831         // drop box if it is too large
00832         if (boxDim > maxBoxDim)
00833         {
00834                 data.unfitPointsCount += colCount;
00835                 return;
00836         }
00837         const Vector mean = d.rowwise().sum() / T(colCount);
00838         const Matrix NN = (d.colwise() - mean);
00839 
00840         // compute covariance
00841         const Matrix C(NN * NN.transpose());
00842         Vector eigenVa = Vector::Identity(featDim-1, 1);
00843         Matrix eigenVe = Matrix::Identity(featDim-1, featDim-1);
00844         // Ensure that the matrix is suited for eigenvalues calculation
00845         if(keepNormals || keepEigenValues || keepEigenVectors)
00846         {
00847                 if(C.fullPivHouseholderQr().rank()+1 >= featDim-1)
00848                 {
00849                         const Eigen::EigenSolver<Matrix> solver(C);
00850                         eigenVa = solver.eigenvalues().real();
00851                         eigenVe = solver.eigenvectors().real();
00852                 }
00853                 else
00854                 {
00855                         data.unfitPointsCount += colCount;
00856                         return;
00857                 }
00858         }
00859 
00860         Vector normal;
00861         if(keepNormals)
00862                 normal = SurfaceNormalDataPointsFilter::computeNormal(eigenVa, eigenVe);
00863 
00864         T densitie = 0;
00865         if(keepDensities)
00866                 densitie = SurfaceNormalDataPointsFilter::computeDensity(NN);
00867 
00868         //if(keepEigenValues) nothing to do
00869 
00870         Vector serialEigVector;
00871         if(keepEigenVectors)
00872                 serialEigVector = SurfaceNormalDataPointsFilter::serializeEigVec(eigenVe);
00873 
00874         // some safety check
00875         if(data.descriptors.rows() != 0)
00876                 assert(data.descriptors.cols() != 0);
00877 
00878         // Filter points randomly
00879         if(samplingMethod == 0)
00880         {
00881                 for(int i=0; i<colCount; i++)
00882                 {
00883                         const float r = (float)std::rand()/(float)RAND_MAX;
00884                         if(r < ratio)
00885                         {
00886                                 // Keep points with their descriptors
00887                                 int k = data.indices[first+i];
00888                                 // Mark the indices which will be part of the final data
00889                                 data.indicesToKeep.push_back(k);
00890 
00891                                 // Build new descriptors
00892                                 if(keepNormals)
00893                                         data.normals->col(k) = normal;
00894                                 if(keepDensities)
00895                                         (*data.densities)(0,k) = densitie;
00896                                 if(keepEigenValues)
00897                                         data.eigenValues->col(k) = eigenVa;
00898                                 if(keepEigenVectors)
00899                                         data.eigenVectors->col(k) = serialEigVector;
00900 
00901                         }
00902                 }
00903         }
00904         else
00905         {
00906 
00907                 int k = data.indices[first];
00908                 // Mark the indices which will be part of the final data
00909                 data.indicesToKeep.push_back(k);
00910                 data.features.col(k).topRows(featDim-1) = mean;
00911                 data.features(featDim-1, k) = 1;
00912 
00913                 if(data.descriptors.rows() != 0)
00914                 {
00915                         // average the existing descriptors
00916                         if (averageExistingDescriptors)
00917                         {
00918                                 Vector mergedDesc(Vector::Zero(data.descriptors.rows()));
00919                                 for (int i = 0; i < colCount; ++i)
00920                                         mergedDesc += data.descriptors.col(data.indices[first+i]);
00921                                 mergedDesc /= T(colCount);
00922                                 data.descriptors.col(k) = mergedDesc;
00923                         }
00924                         // else just keep the first one
00925                 }
00926 
00927                 // Build new descriptors
00928                 if(keepNormals)
00929                         data.normals->col(k) = normal;
00930                 if(keepDensities)
00931                         (*data.densities)(0,k) = densitie;
00932                 if(keepEigenValues)
00933                         data.eigenValues->col(k) = eigenVa;
00934                 if(keepEigenVectors)
00935                         data.eigenVectors->col(k) = serialEigVector;
00936 
00937         }
00938 
00939 }
00940 
00941 template struct DataPointsFiltersImpl<float>::SamplingSurfaceNormalDataPointsFilter;
00942 template struct DataPointsFiltersImpl<double>::SamplingSurfaceNormalDataPointsFilter;
00943 
00944 // OrientNormalsDataPointsFilter
00945 // Constructor
00946 template<typename T>
00947 DataPointsFiltersImpl<T>::OrientNormalsDataPointsFilter::OrientNormalsDataPointsFilter(const Parameters& params):
00948         DataPointsFilter("OrientNormalsDataPointsFilter", OrientNormalsDataPointsFilter::availableParameters(), params),
00949         towardCenter(Parametrizable::get<bool>("towardCenter"))
00950 {
00951 }
00952 
00953 // OrientNormalsDataPointsFilter
00954 // Compute
00955 template<typename T>
00956 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::OrientNormalsDataPointsFilter::filter(
00957         const DataPoints& input)
00958 {
00959         DataPoints output(input);
00960         inPlaceFilter(output);
00961         return output;
00962 }
00963 
00964 // In-place filter
00965 template<typename T>
00966 void DataPointsFiltersImpl<T>::OrientNormalsDataPointsFilter::inPlaceFilter(
00967         DataPoints& cloud)
00968 {
00969         if (!cloud.descriptorExists("normals"))
00970                 throw InvalidField("OrientNormalsDataPointsFilter: Error, cannot find normals in descriptors.");
00971         if (!cloud.descriptorExists("observationDirections"))
00972                 throw InvalidField("OrientNormalsDataPointsFilter: Error, cannot find observation directions in descriptors.");
00973 
00974         BOOST_AUTO(normals, cloud.getDescriptorViewByName("normals"));
00975         const BOOST_AUTO(observationDirections, cloud.getDescriptorViewByName("observationDirections"));
00976         assert(normals.rows() == observationDirections.rows());
00977         for (int i = 0; i < cloud.features.cols(); i++)
00978         {
00979                 // Check normal orientation
00980                 const Vector vecP = observationDirections.col(i);
00981                 const Vector vecN = normals.col(i);
00982                 const double scalar = vecP.dot(vecN);
00983 
00984                 // Swap normal
00985                 if(towardCenter)
00986                 {
00987                         if (scalar < 0)
00988                                 normals.col(i) = -vecN;
00989                 }
00990                 else
00991                 {
00992                         if (scalar > 0)
00993                                 normals.col(i) = -vecN;
00994                 }
00995         }
00996 
00997 }
00998 
00999 template struct DataPointsFiltersImpl<float>::OrientNormalsDataPointsFilter;
01000 template struct DataPointsFiltersImpl<double>::OrientNormalsDataPointsFilter;
01001 
01002 
01003 // RandomSamplingDataPointsFilter
01004 // Constructor
01005 template<typename T>
01006 DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter::RandomSamplingDataPointsFilter(const Parameters& params):
01007         DataPointsFilter("RandomSamplingDataPointsFilter", RandomSamplingDataPointsFilter::availableParameters(), params),
01008         prob(Parametrizable::get<double>("prob"))
01009 {
01010 }
01011 
01012 // Constructor
01013 template<typename T>
01014 DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter::RandomSamplingDataPointsFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
01015         DataPointsFilter(className, paramsDoc, params),
01016         prob(Parametrizable::get<double>("prob"))
01017 {
01018 }
01019 
01020 // Compute
01021 template<typename T>
01022 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter::filter(
01023         const DataPoints& input)
01024 {
01025         DataPoints output(input);
01026         inPlaceFilter(output);
01027         return output;
01028 }
01029 
01030 // In-place filter
01031 template<typename T>
01032 void DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter::inPlaceFilter(
01033         DataPoints& cloud)
01034 {
01035         const int nbPointsIn = cloud.features.cols();
01036 
01037         int j = 0;
01038         for (int i = 0; i < nbPointsIn; i++)
01039         {
01040                 const float r = (float)std::rand()/(float)RAND_MAX;
01041                 if (r < prob)
01042                 {
01043                         cloud.setColFrom(j, cloud, i);
01044                         j++;
01045                 }
01046         }
01047 
01048         cloud.conservativeResize(j);
01049 }
01050 
01051 template struct DataPointsFiltersImpl<float>::RandomSamplingDataPointsFilter;
01052 template struct DataPointsFiltersImpl<double>::RandomSamplingDataPointsFilter;
01053 
01054 
01055 // MaxPointCountDataPointsFilter
01056 // Constructor
01057 template<typename T>
01058 DataPointsFiltersImpl<T>::MaxPointCountDataPointsFilter::MaxPointCountDataPointsFilter(const Parameters& params):
01059         RandomSamplingDataPointsFilter("MaxPointCountDataPointsFilter", MaxPointCountDataPointsFilter::availableParameters(), params),
01060         maxCount(Parametrizable::get<unsigned>("maxCount"))
01061 {
01062 }
01063 
01064 // Compute
01065 template<typename T>
01066 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::MaxPointCountDataPointsFilter::filter(
01067         const DataPoints& input)
01068 {
01069         DataPoints output(input);
01070         inPlaceFilter(output);
01071         return output;
01072 }
01073 
01074 // In-place filter
01075 template<typename T>
01076 void DataPointsFiltersImpl<T>::MaxPointCountDataPointsFilter::inPlaceFilter(
01077         DataPoints& cloud)
01078 {
01079         if (unsigned(cloud.features.cols()) <= maxCount)
01080                 return;
01081         RandomSamplingDataPointsFilter::inPlaceFilter(cloud);
01082 }
01083 
01084 template struct DataPointsFiltersImpl<float>::MaxPointCountDataPointsFilter;
01085 template struct DataPointsFiltersImpl<double>::MaxPointCountDataPointsFilter;
01086 
01087 
01088 // FixStepSamplingDataPointsFilter
01089 // Constructor
01090 template<typename T>
01091 DataPointsFiltersImpl<T>::FixStepSamplingDataPointsFilter::FixStepSamplingDataPointsFilter(const Parameters& params):
01092         DataPointsFilter("FixStepSamplingDataPointsFilter", FixStepSamplingDataPointsFilter::availableParameters(), params),
01093         startStep(Parametrizable::get<unsigned>("startStep")),
01094         endStep(Parametrizable::get<unsigned>("endStep")),
01095         stepMult(Parametrizable::get<double>("stepMult")),
01096         step(startStep)
01097 {
01098         LOG_INFO_STREAM("Using FixStepSamplingDataPointsFilter with startStep=" << startStep << ", endStep=" << endStep << ", stepMult=" << stepMult);
01099 }
01100 
01101 
01102 template<typename T>
01103 void DataPointsFiltersImpl<T>::FixStepSamplingDataPointsFilter::init()
01104 {
01105         step = startStep;
01106 }
01107 
01108 // Compute
01109 template<typename T>
01110 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::FixStepSamplingDataPointsFilter::filter(
01111         const DataPoints& input)
01112 {
01113         DataPoints output(input);
01114         inPlaceFilter(output);
01115         return output;
01116 }
01117 
01118 // In-place filter
01119 template<typename T>
01120 void DataPointsFiltersImpl<T>::FixStepSamplingDataPointsFilter::inPlaceFilter(
01121         DataPoints& cloud)
01122 {
01123         const int iStep(step);
01124         const int nbPointsIn = cloud.features.cols();
01125         const int phase(rand() % iStep);
01126 
01127         int j = 0;
01128         for (int i = phase; i < nbPointsIn; i += iStep)
01129         {
01130                 cloud.setColFrom(j, cloud, i);
01131                 j++;
01132         }
01133 
01134         cloud.conservativeResize(j);
01135 
01136         const double deltaStep(startStep * stepMult - startStep);
01137         step *= stepMult;
01138         if (deltaStep < 0 && step < endStep)
01139                 step = endStep;
01140         if (deltaStep > 0 && step > endStep)
01141                 step = endStep;
01142 
01143 }
01144 
01145 template struct DataPointsFiltersImpl<float>::FixStepSamplingDataPointsFilter;
01146 template struct DataPointsFiltersImpl<double>::FixStepSamplingDataPointsFilter;
01147 
01148 
01149 // ShadowDataPointsFilter
01150 // Constructor
01151 template<typename T>
01152 DataPointsFiltersImpl<T>::ShadowDataPointsFilter::ShadowDataPointsFilter(const Parameters& params):
01153         DataPointsFilter("ShadowDataPointsFilter", ShadowDataPointsFilter::availableParameters(), params),
01154         eps(sin(Parametrizable::get<T>("eps")))
01155 {
01156         //waring: maxAngle is change to sin(maxAngle)!
01157 }
01158 
01159 
01160 // Compute
01161 template<typename T>
01162 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::ShadowDataPointsFilter::filter(
01163         const DataPoints& input)
01164 {
01165         DataPoints output(input);
01166         inPlaceFilter(output);
01167         return output;
01168 }
01169 
01170 // In-place filter
01171 template<typename T>
01172 void DataPointsFiltersImpl<T>::ShadowDataPointsFilter::inPlaceFilter(
01173         DataPoints& cloud)
01174 {
01175         // Check if normals are present
01176         if (!cloud.descriptorExists("normals"))
01177         {
01178                 throw InvalidField("ShadowDataPointsFilter, Error: cannot find normals in descriptors");
01179         }
01180 
01181         const int dim = cloud.features.rows();
01182 
01183         const BOOST_AUTO(normals, cloud.getDescriptorViewByName("normals"));
01184         int j = 0;
01185 
01186         for(int i=0; i < cloud.features.cols(); i++)
01187         {
01188                 const Vector normal = normals.col(i).normalized();
01189                 const Vector point = cloud.features.block(0, i, dim-1, 1).normalized();
01190 
01191                 const T value = anyabs(normal.dot(point));
01192 
01193                 if(value > eps) // test to keep the points
01194                 {
01195                         cloud.features.col(j) = cloud.features.col(i);
01196                         cloud.descriptors.col(j) = cloud.descriptors.col(i);
01197                         j++;
01198                 }
01199         }
01200 
01201         cloud.conservativeResize(j);
01202 }
01203 
01204 template struct DataPointsFiltersImpl<float>::ShadowDataPointsFilter;
01205 template struct DataPointsFiltersImpl<double>::ShadowDataPointsFilter;
01206 
01207 
01208 // SimpleSensorNoiseDataPointsFilter
01209 // Constructor
01210 template<typename T>
01211 DataPointsFiltersImpl<T>::SimpleSensorNoiseDataPointsFilter::SimpleSensorNoiseDataPointsFilter(const Parameters& params):
01212         DataPointsFilter("SimpleSensorNoiseDataPointsFilter", SimpleSensorNoiseDataPointsFilter::availableParameters(), params),
01213         sensorType(Parametrizable::get<unsigned>("sensorType")),
01214         gain(Parametrizable::get<T>("gain"))
01215 {
01216         std::vector<string> sensorNames = boost::assign::list_of ("Sick LMS-1xx")("Hokuyo URG-04LX")("Hokuyo UTM-30LX")("Kinect / Xtion");
01217         if (sensorType >= sensorNames.size())
01218         {
01219                 throw InvalidParameter(
01220                         (boost::format("SimpleSensorNoiseDataPointsFilter: Error, sensorType id %1% does not exist.") % sensorType).str());
01221         }
01222 
01223         LOG_INFO_STREAM("SimpleSensorNoiseDataPointsFilter - using sensor noise model: " << sensorNames[sensorType]);
01224 }
01225 
01226 
01227 // SimpleSensorNoiseDataPointsFilter
01228 // Compute
01229 template<typename T>
01230 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::SimpleSensorNoiseDataPointsFilter::filter(
01231         const DataPoints& input)
01232 {
01233         DataPoints output(input);
01234         inPlaceFilter(output);
01235         return output;
01236 }
01237 
01238 // In-place filter
01239 template<typename T>
01240 void DataPointsFiltersImpl<T>::SimpleSensorNoiseDataPointsFilter::inPlaceFilter(
01241         DataPoints& cloud)
01242 {
01243         cloud.allocateDescriptor("simpleSensorNoise", 1);
01244         BOOST_AUTO(noise, cloud.getDescriptorViewByName("simpleSensorNoise"));
01245 
01246         switch(sensorType)
01247         {
01248         case 0: // Sick LMS-1xx
01249         {
01250                 noise = computeLaserNoise(0.012, 0.0068, 0.0008, cloud.features);
01251                 break;
01252         }
01253         case 1: // Hokuyo URG-04LX
01254         {
01255                 noise = computeLaserNoise(0.028, 0.0013, 0.0001, cloud.features);
01256                 break;
01257         }
01258         case 2: // Hokuyo UTM-30LX
01259         {
01260                 noise = computeLaserNoise(0.018, 0.0006, 0.0015, cloud.features);
01261                 break;
01262         }
01263         case 3: // Kinect / Xtion
01264         {
01265                 const int dim = cloud.features.rows();
01266                 const Matrix squaredValues(cloud.features.topRows(dim-1).colwise().norm().array().square());
01267                 noise = squaredValues*(0.5*0.00285);
01268                 break;
01269         }
01270         default:
01271                 throw InvalidParameter(
01272                         (boost::format("SimpleSensorNoiseDataPointsFilter: Error, cannot compute noise for sensorType id %1% .") % sensorType).str());
01273         }
01274 
01275 }
01276 
01277 template<typename T>
01278 typename PointMatcher<T>::Matrix DataPointsFiltersImpl<T>::SimpleSensorNoiseDataPointsFilter::computeLaserNoise(const T minRadius, const T beamAngle, const T beamConst, const Matrix features)
01279 {
01280         typedef typename Eigen::Array<T, 2, Eigen::Dynamic> Array2rows;
01281 
01282         const int nbPoints = features.cols();
01283         const int dim = features.rows();
01284 
01285         Array2rows evalNoise = Array2rows::Constant(2, nbPoints, minRadius);
01286         evalNoise.row(0) =  beamAngle * features.topRows(dim-1).colwise().norm();
01287         evalNoise.row(0) += beamConst;
01288 
01289         return evalNoise.colwise().maxCoeff();
01290 
01291 }
01292 
01293 
01294 template struct DataPointsFiltersImpl<float>::SimpleSensorNoiseDataPointsFilter;
01295 template struct DataPointsFiltersImpl<double>::SimpleSensorNoiseDataPointsFilter;
01296 
01297 
01298 // ObservationDirectionDataPointsFilter
01299 // Constructor
01300 template<typename T>
01301 DataPointsFiltersImpl<T>::ObservationDirectionDataPointsFilter::ObservationDirectionDataPointsFilter(const Parameters& params):
01302         DataPointsFilter("ObservationDirectionDataPointsFilter", ObservationDirectionDataPointsFilter::availableParameters(), params),
01303         centerX(Parametrizable::get<T>("x")),
01304         centerY(Parametrizable::get<T>("y")),
01305         centerZ(Parametrizable::get<T>("z"))
01306 {
01307 }
01308 
01309 // Compute
01310 template<typename T>
01311 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::ObservationDirectionDataPointsFilter::filter(
01312         const DataPoints& input)
01313 {
01314         DataPoints output(input);
01315         inPlaceFilter(output);
01316         return output;
01317 }
01318 
01319 // In-place filter
01320 template<typename T>
01321 void DataPointsFiltersImpl<T>::ObservationDirectionDataPointsFilter::inPlaceFilter(
01322         DataPoints& cloud)
01323 {
01324         const int dim(cloud.features.rows() - 1);
01325         if (dim != 2 && dim != 3)
01326         {
01327                 throw InvalidField(
01328                         (boost::format("ObservationDirectionDataPointsFilter: Error, works only in 2 or 3 dimensions, cloud has %1% dimensions.") % dim).str()
01329                 );
01330         }
01331 
01332         Vector center(dim);
01333         center[0] = centerX;
01334         center[1] = centerY;
01335         if (dim == 3)
01336                 center[2] = centerZ;
01337 
01338         cloud.allocateDescriptor("observationDirections", dim);
01339         BOOST_AUTO(observationDirections, cloud.getDescriptorViewByName("observationDirections"));
01340 
01341         for (int i = 0; i < cloud.features.cols(); i++)
01342         {
01343                 // Check normal orientation
01344                 const Vector p(cloud.features.block(0, i, dim, 1));
01345                 observationDirections.col(i) = center - p;
01346         }
01347 
01348 }
01349 
01350 template struct DataPointsFiltersImpl<float>::ObservationDirectionDataPointsFilter;
01351 template struct DataPointsFiltersImpl<double>::ObservationDirectionDataPointsFilter;
01352 
01353 // VoxelGridDataPointsFilter
01354 template <typename T>
01355 DataPointsFiltersImpl<T>::VoxelGridDataPointsFilter::VoxelGridDataPointsFilter() :
01356         vSizeX(1),
01357         vSizeY(1),
01358         vSizeZ(1),
01359         useCentroid(true),
01360         averageExistingDescriptors(true) {}
01361 
01362 template <typename T>
01363 DataPointsFiltersImpl<T>::VoxelGridDataPointsFilter::VoxelGridDataPointsFilter(const Parameters& params) :
01364 DataPointsFilter("VoxelGridDataPointsFilter", VoxelGridDataPointsFilter::availableParameters(), params),
01365                 vSizeX(Parametrizable::get<T>("vSizeX")),
01366                 vSizeY(Parametrizable::get<T>("vSizeY")),
01367                 vSizeZ(Parametrizable::get<T>("vSizeZ")),
01368                 useCentroid(Parametrizable::get<bool>("useCentroid")),
01369                 averageExistingDescriptors(Parametrizable::get<bool>("averageExistingDescriptors"))
01370 {
01371 
01372 }
01373 
01374 template <typename T>
01375 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::VoxelGridDataPointsFilter::filter(const DataPoints& input)
01376 {
01377     DataPoints output(input);
01378         inPlaceFilter(output);
01379         return output;
01380 }
01381 
01382 template <typename T>
01383 void DataPointsFiltersImpl<T>::VoxelGridDataPointsFilter::inPlaceFilter(DataPoints& cloud)
01384 {
01385     const int numPoints(cloud.features.cols());
01386         const int featDim(cloud.features.rows());
01387         const int descDim(cloud.descriptors.rows());
01388 
01389         assert (featDim == 3 || featDim == 4);
01390 
01391         int insertDim(0);
01392         if (averageExistingDescriptors)
01393         {
01394                 // TODO: this should be in the form of an assert
01395                 // Validate descriptors and labels
01396                 for(unsigned int i = 0; i < cloud.descriptorLabels.size(); i++)
01397                         insertDim += cloud.descriptorLabels[i].span;
01398                 if (insertDim != descDim)
01399                         throw InvalidField("VoxelGridDataPointsFilter: Error, descriptor labels do not match descriptor data");
01400         }
01401 
01402         // TODO: Check that the voxel size is not too small, given the size of the data
01403 
01404         // Calculate number of divisions along each axis
01405         Vector minValues = cloud.features.rowwise().minCoeff();
01406         Vector maxValues = cloud.features.rowwise().maxCoeff();
01407 
01408     T minBoundX = minValues.x() / vSizeX;
01409     T maxBoundX = maxValues.x() / vSizeX;
01410     T minBoundY = minValues.y() / vSizeY;
01411     T maxBoundY = maxValues.y() / vSizeY;
01412     T minBoundZ = 0;
01413     T maxBoundZ = 0;
01414 
01415     if (featDim == 4)
01416     {
01417         minBoundZ = minValues.z() / vSizeZ;
01418         maxBoundZ = maxValues.z() / vSizeZ;
01419     }
01420 
01421     // number of divisions is total size / voxel size voxels of equal length + 1
01422     // with remaining space
01423     unsigned int numDivX = 1 + maxBoundX - minBoundX;
01424     unsigned int numDivY = 1 + maxBoundY - minBoundY;;
01425     unsigned int numDivZ = 0;
01426 
01427     // If a 3D point cloud
01428     if (featDim == 4 )
01429         numDivZ = 1 + maxBoundZ - minBoundZ;
01430 
01431     unsigned int numVox = numDivX * numDivY;
01432     if ( featDim == 4)
01433         numVox *= numDivZ;
01434 
01435     // Assume point cloud is randomly ordered
01436     // compute a linear index of the following type
01437     // i, j, k are the component indices
01438     // nx, ny number of divisions in x and y components
01439     // idx = i + j * nx + k * nx * ny
01440     std::vector<unsigned int> indices(numPoints);
01441 
01442     // vector to hold the first point in a voxel
01443     // this point will be ovewritten in the input cloud with
01444     // the output value
01445 
01446     std::vector<Voxel>* voxels;
01447 
01448     // try allocating vector. If too big return error
01449     try {
01450         voxels = new std::vector<Voxel>(numVox);
01451     } catch (std::bad_alloc&) {
01452         throw InvalidParameter((boost::format("VoxelGridDataPointsFilter: Memory allocation error with %1% voxels.  Try increasing the voxel dimensions.") % numVox).str());
01453     }
01454 
01455 
01456     for (int p = 0; p < numPoints; p++ )
01457     {
01458         unsigned int i = floor(cloud.features(0,p)/vSizeX - minBoundX);
01459         unsigned int j = floor(cloud.features(1,p)/vSizeY- minBoundY);
01460         unsigned int k = 0;
01461         unsigned int idx;
01462         if ( featDim == 4 )
01463         {
01464             k = floor(cloud.features(2,p)/vSizeZ - minBoundZ);
01465             idx = i + j * numDivX + k * numDivX * numDivY;
01466         }
01467         else
01468         {
01469             idx = i + j * numDivX;
01470         }
01471 
01472         unsigned int pointsInVox = (*voxels)[idx].numPoints + 1;
01473 
01474         if (pointsInVox == 1)
01475         {
01476             (*voxels)[idx].firstPoint = p;
01477         }
01478 
01479         (*voxels)[idx].numPoints = pointsInVox;
01480 
01481         indices[p] = idx;
01482 
01483     }
01484 
01485     // store which points contain voxel position
01486     std::vector<unsigned int> pointsToKeep;
01487 
01488     // Store voxel centroid in output
01489     if (useCentroid)
01490     {
01491         // Iterate through the indices and sum values to compute centroid
01492         for (int p = 0; p < numPoints ; p++)
01493         {
01494             unsigned int idx = indices[p];
01495             unsigned int firstPoint = (*voxels)[idx].firstPoint;
01496 
01497             // If this is the first point in the voxel, leave as is
01498             // if not sum up this point for centroid calculation
01499             if (firstPoint != p)
01500             {
01501                 // Sum up features and descriptors (if we are also averaging descriptors)
01502 
01503                 for (int f = 0; f < (featDim - 1); f++ )
01504                 {
01505                         cloud.features(f,firstPoint) += cloud.features(f,p);
01506                 }
01507 
01508                 if (averageExistingDescriptors) {
01509                         for (int d = 0; d < descDim; d++)
01510                         {
01511                                 cloud.descriptors(d,firstPoint) += cloud.descriptors(d,p);
01512                         }
01513                 }
01514             }
01515         }
01516 
01517         // Now iterating through the voxels
01518         // Normalize sums to get centroid (average)
01519         // Some voxels may be empty and are discarded
01520         for( int idx = 0; idx < numVox; idx++)
01521         {
01522             unsigned int numPoints = (*voxels)[idx].numPoints;
01523             unsigned int firstPoint = (*voxels)[idx].firstPoint;
01524             if(numPoints > 0)
01525             {
01526                 for ( int f = 0; f < (featDim - 1); f++ )
01527                     cloud.features(f,firstPoint) /= numPoints;
01528 
01529                 if (averageExistingDescriptors) {
01530                         for ( int d = 0; d < descDim; d++ )
01531                                 cloud.descriptors(d,firstPoint) /= numPoints;
01532                 }
01533 
01534                 pointsToKeep.push_back(firstPoint);
01535             }
01536         }
01537     }
01538     else
01539     {
01540         // Although we don't sum over the features, we may still need to sum the descriptors
01541         if (averageExistingDescriptors)
01542         {
01543                 // Iterate through the indices and sum values to compute centroid
01544                 for (int p = 0; p < numPoints ; p++)
01545                 {
01546                         unsigned int idx = indices[p];
01547                         unsigned int firstPoint = (*voxels)[idx].firstPoint;
01548 
01549                         // If this is the first point in the voxel, leave as is
01550                         // if not sum up this point for centroid calculation
01551                         if (firstPoint != p)
01552                         {
01553                                 for (int d = 0; d < descDim; d++ )
01554                                 {
01555                                         cloud.descriptors(d,firstPoint) += cloud.descriptors(d,p);
01556                                 }
01557                         }
01558                 }
01559         }
01560 
01561         for (int idx = 0; idx < numVox; idx++)
01562         {
01563             unsigned int numPoints = (*voxels)[idx].numPoints;
01564             unsigned int firstPoint = (*voxels)[idx].firstPoint;
01565 
01566             if (numPoints > 0)
01567             {
01568                 // get back voxel indices in grid format
01569                 // If we are in the last division, the voxel is smaller in size
01570                 // We adjust the center as from the end of the last voxel to the bounding area
01571                 unsigned int i = 0;
01572                 unsigned int j = 0;
01573                 unsigned int k = 0;
01574                 if (featDim == 4)
01575                 {
01576                     k = idx / (numDivX * numDivY);
01577                     if (k == numDivZ)
01578                         cloud.features(3,firstPoint) = maxValues.z() - (k-1) * vSizeZ/2;
01579                     else
01580                         cloud.features(3,firstPoint) = k * vSizeZ + vSizeZ/2;
01581                 }
01582 
01583                 j = (idx - k * numDivX * numDivY) / numDivX;
01584                 if (j == numDivY)
01585                     cloud.features(2,firstPoint) = maxValues.y() - (j-1) * vSizeY/2;
01586                 else
01587                     cloud.features(2,firstPoint) = j * vSizeY + vSizeY / 2;
01588 
01589                 i = idx - k * numDivX * numDivY - j * numDivX;
01590                 if (i == numDivX)
01591                     cloud.features(1,firstPoint) = maxValues.x() - (i-1) * vSizeX/2;
01592                 else
01593                     cloud.features(1,firstPoint) = i * vSizeX + vSizeX / 2;
01594 
01595                 // Descriptors : normalize if we are averaging or keep as is
01596                 if (averageExistingDescriptors) {
01597                         for ( int d = 0; d < descDim; d++ )
01598                                 cloud.descriptors(d,firstPoint) /= numPoints;
01599                 }
01600 
01601                 pointsToKeep.push_back(firstPoint);
01602             }
01603         }
01604 
01605     }
01606 
01607     // deallocate memory for voxels information
01608     delete voxels;
01609 
01610     // Move the points to be kept to the start
01611     // Bring the data we keep to the front of the arrays then
01612         // wipe the leftover unused space.
01613         std::sort(pointsToKeep.begin(), pointsToKeep.end());
01614         int numPtsOut = pointsToKeep.size();
01615         for (int i = 0; i < numPtsOut; i++){
01616                 int k = pointsToKeep[i];
01617                 assert(i <= k);
01618                 cloud.features.col(i) = cloud.features.col(k);
01619                 if (cloud.descriptors.rows() != 0)
01620                         cloud.descriptors.col(i) = cloud.descriptors.col(k);
01621         }
01622         cloud.features.conservativeResize(Eigen::NoChange, numPtsOut);
01623         
01624         if (cloud.descriptors.rows() != 0)
01625                 cloud.descriptors.conservativeResize(Eigen::NoChange, numPtsOut);
01626 }
01627 
01628 template struct DataPointsFiltersImpl<float>::VoxelGridDataPointsFilter;
01629 template struct DataPointsFiltersImpl<double>::VoxelGridDataPointsFilter;
01630 
01631 
01632 // CutAtDescriptorThresholdDataPointsFilter
01633 // Constructor
01634 template<typename T>
01635 DataPointsFiltersImpl<T>::CutAtDescriptorThresholdDataPointsFilter::CutAtDescriptorThresholdDataPointsFilter(const Parameters& params):
01636         DataPointsFilter("CutAtDescriptorThresholdDataPointsFilter", CutAtDescriptorThresholdDataPointsFilter::availableParameters(), params),
01637         descName(Parametrizable::get<std::string>("descName")),
01638         useLargerThan(Parametrizable::get<bool>("useLargerThan")),
01639         threshold(Parametrizable::get<T>("threshold"))
01640 {
01641 }
01642 
01643 // Compute
01644 template<typename T>
01645 typename PointMatcher<T>::DataPoints DataPointsFiltersImpl<T>::CutAtDescriptorThresholdDataPointsFilter::filter(
01646         const DataPoints& input)
01647 {
01648         DataPoints output(input);
01649         inPlaceFilter(output);
01650         return output;
01651 }
01652 
01653 // In-place filter
01654 template<typename T>
01655 void DataPointsFiltersImpl<T>::CutAtDescriptorThresholdDataPointsFilter::inPlaceFilter(
01656         DataPoints& cloud)
01657 {
01658         // Check field exists
01659         if (!cloud.descriptorExists(descName))
01660         {
01661                 throw InvalidField("CutAtDescriptorThresholdDataPointsFilter: Error, field not found in descriptors.");
01662         }
01663 
01664         const int nbPointsIn = cloud.features.cols();
01665         typename DataPoints::View values = cloud.getDescriptorViewByName(descName);
01666 
01667         // fill cloud values
01668         int j = 0;
01669         if (useLargerThan)
01670         {
01671                 for (int i = 0; i < nbPointsIn; i++)
01672                 {
01673                         const T value(values(0,i));
01674                         if (value <= threshold)
01675                         {
01676                                 cloud.setColFrom(j, cloud, i);
01677                                 j++;
01678                         }
01679                 }
01680         }
01681         else
01682         {
01683                 for (int i = 0; i < nbPointsIn; i++)
01684                 {
01685                         const T value(values(0,i));
01686                         if (value >= threshold)
01687                         {
01688                                 cloud.setColFrom(j, cloud, i);
01689                                 j++;
01690                         }
01691                 }
01692         }
01693         cloud.conservativeResize(j);
01694 }
01695 
01696 template struct DataPointsFiltersImpl<float>::CutAtDescriptorThresholdDataPointsFilter;
01697 template struct DataPointsFiltersImpl<double>::CutAtDescriptorThresholdDataPointsFilter;
01698 


upstream_src
Author(s):
autogenerated on Mon Oct 6 2014 10:27:39