24 icp.readingDataPointsFilters.clear();
32 std::shared_ptr<PM::DataPointsFilter> testedDataPointFilter =
33 PM::get().DataPointsFilterRegistrar.create(name, params);
35 icp.readingDataPointsFilters.push_back(testedDataPointFilter);
40 std::shared_ptr<PM::DataPointsFilter> testedDataPointFilter =
41 PM::get().DataPointsFilterRegistrar.create(name);
43 icp.readingDataPointsFilters.push_back(testedDataPointFilter);
48 const int dimFeatures = 4;
49 const int dimDescriptors = 3;
50 const int dimTime = 2;
52 PM::Matrix randFeat = PM::Matrix::Random(dimFeatures, nbPoints);
57 featLabels.push_back(
DP::Label(
"pad", 1));
59 PM::Matrix randDesc = PM::Matrix::Random(dimDescriptors, nbPoints);
61 descLabels.push_back(
DP::Label(
"dummyDesc", 3));
65 timeLabels.push_back(
DP::Label(
"dummyTime", 2));
68 DP pointCloud =
DP(randFeat, featLabels, randDesc, descLabels, randTimes, timeLabels);
80 addFilter(
"IdentityDataPointsFilter");
81 icp.readingDataPointsFilters.apply(ref2DCopy);
90 const float nan(std::numeric_limits<float>::quiet_NaN());
91 for (
int i(0); i < ref2DCopy.
features.cols(); ++i)
102 addFilter(
"RemoveNaNDataPointsFilter");
103 icp.readingDataPointsFilters.apply(ref2DCopy);
116 icp.readingDataPointsFilters.clear();
117 addFilter(
"MaxDistDataPointsFilter",
params);
118 validate2dTransformation();
119 validate3dTransformation();
123 icp.readingDataPointsFilters.clear();
124 addFilter(
"MaxDistDataPointsFilter",
params);
125 validate2dTransformation();
126 validate3dTransformation();
130 icp.readingDataPointsFilters.clear();
131 addFilter(
"MaxDistDataPointsFilter",
params);
133 validate3dTransformation();
137 icp.readingDataPointsFilters.clear();
138 addFilter(
"MaxDistDataPointsFilter",
params);
139 validate2dTransformation();
140 validate3dTransformation();
158 icp.readingDataPointsFilters.clear();
159 addFilter(
"MinDistDataPointsFilter",
params);
160 validate2dTransformation();
161 validate3dTransformation();
165 icp.readingDataPointsFilters.clear();
166 addFilter(
"MinDistDataPointsFilter",
params);
167 validate2dTransformation();
168 validate3dTransformation();
173 icp.readingDataPointsFilters.clear();
174 addFilter(
"MinDistDataPointsFilter",
params);
176 validate3dTransformation();
180 icp.readingDataPointsFilters.clear();
181 addFilter(
"MinDistDataPointsFilter",
params);
182 validate2dTransformation();
183 validate3dTransformation();
190 string ratio =
"0.95";
197 icp.readingDataPointsFilters.clear();
198 addFilter(
"MaxQuantileOnAxisDataPointsFilter",
params);
199 validate2dTransformation();
200 validate3dTransformation();
204 icp.readingDataPointsFilters.clear();
205 addFilter(
"MaxQuantileOnAxisDataPointsFilter",
params);
206 validate2dTransformation();
207 validate3dTransformation();
211 icp.readingDataPointsFilters.clear();
212 addFilter(
"MaxQuantileOnAxisDataPointsFilter",
params);
214 validate3dTransformation();
224 params[
"epsilon"] =
"0.1";
225 params[
"keepNormals"] =
"1";
226 params[
"keepDensities"] =
"1";
227 params[
"keepEigenValues"] =
"1";
228 params[
"keepEigenVectors"] =
"1" ;
229 params[
"keepMatchedIds"] =
"1" ;
232 addFilter(
"SurfaceNormalDataPointsFilter",
params);
233 validate2dTransformation();
234 validate3dTransformation();
245 vector<double> ratio = {100, 1000, 5000};
247 for(
unsigned i=0; i < ratio.size(); i++)
249 icp.readingDataPointsFilters.clear();
252 params[
"epsilon"] =
"0.1";
253 params[
"keepNormals"] =
"0";
254 params[
"keepDensities"] =
"1";
255 params[
"keepEigenValues"] =
"0";
256 params[
"keepEigenVectors"] =
"0" ;
257 params[
"keepMatchedIds"] =
"0" ;
259 addFilter(
"SurfaceNormalDataPointsFilter",
params);
264 addFilter(
"MaxDensityDataPointsFilter",
params);
273 validate3dTransformation();
276 double nbRemainingPts =
icp.getPrefilteredReadingPtsCount();
286 params[
"averageExistingDescriptors"] =
"1";
287 params[
"keepNormals"] =
"1";
288 params[
"keepDensities"] =
"1";
289 params[
"keepEigenValues"] =
"1";
290 params[
"keepEigenVectors"] =
"1";
292 addFilter(
"SamplingSurfaceNormalDataPointsFilter",
params);
293 validate2dTransformation();
294 validate3dTransformation();
330 params[
"averageExistingDescriptors"] =
"1";
331 params[
"keepNormals"] =
"1";
332 params[
"keepEigenValues"] =
"1";
333 params[
"keepEigenVectors"] =
"1";
334 params[
"maxBoxDim"] =
"1";
335 params[
"keepMeans"] =
"1";
336 params[
"keepCovariances"] =
"1";
337 params[
"keepGestaltFeatures"] =
"1";
341 addFilter(
"GestaltDataPointsFilter",
params);
342 validate3dTransformation();
348 std::shared_ptr<PM::DataPointsFilter> extraDataPointFilter;
349 extraDataPointFilter =
PM::get().DataPointsFilterRegistrar.create(
350 "SurfaceNormalDataPointsFilter");
351 icp.readingDataPointsFilters.push_back(extraDataPointFilter);
352 addFilter(
"ObservationDirectionDataPointsFilter");
353 addFilter(
"OrientNormalsDataPointsFilter", {
354 {
"towardCenter",
toParam(
false)}
357 validate2dTransformation();
358 validate3dTransformation();
364 for(
const double prob : {0.8, 0.85, 0.9, 0.95})
366 for(
const unsigned int samplingMethod : {0, 1})
373 icp.readingDataPointsFilters.clear();
374 addFilter(
"RandomSamplingDataPointsFilter",
params);
375 validate2dTransformation();
376 validate3dTransformation();
383 vector<unsigned> steps = {1, 2, 3};
384 for(
unsigned i=0; i<steps.size(); i++)
390 icp.readingDataPointsFilters.clear();
391 addFilter(
"FixStepSamplingDataPointsFilter",
params);
392 validate2dTransformation();
393 validate3dTransformation();
401 const size_t maxCount = 1000;
407 std::shared_ptr<PM::DataPointsFilter> maxPtsFilter =
408 PM::get().DataPointsFilterRegistrar.create(
"MaxPointCountDataPointsFilter",
params);
410 DP filteredCloud = maxPtsFilter->filter(cloud);
420 DP filteredCloud2 = maxPtsFilter->filter(cloud);
429 std::shared_ptr<PM::DataPointsFilter> maxPtsFilter2 =
430 PM::get().DataPointsFilterRegistrar.create(
"MaxPointCountDataPointsFilter",
params);
432 DP filteredCloud3 = maxPtsFilter2->filter(cloud);
443 icp.readingDataPointsFilters.clear();
444 addFilter(
"MaxPointCountDataPointsFilter",
params);
445 validate2dTransformation();
446 validate3dTransformation();
451 const unsigned int nbPts = 60000;
452 const DP cloud = generateRandomDataPoints(nbPts);
455 std::shared_ptr<PM::DataPointsFilter> octreeFilter;
457 for(
const int meth : {0,1,2,3})
458 for(
const size_t maxData : {1,5})
459 for(
const float maxSize : {0.,0.05})
465 params[
"buildParallel"] =
"1";
467 octreeFilter =
PM::get().DataPointsFilterRegistrar.create(
"OctreeGridDataPointsFilter",
params);
469 const DP filteredCloud = octreeFilter->filter(cloud);
471 if(maxData==1 and maxSize==0.)
489 icp.readingDataPointsFilters.clear();
490 addFilter(
"OctreeGridDataPointsFilter",
params);
491 validate2dTransformation();
492 validate3dTransformation();
498 const size_t nbPts = 60000;
499 DP cloud = generateRandomDataPoints(nbPts);
505 std::shared_ptr<PM::DataPointsFilter> nssFilter;
509 paramsNorm[
"knn"] =
"5";
510 paramsNorm[
"epsilon"] =
"0.1";
511 paramsNorm[
"keepNormals"] =
"1";
512 std::shared_ptr<PM::DataPointsFilter> normalFilter =
PM::get().DataPointsFilterRegistrar.create(
"SurfaceNormalDataPointsFilter", paramsNorm);
514 normalFilter->inPlaceFilter(cloud);
517 std::vector<size_t> samples = { 1500, 5000, nbPts, nbPts3D};
518 for(
const float epsilon : {M_PI/6., M_PI/32., M_PI/64.})
519 for(
const size_t nbSample : samples)
521 icp.readingDataPointsFilters.clear();
527 nssFilter =
PM::get().DataPointsFilterRegistrar.create(
"NormalSpaceDataPointsFilter",
params);
529 addFilter(
"SurfaceNormalDataPointsFilter", paramsNorm);
530 addFilter(
"NormalSpaceDataPointsFilter",
params);
532 const DP filteredCloud = nssFilter->filter(cloud);
546 if (nbSample == nbPts)
556 validate3dTransformation();
563 const size_t nbPts = 60000;
564 DP cloud = generateRandomDataPoints(nbPts);
569 std::shared_ptr<PM::DataPointsFilter> covsFilter;
573 paramsNorm[
"knn"] =
"5";
574 paramsNorm[
"epsilon"] =
"0.1";
575 paramsNorm[
"keepNormals"] =
"1";
576 std::shared_ptr<PM::DataPointsFilter> normalFilter =
PM::get().DataPointsFilterRegistrar.create(
"SurfaceNormalDataPointsFilter", paramsNorm);
578 normalFilter->inPlaceFilter(cloud);
581 std::vector<size_t> samples = {500, 1500, 5000, nbPts, nbPts3D};
582 for(
const size_t nbSample : samples)
584 icp.readingDataPointsFilters.clear();
589 covsFilter =
PM::get().DataPointsFilterRegistrar.create(
"CovarianceSamplingDataPointsFilter",
params);
591 addFilter(
"SurfaceNormalDataPointsFilter", paramsNorm);
592 addFilter(
"CovarianceSamplingDataPointsFilter",
params);
594 const DP filteredCloud = covsFilter->filter(cloud);
596 if (nbSample == nbPts3D)
600 else if (nbSample == nbPts)
610 validate3dTransformation();
618 DP cloud = generateRandomDataPoints();
627 std::shared_ptr<PM::DataPointsFilter> voxelFilter =
628 PM::get().DataPointsFilterRegistrar.create(
"VoxelGridDataPointsFilter",
params);
630 DP filteredCloud = voxelFilter->filter(cloud);
637 vector<bool> useCentroid = {
false,
true};
638 vector<bool> averageExistingDescriptors = {
false,
true};
639 for (
unsigned i = 0 ; i < useCentroid.size() ; i++)
641 for (
unsigned j = 0; j < averageExistingDescriptors.size(); j++)
644 params[
"vSizeX"] =
"0.02";
645 params[
"vSizeY"] =
"0.02";
646 params[
"vSizeZ"] =
"0.02";
650 icp.readingDataPointsFilters.clear();
651 addFilter(
"VoxelGridDataPointsFilter",
params);
652 validate2dTransformation();
656 for (
unsigned i = 0 ; i < useCentroid.size() ; i++)
658 for (
unsigned j = 0; j < averageExistingDescriptors.size(); j++)
667 icp.readingDataPointsFilters.clear();
668 addFilter(
"VoxelGridDataPointsFilter",
params);
669 validate3dTransformation();
677 vector<double> thresholds = {100, 1000, 5000};
681 icp.readingDataPointsFilters.clear();
684 params[
"epsilon"] =
"0.1";
685 params[
"keepNormals"] =
"0";
686 params[
"keepDensities"] =
"1";
687 params[
"keepEigenValues"] =
"0";
688 params[
"keepEigenVectors"] =
"0";
689 params[
"keepMatchedIds"] =
"0";
692 addFilter(
"SurfaceNormalDataPointsFilter",
params);
693 icp.readingDataPointsFilters.apply(ref3Ddensities);
695 for(
unsigned i=0; i < thresholds.size(); i++)
702 for (
unsigned j=0; j < densities.cols(); ++j)
704 if (densities(0, j) <= thresholds[i])
708 if (densities(0, j) >= thresholds[i])
714 for(
bool useLargerThan(
true); useLargerThan; useLargerThan=
false)
716 DP ref3DCopy = ref3Ddensities;
718 icp.readingDataPointsFilters.clear();
725 addFilter(
"CutAtDescriptorThresholdDataPointsFilter",
params);
726 icp.readingDataPointsFilters.apply(ref3DCopy);
744 params[
"removeInside"] =
"0";
748 icp.readingDataPointsFilters.clear();
749 addFilter(
"DistanceLimitDataPointsFilter",
params);
750 validate2dTransformation();
751 validate3dTransformation();
755 icp.readingDataPointsFilters.clear();
756 addFilter(
"DistanceLimitDataPointsFilter",
params);
757 validate2dTransformation();
758 validate3dTransformation();
762 icp.readingDataPointsFilters.clear();
763 addFilter(
"DistanceLimitDataPointsFilter",
params);
765 validate3dTransformation();
769 icp.readingDataPointsFilters.clear();
770 addFilter(
"DistanceLimitDataPointsFilter",
params);
771 validate2dTransformation();
772 validate3dTransformation();
783 params[
"removeInside"] =
"1";
787 icp.readingDataPointsFilters.clear();
788 addFilter(
"DistanceLimitDataPointsFilter",
params);
789 validate2dTransformation();
790 validate3dTransformation();
794 icp.readingDataPointsFilters.clear();
795 addFilter(
"DistanceLimitDataPointsFilter",
params);
796 validate2dTransformation();
797 validate3dTransformation();
802 icp.readingDataPointsFilters.clear();
803 addFilter(
"DistanceLimitDataPointsFilter",
params);
805 validate3dTransformation();
809 icp.readingDataPointsFilters.clear();
810 addFilter(
"DistanceLimitDataPointsFilter",
params);
811 validate2dTransformation();
812 validate3dTransformation();
819 std::shared_ptr<PM::DataPointsFilter> df =
PM::get().DataPointsFilterRegistrar.create(
"MaxPointCountDataPointsFilter",
params);
821 icp.referenceDataPointsFilters.push_back(df);
822 icp.readingDataPointsFilters.push_back(df);
827 const size_t nbPts = 6;
828 const double expectedErrors_LMS1xx[6] = {0., -0.0015156, -0.059276,
829 0., -0.002311, -0.163689};
830 const double expectedErrors_HDL32E[6] = {0., -0.002945, -0.075866,
831 0., -0.002998,-0.082777 };
835 0, 0, 0, 0, 0, 0).finished();
837 pointsLabels.push_back(
DP::Label(
"x", 1));
838 pointsLabels.push_back(
DP::Label(
"y", 1));
839 pointsLabels.push_back(
DP::Label(
"z", 1));
840 pointsLabels.push_back(
DP::Label(
"pad", 1));
843 -1, -1, -1, -5, -5, -5,
845 0, 0, 0, 0, 0, 0).finished();
848 -1, -1, -1, -5, -5, -5,
850 0, 0, 0, 0, 0, 0).finished();
852 descLabels.push_back(
DP::Label(
"incidenceAngles", 1));
853 descLabels.push_back(
DP::Label(
"observationDirections", 3));
857 timeLabels.push_back(
DP::Label(
"dummyTime", 2));
860 DP pointCloud =
DP(points, pointsLabels, desc, descLabels, randTimes, timeLabels);
864 parameters[
"sensorType"] =
toParam(0);
865 std::shared_ptr<PM::DataPointsFilter> removeSensorBiasFilter =
PM::get().DataPointsFilterRegistrar.create(
"RemoveSensorBiasDataPointsFilter", parameters);
866 DP resultCloud = removeSensorBiasFilter->filter(pointCloud);
869 for(std::size_t i = 0; i< nbPts; ++i)
871 const double error = pointCloud.
features.col(i).norm() - resultCloud.
features.col(i).norm();
872 EXPECT_NEAR(expectedErrors_LMS1xx[i], error, 1e-3);
875 parameters[
"sensorType"] =
toParam(1);
876 removeSensorBiasFilter =
PM::get().DataPointsFilterRegistrar.create(
"RemoveSensorBiasDataPointsFilter", parameters);
877 resultCloud = removeSensorBiasFilter->filter(pointCloud);
879 for(std::size_t i = 0; i< nbPts; ++i)
881 const double error = pointCloud.
features.col(i).norm() - resultCloud.
features.col(i).norm();
882 EXPECT_NEAR(expectedErrors_HDL32E[i], error, 1e-4);
887 pointCloud =
DP(points, pointsLabels, desc2, descLabels, randTimes, timeLabels);
889 parameters[
"sensorType"] =
toParam(0);
890 parameters[
"angleThreshold"] =
toParam(30.);
891 removeSensorBiasFilter =
PM::get().DataPointsFilterRegistrar.create(
"RemoveSensorBiasDataPointsFilter", parameters);
892 resultCloud = removeSensorBiasFilter->filter(pointCloud);
904 params[
"keepNormals"] =
"1";
905 params[
"keepLabels"] =
"1";
906 params[
"keepTensors"] =
"1";
908 addFilter(
"SaliencyDataPointsFilter",
params);
909 validate3dTransformation();
914 using DPFiltersPtr = std::shared_ptr<PM::DataPointsFilter>;
917 DP cloud = generateRandomDataPoints(300000);
925 params[
"keepNormals"] =
"1";
926 params[
"keepLabels"] =
"1";
927 params[
"keepLambdas"] =
"1";
928 params[
"keepTensors"] =
"1";
930 DPFiltersPtr spdf =
PM::get().DataPointsFilterRegistrar.create(
931 "SpectralDecompositionDataPointsFilter",
params 934 DP filteredCloud = spdf->filter(cloud);
942 params[
"sigma"] =
"1.";
943 params[
"radius"] =
"2.";
944 params[
"itMax"] =
"15";
945 params[
"keepNormals"] =
"1";
946 params[
"keepLabels"] =
"1";
947 params[
"keepLambdas"] =
"1";
948 params[
"keepTensors"] =
"1";
950 addFilter(
"SpectralDecompositionDataPointsFilter", params);
951 validate3dTransformation();
Subsampling. Filter points beyond a maximum distance measured on a specific axis. ...
Subsampling. Filter points based on distance measured on a specific axis.
unsigned getTimeDim() const
Return the total number of times.
IdentityDataPointsFilter, does nothing.
std::string toParam(const S &value)
Return the a string value using lexical_cast.
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
Remove points having NaN as coordinate.
unsigned getNbPoints() const
Return the number of points contained in the point cloud.
Maximum number of points.
#define EXPECT_GE(val1, val2)
DP generateRandomDataPoints(int nbPoints=100)
#define EXPECT_ANY_THROW(statement)
Subsampling. Cut points with value of a given descriptor above or below a given threshold.
The name for a certain number of dim.
Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Parametrizable::Parameters Parameters
alias
#define EXPECT_GT(val1, val2)
#define EXPECT_NEAR(val1, val2, abs_error)
Functions and classes that are not dependant on scalar type are defined in this namespace.
void addFilter(string name, PM::Parameters params)
Sampling surface normals. First decimate the space until there is at most knn points, then find the center of mass and use the points to estimate nromal using eigen-decomposition.
static const PointMatcher & get()
Return instances.
void addFilter(string name)
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
A dense signed 64-bits matrix.
Data Filter based on Octree representation.
#define EXPECT_EQ(expected, actual)
Gestalt descriptors filter as described in Bosse & Zlot ICRA 2013.
TEST_F(DataFilterTest, IdentityDataPointsFilter)
Surface normals estimation. Find the normal for every point using eigen-decomposition of neighbour po...
#define EXPECT_TRUE(condition)
Subsampling. Filter points beyond a maximum quantile measured on a specific axis. ...
Subsampling. Filter points before a minimum distance measured on a specific axis. ...
Subsampling. Reduce the points number by randomly removing points with a dentsity higher than a tresh...
Matrix features
features of points in the cloud
unsigned getDescriptorDim() const
Return the total number of descriptors.
#define EXPECT_FALSE(condition)
Systematic sampling, with variation over time.
Reorientation of normals.