DataPointsFiltersImpl.h
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 #ifndef __POINTMATCHER_DATAPOINTSFILTERS_H
00037 #define __POINTMATCHER_DATAPOINTSFILTERS_H
00038 
00039 #include "PointMatcher.h"
00040 
00041 template<typename T>
00042 struct DataPointsFiltersImpl
00043 {
00044         typedef PointMatcherSupport::Parametrizable Parametrizable;
00045         typedef PointMatcherSupport::Parametrizable P;
00046         typedef Parametrizable::Parameters Parameters;
00047         typedef Parametrizable::ParameterDoc ParameterDoc;
00048         typedef Parametrizable::ParametersDoc ParametersDoc;
00049         typedef Parametrizable::InvalidParameter InvalidParameter;
00050         
00051         typedef typename PointMatcher<T>::Vector Vector;
00052         typedef typename PointMatcher<T>::Matrix Matrix;        
00053         typedef typename PointMatcher<T>::DataPoints DataPoints;
00054         typedef typename PointMatcher<T>::DataPointsFilter DataPointsFilter;
00055         typedef typename PointMatcher<T>::DataPoints::InvalidField InvalidField;
00056         
00058         struct IdentityDataPointsFilter: public DataPointsFilter
00059         {
00060                 inline static const std::string description()
00061                 {
00062                         return "Does nothing.";
00063                 }
00064                 
00065                 //inline static const ParametersDoc availableParameters()
00066                 //{
00067                 //      return ParametersDoc({
00068                 //              ( "param1", "Description of the parameter", "defaultValue", "minValue", "maxValue", type of the parameter )
00069                 //              ) "param2", "Description of the parameter", "defaultValue", "minValue", "maxValue", type of the parameter )
00070                 //      ;
00071                 //}
00073                 //IdentityDataPointsFilter(const Parameters& params = Parameters());
00074                 
00075                 virtual DataPoints filter(const DataPoints& input);
00076                 virtual void inPlaceFilter(DataPoints& cloud);
00077         };
00078         
00079         
00081         struct RemoveNaNDataPointsFilter: public DataPointsFilter
00082         {
00083                 inline static const std::string description()
00084                 {
00085                         return "Remove points having NaN as coordinate.";
00086                 }
00087                 
00088                 virtual DataPoints filter(const DataPoints& input);
00089                 virtual void inPlaceFilter(DataPoints& cloud);
00090         };
00091         
00093         struct MaxDistDataPointsFilter: public DataPointsFilter
00094         {
00095                 inline static const std::string description()
00096                 {
00097                         return "Subsampling. Filter points beyond a maximum distance measured on a specific axis. If dim is set to -1, points are filtered based on a maximum radius.";
00098                 }
00099                 inline static const ParametersDoc availableParameters()
00100                 {
00101                         return boost::assign::list_of<ParameterDoc>
00102                                 ( "dim", "dimension on which the filter will be applied. x=0, y=1, z=2, radius=-1", "-1", "-1", "2", &P::Comp<int> )
00103                                 ( "maxDist", "maximum distance authorized. If dim is set to -1 (radius), the absolute value of minDist will be used. All points beyond that will be filtered.", "1", "-inf", "inf", &P::Comp<T> )
00104                         ;
00105                 }
00106 
00107                 const int dim;
00108                 const T maxDist;
00109                 
00111                 MaxDistDataPointsFilter(const Parameters& params = Parameters());
00112                 virtual DataPoints filter(const DataPoints& input);
00113                 virtual void inPlaceFilter(DataPoints& cloud);
00114         };
00115 
00117         struct MinDistDataPointsFilter: public DataPointsFilter
00118         {
00119                 inline static const std::string description()
00120                 {
00121                         return "Subsampling. Filter points before a minimum distance measured on a specific axis. If dim is set to -1, points are filtered based on a minimum radius.";
00122                 }
00123                 inline static const ParametersDoc availableParameters()
00124                 {
00125                         return boost::assign::list_of<ParameterDoc>
00126                                 ( "dim", "dimension on which the filter will be applied. x=0, y=1, z=2, radius=-1", "-1", "-1", "2", &P::Comp<int> )
00127                                 ( "minDist", "minimum value authorized. If dim is set to -1 (radius), the absolute value of minDist will be used. All points before that will be filtered.", "1", "-inf", "inf", &P::Comp<T> )
00128                         ;
00129                 }
00130                 
00131                 const int dim;
00132                 const T minDist;
00133 
00135                 MinDistDataPointsFilter(const Parameters& params = Parameters());
00136                 virtual DataPoints filter(const DataPoints& input);
00137                 virtual void inPlaceFilter(DataPoints& cloud);
00138         };
00139         
00141         struct BoundingBoxDataPointsFilter: public DataPointsFilter
00142         {
00143                 inline static const std::string description()
00144                 {
00145                         return "Subsampling. Remove points laying in a bounding box which is axis aligned.";
00146                 }
00147                 inline static const ParametersDoc availableParameters()
00148                 {
00149                         return boost::assign::list_of<ParameterDoc>
00150                                 ( "xMin", "minimum value on x-axis defining one side of the bounding box", "-1", "-inf", "inf", &P::Comp<T> )
00151                                 ( "xMax", "maximum value on x-axis defining one side of the bounding box", "1", "-inf", "inf", &P::Comp<T> )
00152                                 ( "yMin", "minimum value on y-axis defining one side of the bounding box", "-1", "-inf", "inf", &P::Comp<T> )
00153                                 ( "yMax", "maximum value on y-axis defining one side of the bounding box", "1", "-inf", "inf", &P::Comp<T> )
00154                                 ( "zMin", "minimum value on z-axis defining one side of the bounding box", "-1", "-inf", "inf", &P::Comp<T> )
00155                                 ( "zMax", "maximum value on z-axis defining one side of the bounding box", "1", "-inf", "inf", &P::Comp<T> )
00156                                 ( "removeInside", "If set to true (1), remove points inside the bounding box; else (0), remove points outside the bounding box", "1", "0", "1", P::Comp<bool> )
00157                         ;
00158                 }
00159 
00160                 const T xMin;
00161                 const T xMax;
00162                 const T yMin;
00163                 const T yMax;
00164                 const T zMin;
00165                 const T zMax;
00166                 const bool removeInside;
00167                 
00169                 BoundingBoxDataPointsFilter(const Parameters& params = Parameters());
00170                 virtual DataPoints filter(const DataPoints& input);
00171                 virtual void inPlaceFilter(DataPoints& cloud);
00172         };
00173 
00175         struct MaxQuantileOnAxisDataPointsFilter: public DataPointsFilter
00176         {
00177                 inline static const std::string description()
00178                 {
00179                         return "Subsampling. Filter points beyond a maximum quantile measured on a specific axis.";
00180                 }
00181                 inline static const ParametersDoc availableParameters()
00182                 {
00183                         return boost::assign::list_of<ParameterDoc>
00184                                 ( "dim", "dimension on which the filter will be applied. x=0, y=1, z=2", "0", "0", "2", &P::Comp<unsigned> )
00185                                 ( "ratio", "maximum quantile authorized. All points beyond that will be filtered.", "0.5", "0.0000001", "0.9999999", &P::Comp<T> )
00186                         ;
00187                 }
00188                 
00189                 const unsigned dim;
00190                 const T ratio;
00191                 
00193                 MaxQuantileOnAxisDataPointsFilter(const Parameters& params = Parameters());
00194                 virtual DataPoints filter(const DataPoints& input);
00195                 virtual void inPlaceFilter(DataPoints& cloud);
00196         };
00197 
00199         struct MaxDensityDataPointsFilter: public DataPointsFilter
00200         {
00201                 inline static const std::string description()
00202                 {
00203                         return "Subsampling. Reduce the points number by randomly removing points with a density highler than a treshold.";
00204                 }
00205                 inline static const ParametersDoc availableParameters()
00206                 {
00207                         return boost::assign::list_of<ParameterDoc>
00208                                 ( "maxDensity", "Maximum density of points to target. Unit: number of points per m^3.", "10", "0.0000001", "inf", &P::Comp<T> )
00209                         ;
00210                 }
00211                 
00212                 const T maxDensity;
00213                 
00215                 MaxDensityDataPointsFilter(const Parameters& params = Parameters());
00216                 virtual DataPoints filter(const DataPoints& input);
00217                 virtual void inPlaceFilter(DataPoints& cloud);
00218         };
00219 
00221         struct SurfaceNormalDataPointsFilter: public DataPointsFilter
00222         {
00223                 inline static const std::string description()
00224                 {
00225                         return "Normals. This filter extracts the normal to each point by taking the eigenvector corresponding to the smallest eigenvalue of its nearest neighbors.";
00226                 }
00227                 inline static const ParametersDoc availableParameters()
00228                 {
00229                         return boost::assign::list_of<ParameterDoc>
00230                                 ( "knn", "number of nearest neighbors to consider, including the point itself", "5", "3", "2147483647", &P::Comp<unsigned> )
00231                                 ( "epsilon", "approximation to use for the nearest-neighbor search", "0", "0", "inf", &P::Comp<T> )
00232                                 ( "keepNormals", "whether the normals should be added as descriptors to the resulting cloud", "1" )
00233                                 ( "keepDensities", "whether the point densities should be added as descriptors to the resulting cloud", "0" )
00234                                 ( "keepEigenValues", "whether the eigen values should be added as descriptors to the resulting cloud", "0" )
00235                                 ( "keepEigenVectors", "whether the eigen vectors should be added as descriptors to the resulting cloud", "0" )
00236                                 ( "keepMatchedIds" , "whethen the identifiers of matches points should be added as descriptors to the resulting cloud", "0" )
00237                         ;
00238                 }
00239                 
00240                 const unsigned knn;
00241                 const double epsilon;
00242                 const bool keepNormals;
00243                 const bool keepDensities;
00244                 const bool keepEigenValues;
00245                 const bool keepEigenVectors;
00246                 const bool keepMatchedIds;
00247 
00248                 SurfaceNormalDataPointsFilter(const Parameters& params = Parameters());
00249                 virtual ~SurfaceNormalDataPointsFilter() {};
00250                 virtual DataPoints filter(const DataPoints& input);
00251                 virtual void inPlaceFilter(DataPoints& cloud);
00252 
00253                 static Vector computeNormal(const Vector eigenVa, const Matrix eigenVe);
00254                 static T computeDensity(const Matrix NN);
00255                 static Vector serializeEigVec(const Matrix eigenVe);
00256         };
00257 
00259         struct SamplingSurfaceNormalDataPointsFilter: public DataPointsFilter
00260         {
00261                 inline static const std::string description()
00262                 {
00263                         return "Subsampling, Normals. This filter decomposes the point-cloud space in boxes, by recursively splitting the cloud through axis-aligned hyperplanes such as to maximize the evenness of the aspect ratio of the box. When the number of points in a box reaches a value knn or lower, the filter computes the center of mass of these points and its normal by taking the eigenvector corresponding to the smallest eigenvalue of all points in the box.";
00264                 }
00265                 inline static const ParametersDoc availableParameters()
00266                 {
00267                         return boost::assign::list_of<ParameterDoc>
00268                                 ( "ratio", "ratio of points to keep with random subsampling. Matrix (normal, density, etc.) will be associated to all points in the same bin.", "0.5", "0.0000001", "0.9999999", &P::Comp<T> )
00269                                 ( "knn", "determined how many points are used to compute the normals. Direct link with the rapidity of the computation (large = fast). Technically, limit over which a box is splitted in two", "7", "3", "2147483647", &P::Comp<unsigned> )
00270                                 ( "samplingMethod", "if set to 0, random subsampling using the parameter ratio. If set to 1, bin subsampling with the resulting number of points being 1/knn.", "0", "0", "1", &P::Comp<unsigned> )
00271                                 ( "maxBoxDim", "maximum length of a box above which the box is discarded", "inf" )
00272                                 ( "averageExistingDescriptors", "whether the filter keep the existing point descriptors and average them or should it drop them", "1" )
00273                                 ( "keepNormals", "whether the normals should be added as descriptors to the resulting cloud", "1" )
00274                                 ( "keepDensities", "whether the point densities should be added as descriptors to the resulting cloud", "0" )
00275                                 ( "keepEigenValues", "whether the eigen values should be added as descriptors to the resulting cloud", "0" )
00276                                 ( "keepEigenVectors", "whether the eigen vectors should be added as descriptors to the resulting cloud", "0" )
00277                         ;
00278                 }
00279                 
00280                 const T ratio;
00281                 const unsigned knn;
00282                 const unsigned samplingMethod; 
00283                 const T maxBoxDim;
00284                 const bool averageExistingDescriptors;
00285                 const bool keepNormals;
00286                 const bool keepDensities;
00287                 const bool keepEigenValues;
00288                 const bool keepEigenVectors;
00289                 
00290                 
00291         public:
00292                 SamplingSurfaceNormalDataPointsFilter(const Parameters& params = Parameters());
00293                 virtual ~SamplingSurfaceNormalDataPointsFilter() {}
00294                 virtual DataPoints filter(const DataPoints& input);
00295                 virtual void inPlaceFilter(DataPoints& cloud);
00296 
00297         protected:
00298                 struct BuildData
00299                 {
00300                         typedef std::vector<int> Indices;
00301                         typedef typename DataPoints::View View;
00302                         
00303                         Indices indices;
00304                         Indices indicesToKeep;
00305                         Matrix& features;
00306                         Matrix& descriptors;
00307                         boost::optional<View> normals;
00308                         boost::optional<View> densities;
00309                         boost::optional<View> eigenValues;
00310                         boost::optional<View> eigenVectors;
00311                         int outputInsertionPoint;
00312                         int unfitPointsCount;
00313 
00314                         BuildData(Matrix& features, Matrix& descriptors):
00315                                 features(features),
00316                                 descriptors(descriptors),
00317                                 unfitPointsCount(0)
00318                         {
00319                                 const int pointsCount(features.cols());
00320                                 indices.reserve(pointsCount);
00321                                 for (int i = 0; i < pointsCount; ++i)
00322                                         indices.push_back(i);
00323                         }
00324                 };
00325                 
00326                 struct CompareDim
00327                 {
00328                         const int dim;
00329                         const BuildData& buildData;
00330                         CompareDim(const int dim, const BuildData& buildData):dim(dim),buildData(buildData){}
00331                         bool operator() (const int& p0, const int& p1)
00332                         {
00333                                 return buildData.features(dim, p0) <
00334                                                 buildData.features(dim, p1);
00335                         }
00336                 };
00337                 
00338         protected:
00339                 void buildNew(BuildData& data, const int first, const int last, const Vector minValues, const Vector maxValues) const;
00340                 void fuseRange(BuildData& data, const int first, const int last) const;
00341         };
00342 
00344         struct OrientNormalsDataPointsFilter: public DataPointsFilter
00345         {
00346                 inline static const std::string description()
00347                 {
00348                         return "Normals. Reorient normals so that they all point in the same direction, with respect to the observation points.";
00349                 }
00350                 
00351                 inline static const ParametersDoc availableParameters()
00352                 {
00353                         return boost::assign::list_of<ParameterDoc>
00354                                 ( "towardCenter", "If set to true(1), all the normals will point inside the surface (i.e. toward the observation points).", "1", "0", "1", &P::Comp<bool> )
00355                         ;
00356                 }
00357 
00358                 OrientNormalsDataPointsFilter(const Parameters& params = Parameters());
00359                 virtual ~OrientNormalsDataPointsFilter() {};
00360                 virtual DataPoints filter(const DataPoints& input);
00361                 virtual void inPlaceFilter(DataPoints& cloud);
00362 
00363                 const bool towardCenter;
00364         };
00365 
00367         struct RandomSamplingDataPointsFilter: public DataPointsFilter
00368         {
00369                 inline static const std::string description()
00370                 {
00371                         return "Subsampling. This filter reduces the size of the point cloud by randomly dropping points. Based on \\cite{Masuda1996Random}";
00372                 }
00373                 inline static const ParametersDoc availableParameters()
00374                 {
00375                         return boost::assign::list_of<ParameterDoc>
00376                                 ( "prob", "probability to keep a point, one over decimation factor ", "0.75", "0", "1", &P::Comp<T> )
00377                         ;
00378                 }
00379                 
00380                 const double prob;
00381                 
00382                 RandomSamplingDataPointsFilter(const Parameters& params = Parameters());
00383                 virtual ~RandomSamplingDataPointsFilter() {};
00384                 virtual DataPoints filter(const DataPoints& input);
00385                 virtual void inPlaceFilter(DataPoints& cloud);
00386 
00387         protected:
00388                 RandomSamplingDataPointsFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00389 
00390         };
00391         
00393         struct MaxPointCountDataPointsFilter: public DataPointsFilter
00394         {
00395                 inline static const std::string description()
00396                 {
00397                         return "Conditional subsampling. This filter reduces the size of the point cloud by randomly dropping points if their number is above maxCount. Based on \\cite{Masuda1996Random}";
00398                 }
00399                 inline static const ParametersDoc availableParameters()
00400                 {
00401                         return boost::assign::list_of<ParameterDoc>
00402                                 ( "seed", "srand seed", "1", "0", "2147483647", &P::Comp<unsigned> )
00403                                 ( "maxCount", "maximum number of points", "1000", "0", "2147483647", &P::Comp<unsigned> )
00404                         ;
00405                 }
00406                 
00407                 const unsigned maxCount;
00408                 unsigned seed;
00409                 
00410                 MaxPointCountDataPointsFilter(const Parameters& params = Parameters());
00411                 virtual ~MaxPointCountDataPointsFilter() {};
00412                 virtual DataPoints filter(const DataPoints& input);
00413                 virtual void inPlaceFilter(DataPoints& cloud);
00414         };
00415 
00417         struct FixStepSamplingDataPointsFilter: public DataPointsFilter
00418         {
00419                 inline static const std::string description()
00420                 {
00421                         return "Subsampling. This filter reduces the size of the point cloud by only keeping one point over step ones; with step varying in time from startStep to endStep, each iteration getting multiplied by stepMult. If use as prefilter (i.e. before the iterations), only startStep is used.";
00422                 }
00423                 inline static const ParametersDoc availableParameters()
00424                 {
00425                         return boost::assign::list_of<ParameterDoc>
00426                                 ( "startStep", "initial number of point to skip (initial decimation factor)", "10", "1", "2147483647", &P::Comp<unsigned> )
00427                                 ( "endStep", "maximal or minimal number of points to skip (final decimation factor)", "10", "1", "2147483647", &P::Comp<unsigned> )
00428                                 ( "stepMult", "multiplication factor to compute the new decimation factor for each iteration", "1", "0.0000001", "inf", &P::Comp<double> )
00429                         ;
00430                 }
00431                 
00432                 // number of steps to skip
00433                 const unsigned startStep;
00434                 const unsigned endStep;
00435                 const double stepMult;
00436 
00437         protected:
00438                 double step;
00439                 
00440         public:
00441                 FixStepSamplingDataPointsFilter(const Parameters& params = Parameters());
00442                 virtual ~FixStepSamplingDataPointsFilter() {};
00443                 virtual void init();
00444                 virtual DataPoints filter(const DataPoints& input);
00445                 virtual void inPlaceFilter(DataPoints& cloud);
00446         };
00447 
00449         struct ShadowDataPointsFilter: public DataPointsFilter
00450         {
00451                 inline static const std::string description()
00452                 {
00453                         return "Remove ghost points appearing on edge discontinuties. Assume that the origine of the point cloud is close to where the laser center was. Requires surface normal for every points";
00454                 }
00455                 
00456                 inline static const ParametersDoc availableParameters()
00457                 {
00458                         return boost::assign::list_of<ParameterDoc>
00459                                 ( "eps", "Small angle (in rad) around which a normal shoudn't be observable", "0.1", "0.0", "3.1416", &P::Comp<T> )
00460                         ;
00461                 }
00462 
00463                 const T eps;
00464 
00466                 ShadowDataPointsFilter(const Parameters& params = Parameters());
00467                 
00468                 virtual DataPoints filter(const DataPoints& input);
00469                 virtual void inPlaceFilter(DataPoints& cloud);
00470         };
00471 
00473         struct SimpleSensorNoiseDataPointsFilter: public DataPointsFilter
00474         {
00475                 inline static const std::string description()
00476                 {
00477                         return "Add a 1D descriptor named <sensorNoise> that would represent the noise radius expressed in meter based on SICK LMS specifications \\cite{Pomerleau2012Noise}.";
00478                 }
00479                 
00480                 inline static const ParametersDoc availableParameters()
00481                 {
00482                         return boost::assign::list_of<ParameterDoc>
00483                                 ( "sensorType", "Type of the sensor used. Choices: 0=Sick LMS-1xx, 1=Hokuyo URG-04LX, 2=Hokuyo UTM-30LX, 3=Kinect/Xtion", "0", "0", "2147483647", &P::Comp<unsigned> )
00484                                 ( "gain", "If the point cloud is coming from an untrusty source, you can use the gain to augment the uncertainty", "1", "1", "inf", &P::Comp<T> )
00485                         ;
00486                 }
00487         
00488                 const unsigned sensorType;
00489                 const T gain;
00490                 
00492                 SimpleSensorNoiseDataPointsFilter(const Parameters& params = Parameters());
00493                 
00494                 virtual DataPoints filter(const DataPoints& input);
00495                 virtual void inPlaceFilter(DataPoints& cloud);
00496 
00497         private:
00502                 Matrix computeLaserNoise(const T minRadius, const T beamAngle, const T beamConst, const Matrix features);
00503 
00504         };
00505         
00507         struct ObservationDirectionDataPointsFilter: public DataPointsFilter
00508         {
00509                 inline static const std::string description()
00510                 {
00511                         return "Observation direction. This filter extracts observation directions (vector from point to sensor), considering a sensor at position (x,y,z).";
00512                 }
00513                 
00514                 inline static const ParametersDoc availableParameters()
00515                 {
00516                         return boost::assign::list_of<ParameterDoc>
00517                                 ( "x", "x-coordinate of sensor", "0" )
00518                                 ( "y", "y-coordinate of sensor", "0" )
00519                                 ( "z", "z-coordinate of sensor", "0" )
00520                         ;
00521                 }
00522         
00523                 const T centerX;
00524                 const T centerY;
00525                 const T centerZ;
00526         
00528                 ObservationDirectionDataPointsFilter(const Parameters& params = Parameters());
00529                 virtual DataPoints filter(const DataPoints& input);
00530                 virtual void inPlaceFilter(DataPoints& cloud);
00531         };
00532 
00533         struct VoxelGridDataPointsFilter : public DataPointsFilter
00534         {
00535         // Type definitions
00536                 typedef PointMatcher<T> PM;
00537                 typedef typename PM::DataPoints DataPoints;
00538                 typedef typename PM::DataPointsFilter DataPointsFilter;
00539 
00540                 typedef PointMatcherSupport::Parametrizable Parametrizable;
00541                 typedef PointMatcherSupport::Parametrizable P;
00542                 typedef Parametrizable::Parameters Parameters;
00543                 typedef Parametrizable::ParameterDoc ParameterDoc;
00544                 typedef Parametrizable::ParametersDoc ParametersDoc;
00545                 typedef Parametrizable::InvalidParameter InvalidParameter;
00546 
00547                 typedef typename PointMatcher<T>::Matrix Matrix;
00548                 typedef typename PointMatcher<T>::Vector Vector;
00549                 typedef typename Eigen::Matrix<T,2,1> Vector2;
00550                 typedef typename Eigen::Matrix<T,3,1> Vector3;
00551                 typedef typename PointMatcher<T>::DataPoints::InvalidField InvalidField;
00552 
00553         // Destr
00554                 virtual ~VoxelGridDataPointsFilter() {};
00555 
00556                 inline static const std::string description()
00557                 {
00558                         return "Construct Voxel grid of the point cloud. Down-sample by taking centroid or center of grid cells./n";
00559                 }
00560 
00561                 inline static const ParametersDoc availableParameters()
00562                 {
00563                         return boost::assign::list_of<ParameterDoc>
00564                         ( "vSizeX", "Dimension of each voxel cell in x direction", "1.0", "-inf", "inf", &P::Comp<T> )
00565                         ( "vSizeY", "Dimension of each voxel cell in y direction", "1.0", "-inf", "inf", &P::Comp<T> )
00566                         ( "vSizeZ", "Dimension of each voxel cell in z direction", "1.0", "-inf", "inf", &P::Comp<T> )
00567                         ( "useCentroid", "If 1 (true), down-sample by using centroid of voxel cell.  If false (0), use center of voxel cell.", "1", "0", "1", P::Comp<bool> )
00568                         ( "averageExistingDescriptors", "whether the filter keep the existing point descriptors and average them or should it drop them", "1", "0", "1", P::Comp<bool> )
00569                         ;
00570                 }
00571 
00572                 const T vSizeX;
00573                 const T vSizeY;
00574                 const T vSizeZ;
00575                 const bool useCentroid;
00576                 const bool averageExistingDescriptors;
00577 
00578                 struct Voxel {
00579                         unsigned int    numPoints;
00580                         unsigned int    firstPoint;
00581                         Voxel() : numPoints(0), firstPoint(0) {}
00582                 };
00583 
00584                 //Constructor, uses parameter interface
00585                 VoxelGridDataPointsFilter(const Parameters& params = Parameters());
00586 
00587                 VoxelGridDataPointsFilter();
00588 
00589                 virtual DataPoints filter(const DataPoints& input);
00590                 virtual void inPlaceFilter(DataPoints& cloud);
00591 
00592         };      
00593 
00595         struct CutAtDescriptorThresholdDataPointsFilter: public DataPointsFilter
00596         {
00597                 inline static const std::string description()
00598                 {
00599                         return "Subsampling. Cut points with value of a given descriptor above or below a given threshold.";
00600                 }
00601                 inline static const ParametersDoc availableParameters()
00602                 {
00603                         return boost::assign::list_of<ParameterDoc>
00604                                 ( "descName", "Descriptor name used to cut points", "none")
00605                                 ( "useLargerThan", "If set to 1 (true), points with values above the 'threshold' will be cut.  If set to 0 (false), points with values below the 'threshold' will be cut.", "1", "0", "1", P::Comp<bool>)
00606                                 ( "threshold", "Value at which to cut.", "0", "-inf", "inf", &P::Comp<T>)
00607                         ;
00608                 }
00609                 
00610                 const std::string descName; 
00611                 const bool useLargerThan;
00612                 const T threshold;
00613                 
00615                 CutAtDescriptorThresholdDataPointsFilter(const Parameters& params = Parameters());
00616                 virtual DataPoints filter(const DataPoints& input);
00617                 virtual void inPlaceFilter(DataPoints& cloud);
00618         };
00619 
00620 }; // DataPointsFiltersImpl
00621 
00622 #endif // __POINTMATCHER_DATAPOINTSFILTERS_H


libpointmatcher
Author(s):
autogenerated on Mon Sep 14 2015 02:59:04