DataFilters.cpp
Go to the documentation of this file.
00001 #include "../utest.h"
00002 
00003 using namespace std;
00004 using namespace PointMatcherSupport;
00005 
00006 //---------------------------
00007 // DataFilter modules
00008 //---------------------------
00009 
00010 // Utility classes
00011 class DataFilterTest: public IcpHelper
00012 {
00013 public:
00014         // Will be called for every tests
00015         virtual void SetUp()
00016         {
00017                 icp.setDefault();
00018                 // Uncomment for console outputs
00019                 //setLogger(PM::get().LoggerRegistrar.create("FileLogger"));
00020                 
00021                 // We'll test the filters on reading point cloud
00022                 icp.readingDataPointsFilters.clear();
00023         }
00024 
00025         // Will be called for every tests
00026         virtual void TearDown() {}
00027 
00028         void addFilter(string name, PM::Parameters params)
00029         {
00030                 PM::DataPointsFilter* testedDataPointFilter = 
00031                         PM::get().DataPointsFilterRegistrar.create(name, params);
00032         
00033                 icp.readingDataPointsFilters.push_back(testedDataPointFilter);
00034         }
00035         
00036         void addFilter(string name)
00037         {
00038                 PM::DataPointsFilter* testedDataPointFilter = 
00039                         PM::get().DataPointsFilterRegistrar.create(name);
00040                 
00041                 icp.readingDataPointsFilters.push_back(testedDataPointFilter);
00042         }
00043 };
00044 
00045 
00046 TEST_F(DataFilterTest, RemoveNaNDataPointsFilter)
00047 {
00048         // build test cloud
00049         DP ref2DCopy(ref2D);
00050         int goodCount(0);
00051         const float nan(std::numeric_limits<float>::quiet_NaN());
00052         for (int i(0); i < ref2DCopy.features.cols(); ++i)
00053         {
00054                 if (rand() % 3 == 0)
00055                 {
00056                         ref2DCopy.features(rand() % ref2DCopy.features.rows(), i) = nan;
00057                 }
00058                 else
00059                         ++goodCount;
00060         }
00061         
00062         // apply and checked
00063         addFilter("RemoveNaNDataPointsFilter");
00064         icp.readingDataPointsFilters.apply(ref2DCopy);
00065         EXPECT_TRUE(ref2DCopy.features.cols() == goodCount);
00066 }
00067 
00068 TEST_F(DataFilterTest, MaxDistDataPointsFilter)
00069 {
00070         // Max dist has been selected to not affect the points
00071         params = PM::Parameters();
00072         params["dim"] = "0";
00073         params["maxDist"] = toParam(6.0);
00074         
00075         // Filter on x axis
00076         params["dim"] = "0";
00077         icp.readingDataPointsFilters.clear();
00078         addFilter("MaxDistDataPointsFilter", params);
00079         validate2dTransformation();
00080         validate3dTransformation();
00081         
00082         // Filter on y axis
00083         params["dim"] = "1";
00084         icp.readingDataPointsFilters.clear();
00085         addFilter("MaxDistDataPointsFilter", params);
00086         validate2dTransformation();
00087         validate3dTransformation();
00088         
00089         // Filter on z axis (not existing)
00090         params["dim"] = "2";
00091         icp.readingDataPointsFilters.clear();
00092         addFilter("MaxDistDataPointsFilter", params);
00093         EXPECT_ANY_THROW(validate2dTransformation());
00094         validate3dTransformation();
00095         
00096         // Filter on a radius
00097         params["dim"] = "-1";
00098         icp.readingDataPointsFilters.clear();
00099         addFilter("MaxDistDataPointsFilter", params);
00100         validate2dTransformation();
00101         validate3dTransformation();
00102         
00103         // Parameter outside valid range
00104         params["dim"] = "3";
00105         //TODO: specify the exception, move that to GenericTest
00106         EXPECT_ANY_THROW(addFilter("MaxDistDataPointsFilter", params));
00107         
00108 }
00109 
00110 TEST_F(DataFilterTest, MinDistDataPointsFilter)
00111 {
00112         // Min dist has been selected to not affect the points too much
00113         params = PM::Parameters();
00114         params["dim"] = "0";
00115         params["minDist"] = toParam(0.05);
00116         
00117         // Filter on x axis
00118         params["dim"] = "0";
00119         icp.readingDataPointsFilters.clear();
00120         addFilter("MinDistDataPointsFilter", params);
00121         validate2dTransformation();
00122         validate3dTransformation();
00123         
00124         // Filter on y axis
00125         params["dim"] = "1";
00126         icp.readingDataPointsFilters.clear();
00127         addFilter("MinDistDataPointsFilter", params);
00128         validate2dTransformation();
00129         validate3dTransformation();
00130         
00131         //TODO: move that to specific 2D test
00132         // Filter on z axis (not existing)
00133         params["dim"] = "2";
00134         icp.readingDataPointsFilters.clear();
00135         addFilter("MinDistDataPointsFilter", params);
00136         EXPECT_ANY_THROW(validate2dTransformation());
00137         validate3dTransformation();
00138         
00139         // Filter on a radius
00140         params["dim"] = "-1";
00141         icp.readingDataPointsFilters.clear();
00142         addFilter("MinDistDataPointsFilter", params);
00143         validate2dTransformation();
00144         validate3dTransformation();
00145                 
00146 }
00147 
00148 TEST_F(DataFilterTest, MaxQuantileOnAxisDataPointsFilter)
00149 {
00150         // Ratio has been selected to not affect the points too much
00151         string ratio = "0.95";
00152         params = PM::Parameters();
00153         params["dim"] = "0";
00154         params["ratio"] = ratio;
00155         
00156         // Filter on x axis
00157         params["dim"] = "0";
00158         icp.readingDataPointsFilters.clear();
00159         addFilter("MaxQuantileOnAxisDataPointsFilter", params);
00160         validate2dTransformation();
00161         validate3dTransformation();
00162         
00163         // Filter on y axis
00164         params["dim"] = "1";
00165         icp.readingDataPointsFilters.clear();
00166         addFilter("MaxQuantileOnAxisDataPointsFilter", params);
00167         validate2dTransformation();
00168         validate3dTransformation();
00169         
00170         // Filter on z axis (not existing)
00171         params["dim"] = "2";
00172         icp.readingDataPointsFilters.clear();
00173         addFilter("MaxQuantileOnAxisDataPointsFilter", params);
00174         EXPECT_ANY_THROW(validate2dTransformation());
00175         validate3dTransformation();
00176 }
00177 
00178 
00179 
00180 TEST_F(DataFilterTest, SurfaceNormalDataPointsFilter)
00181 {
00182         // This filter create descriptor, so parameters should'nt impact results
00183         params = PM::Parameters();
00184         params["knn"] =  "5"; 
00185         params["epsilon"] =  "0.1"; 
00186         params["keepNormals"] =  "1";
00187         params["keepDensities"] =  "1";
00188         params["keepEigenValues"] =  "1";
00189         params["keepEigenVectors"] =  "1" ;
00190         params["keepMatchedIds"] =  "1" ;
00191         // FIXME: the parameter keepMatchedIds seems to do nothing...
00192 
00193         addFilter("SurfaceNormalDataPointsFilter", params);
00194         validate2dTransformation();     
00195         validate3dTransformation();
00196 
00197         // TODO: standardize how filter are tested:
00198         // 1- impact on number of points
00199         // 2- impact on descriptors
00200         // 3- impact on ICP (that's what we test now)
00201 }
00202 
00203 TEST_F(DataFilterTest, MaxDensityDataPointsFilter)
00204 {
00205         // Ratio has been selected to not affect the points too much
00206         vector<double> ratio = list_of (100) (1000) (5000);
00207  
00208         for(unsigned i=0; i < ratio.size(); i++)
00209         {
00210                 icp.readingDataPointsFilters.clear();
00211                 params = PM::Parameters();
00212                 params["knn"] = "5"; 
00213                 params["epsilon"] = "0.1"; 
00214                 params["keepNormals"] = "0";
00215                 params["keepDensities"] = "1";
00216                 params["keepEigenValues"] = "0";
00217                 params["keepEigenVectors"] = "0" ;
00218                 params["keepMatchedIds"] = "0" ;
00219 
00220                 addFilter("SurfaceNormalDataPointsFilter", params);
00221 
00222                 params = PM::Parameters();
00223                 params["maxDensity"] = toParam(ratio[i]);
00224 
00225                 addFilter("MaxDensityDataPointsFilter", params);
00226                 
00227                 // FIXME BUG: the density in 2D is not well computed
00228                 //validate2dTransformation();   
00229  
00230                 //double nbInitPts = data2D.features.cols();
00231                 //double nbRemainingPts = icp.getPrefilteredReadingPtsCount();
00232                 //EXPECT_TRUE(nbRemainingPts < nbInitPts);
00233                 
00234                 validate3dTransformation();
00235 
00236                 double nbInitPts = data3D.features.cols();
00237                 double nbRemainingPts = icp.getPrefilteredReadingPtsCount();
00238                 EXPECT_TRUE(nbRemainingPts < nbInitPts);
00239         }
00240 }
00241 
00242 TEST_F(DataFilterTest, SamplingSurfaceNormalDataPointsFilter)
00243 {
00244         // This filter create descriptor AND subsample
00245         params = PM::Parameters();
00246         params["knn"] = "5";
00247         params["averageExistingDescriptors"] = "1";
00248         params["keepNormals"] = "1";
00249         params["keepDensities"] = "1";
00250         params["keepEigenValues"] = "1";
00251         params["keepEigenVectors"] = "1";
00252         
00253         addFilter("SamplingSurfaceNormalDataPointsFilter", params);
00254         validate2dTransformation();
00255         validate3dTransformation();
00256 
00257 }
00258 
00259 TEST_F(DataFilterTest, OrientNormalsDataPointsFilter)
00260 {
00261         // Used to create normal for reading point cloud
00262         PM::DataPointsFilter* extraDataPointFilter;
00263         extraDataPointFilter = PM::get().DataPointsFilterRegistrar.create(
00264                         "SurfaceNormalDataPointsFilter");
00265         icp.readingDataPointsFilters.push_back(extraDataPointFilter);
00266         addFilter("ObservationDirectionDataPointsFilter");
00267         addFilter("OrientNormalsDataPointsFilter", map_list_of
00268                 ("towardCenter", toParam(false))
00269         );
00270         validate2dTransformation();
00271         validate3dTransformation();
00272 }
00273 
00274 
00275 TEST_F(DataFilterTest, RandomSamplingDataPointsFilter)
00276 {
00277         vector<double> prob = list_of (0.80) (0.85) (0.90) (0.95);
00278         for(unsigned i=0; i<prob.size(); i++)
00279         {
00280                 // Try to avoid to low value for the reduction to avoid under sampling
00281                 params = PM::Parameters();
00282                 params["prob"] = toParam(prob[i]);
00283 
00284                 icp.readingDataPointsFilters.clear();
00285                 addFilter("RandomSamplingDataPointsFilter", params);
00286                 validate2dTransformation();
00287                 validate3dTransformation();
00288         }
00289 }
00290 
00291 TEST_F(DataFilterTest, FixStepSamplingDataPointsFilter)
00292 {
00293         vector<unsigned> steps = list_of (1) (2) (3);
00294         for(unsigned i=0; i<steps.size(); i++)
00295         {
00296                 // Try to avoid too low value for the reduction to avoid under sampling
00297                 params = PM::Parameters();
00298                 params["startStep"] = toParam(steps[i]);
00299 
00300                 icp.readingDataPointsFilters.clear();
00301                 addFilter("FixStepSamplingDataPointsFilter", params);
00302                 validate2dTransformation();
00303                 validate3dTransformation();
00304         }
00305 }
00306 
00307 TEST_F(DataFilterTest, VoxelGridDataPointsFilter)
00308 {
00309         vector<bool> useCentroid = list_of(false)(true);
00310         vector<bool> averageExistingDescriptors = list_of(false)(true);
00311         for (unsigned i = 0 ; i < useCentroid.size() ; i++) 
00312         {
00313                 for (unsigned j = 0; j < averageExistingDescriptors.size(); j++) 
00314                 {
00315                         params = PM::Parameters(); 
00316                         params["vSizeX"] = "0.02";
00317                         params["vSizeY"] = "0.02";
00318                         params["vSizeZ"] = "0.02";
00319                         params["useCentroid"] = toParam(true);
00320                         params["averageExistingDescriptors"] = toParam(true);
00321                         
00322                         icp.readingDataPointsFilters.clear();
00323                         addFilter("VoxelGridDataPointsFilter", params);
00324                         validate2dTransformation();
00325                 }
00326         }
00327 
00328         for (unsigned i = 0 ; i < useCentroid.size() ; i++)
00329         {
00330                 for (unsigned j = 0; j < averageExistingDescriptors.size(); j++)
00331                 {
00332                         params = PM::Parameters();
00333                         params["vSizeX"] = "1";
00334                         params["vSizeY"] = "1";
00335                         params["vSizeZ"] = "1";
00336                         params["useCentroid"] = toParam(true);
00337                         params["averageExistingDescriptors"] = toParam(true);
00338                         
00339                         icp.readingDataPointsFilters.clear();
00340                         addFilter("VoxelGridDataPointsFilter", params);
00341                         validate3dTransformation();
00342                 }
00343         }
00344 }
00345 
00346 TEST_F(DataFilterTest, CutAtDescriptorThresholdDataPointsFilter)
00347 {
00348         // Copied from density ratio above
00349         vector<double> thresholds = list_of (100) (1000) (5000);
00350 
00351         DP ref3Ddensities = ref3D;
00352         // Adding descriptor "densities"
00353         icp.readingDataPointsFilters.clear();
00354         params = PM::Parameters();
00355         params["knn"] = "5"; 
00356         params["epsilon"] = "0.1"; 
00357         params["keepNormals"] = "0";
00358         params["keepDensities"] = "1";
00359         params["keepEigenValues"] = "0";
00360         params["keepEigenVectors"] = "0";
00361         params["keepMatchedIds"] = "0";
00362         
00363 
00364         addFilter("SurfaceNormalDataPointsFilter", params);
00365         icp.readingDataPointsFilters.apply(ref3Ddensities);
00366 
00367         for(unsigned i=0; i < thresholds.size(); i++)
00368         {
00369                 int belowCount=0;
00370                 int aboveCount=0;
00371 
00372                 // counting points above and below
00373                 PM::DataPoints::View densities = ref3Ddensities.getDescriptorViewByName("densities");
00374                 for (unsigned j=0; j < densities.cols(); ++j)
00375                 {
00376                         if (densities(0, j) <= thresholds[i])
00377                         {
00378                                 ++belowCount;
00379                         }
00380                         if (densities(0, j) >= thresholds[i])
00381                         {
00382                                 ++aboveCount;
00383                         }
00384                 }
00385 
00386                 for(bool useLargerThan(true); useLargerThan; useLargerThan=false)
00387                 {
00388                         DP ref3DCopy = ref3Ddensities;
00389 
00390                         icp.readingDataPointsFilters.clear();
00391                         params = PM::Parameters(); 
00392                         params["descName"] = toParam("densities");
00393                         params["useLargerThan"] = toParam(useLargerThan);
00394                         params["threshold"] = toParam(thresholds[i]);
00395                         
00396 
00397                         addFilter("CutAtDescriptorThresholdDataPointsFilter", params);
00398                         icp.readingDataPointsFilters.apply(ref3DCopy);
00399                         if (useLargerThan)
00400                         {
00401                                 EXPECT_TRUE(ref3DCopy.features.cols() == belowCount);
00402                         }
00403                         else
00404                         {
00405                                 EXPECT_TRUE(ref3DCopy.features.cols() == aboveCount);
00406                         }
00407                 }
00408         }
00409 }
00410 


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