00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "utest.h"
00037
00038 using namespace std;
00039 using namespace PointMatcherSupport;
00040
00041
00042
00043 std::string dataPath;
00044
00045 DP ref2D;
00046 DP data2D;
00047 DP ref3D;
00048 DP data3D;
00049 PM::TransformationParameters validT2d;
00050 PM::TransformationParameters validT3d;
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075 double median_coeff(Eigen::MatrixXf& A){
00076 Eigen::Map<Eigen::VectorXf> v(A.data(),A.size());
00077 std::sort(v.data(), v.data() + v.size());
00078 return v[v.size()/2];
00079 }
00080
00081 TEST(icpTest, icpTest)
00082 {
00083 DP ref = DP::load(dataPath + "cloud.00000.vtk");
00084 DP data = DP::load(dataPath + "cloud.00001.vtk");
00085
00086 namespace fs = boost::filesystem;
00087 fs::path config_dir(dataPath + "icp_data");
00088 EXPECT_TRUE( fs::exists(config_dir) && fs::is_directory(config_dir) );
00089
00090 fs::directory_iterator end_iter;
00091 for( fs::directory_iterator d(config_dir); d != end_iter; ++d)
00092 {
00093 if (!fs::is_regular_file(d->status()) ) continue;
00094
00095 std::cout << "Testing file " << d->path().string() << std::endl;
00096
00097 PM::ICP icp;
00098 std::string config_file = d->path().string();
00099 if (fs::extension(config_file) != ".yaml") continue;
00100 std::ifstream ifs(config_file.c_str());
00101 EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file;
00102
00103
00104 PM::TransformationParameters curT = icp(data, ref);
00105
00106
00107
00108 fs::path cur_file = d->path();
00109 cur_file.replace_extension(".cur_trans");
00110
00111 std::ofstream otfs(cur_file.c_str());
00112 otfs.precision(16);
00113 otfs << curT;
00114 otfs.close();
00115
00116
00117 fs::path ref_file = d->path();
00118 ref_file.replace_extension(".ref_trans");
00119 PM::TransformationParameters refT = 0*curT;
00120
00121 std::ifstream itfs(ref_file.c_str());
00122 EXPECT_TRUE(itfs.good()) << "Could not find " << ref_file
00123 << ". If this is the first time this test is run, "
00124 << "create it as a copy of " << cur_file;
00125
00126 for (int row = 0; row < refT.cols(); row++)
00127 {
00128 for (int col = 0; col < refT.cols(); col++)
00129 {
00130 itfs >>refT(row, col);
00131 }
00132 }
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147 Eigen::MatrixXf AbsDiff = (curT*data.features - refT*data.features).array().abs();
00148 double median_diff = median_coeff(AbsDiff);
00149
00150
00151 Eigen::MatrixXf Data = (curT*data.features).array().abs();
00152 double median_data = median_coeff(Data);
00153
00154
00155 double rel_err = median_diff/median_data;
00156
00157
00158 EXPECT_LT(rel_err, 0.03) << "This error was caused by the test file:" << endl << " " << config_file;
00159 }
00160 }
00161
00162 TEST(icpTest, icpSingular)
00163 {
00164
00165
00166
00167
00168 const size_t nX = 10, nY = nX;
00169 Eigen::MatrixXf points(4, nX * nY);
00170 const float d = 0.1;
00171 const float oX = -(nX * d / 2), oY = -(nY * d / 2);
00172
00173 for(size_t x = 0; x < nX; x++){
00174 for(size_t y = 0; y < nY; y++){
00175 points.col( x * nY + y) << d * x + oX, d * y + oY, 0, 1;
00176 }
00177 }
00178
00179 DP pts0;
00180 pts0.features = points;
00181 DP pts1;
00182 points.row(2).setOnes();
00183 pts1.features = points;
00184
00185 PM::ICP icp;
00186 std::string config_file = dataPath + "default-identity.yaml";
00187 EXPECT_TRUE(boost::filesystem::exists(config_file));
00188
00189 std::ifstream ifs(config_file.c_str());
00190 EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file;
00191
00192
00193 PM::TransformationParameters curT = icp(pts0, pts1);
00194
00195 PM::Matrix expectedT = PM::Matrix::Identity(4,4);
00196 expectedT(2,3) = 1;
00197 EXPECT_TRUE(expectedT.isApprox(curT)) << "Expecting pure translation in z-direction of unit distance." << endl;
00198 }
00199
00200 TEST(icpTest, icpIdentity)
00201 {
00202
00203
00204 const float epsilon = 0.0001;
00205
00206 DP pts0 = DP::load(dataPath + "cloud.00000.vtk");
00207 DP pts1 = DP::load(dataPath + "cloud.00000.vtk");
00208
00209 PM::ICP icp;
00210 std::string config_file = dataPath + "default-identity.yaml";
00211 EXPECT_TRUE(boost::filesystem::exists(config_file));
00212
00213 std::ifstream ifs(config_file.c_str());
00214 EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file;
00215
00216
00217 PM::TransformationParameters curT = icp(pts0, pts1);
00218
00219 EXPECT_TRUE(curT.isApprox(PM::Matrix::Identity(4, 4), epsilon)) << "Expecting identity transform." << endl;
00220 }
00221
00222 TEST(icpTest, similarityTransform)
00223 {
00224
00225
00226 DP pts0 = DP::load(dataPath + "car_cloud400.csv");
00227 DP pts1 = DP::load(dataPath + "car_cloud400_scaled.csv");
00228
00229 PM::ICP icp;
00230 std::string config_file = dataPath + "icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.yaml";
00231 EXPECT_TRUE(boost::filesystem::exists(config_file));
00232
00233 std::ifstream ifs(config_file.c_str());
00234 EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file;
00235
00236
00237 PM::TransformationParameters curT = icp(pts0, pts1);
00238
00239
00240 double scale = pow(curT.determinant(), 1.0/3.0);
00241 EXPECT_LT( std::abs(scale - 1.04), 0.001)
00242 << "Expecting the similarity transform scale to be 1.04.";
00243 }
00244
00245 TEST(icpTest, icpSequenceTest)
00246 {
00247 DP pts0 = DP::load(dataPath + "cloud.00000.vtk");
00248 DP pts1 = DP::load(dataPath + "cloud.00001.vtk");
00249 DP pts2 = DP::load(dataPath + "cloud.00002.vtk");
00250
00251 PM::TransformationParameters Ticp = PM::Matrix::Identity(4,4);
00252
00253 PM::ICPSequence icpSequence;
00254
00255 std::ifstream ifs((dataPath + "default.yaml").c_str());
00256 icpSequence.loadFromYaml(ifs);
00257
00258 EXPECT_FALSE(icpSequence.hasMap());
00259
00260 DP map = icpSequence.getPrefilteredInternalMap();
00261 EXPECT_EQ(map.getNbPoints(), 0u);
00262 EXPECT_EQ(map.getHomogeneousDim(), 0u);
00263
00264 map = icpSequence.getPrefilteredMap();
00265 EXPECT_EQ(map.getNbPoints(), 0u);
00266 EXPECT_EQ(map.getHomogeneousDim(), 0u);
00267
00268 icpSequence.setMap(pts0);
00269 map = icpSequence.getPrefilteredInternalMap();
00270 EXPECT_LE(map.getNbPoints(), pts0.getNbPoints());
00271 EXPECT_GT(map.getNbPoints(), 0u);
00272 EXPECT_EQ(map.getHomogeneousDim(), pts0.getHomogeneousDim());
00273
00274 Ticp = icpSequence(pts1);
00275 map = icpSequence.getPrefilteredMap();
00276 EXPECT_LE(map.getNbPoints(), pts0.getNbPoints());
00277 EXPECT_GT(map.getNbPoints(), 0u);
00278 EXPECT_EQ(map.getHomogeneousDim(), pts0.getHomogeneousDim());
00279
00280 Ticp = icpSequence(pts2);
00281 map = icpSequence.getPrefilteredMap();
00282 EXPECT_LE(map.getNbPoints(), pts0.getNbPoints());
00283 EXPECT_GT(map.getNbPoints(), 0u);
00284 EXPECT_EQ(map.getHomogeneousDim(), pts0.getHomogeneousDim());
00285
00286 icpSequence.clearMap();
00287 map = icpSequence.getPrefilteredInternalMap();
00288 EXPECT_EQ(map.getNbPoints(), 0u);
00289 EXPECT_EQ(map.getHomogeneousDim(), 0u);
00290 }
00291
00292
00293 class GenericTest: public IcpHelper
00294 {
00295
00296 public:
00297
00298
00299 virtual void SetUp()
00300 {
00301 icp.setDefault();
00302
00303
00304 }
00305
00306
00307 virtual void TearDown()
00308 {
00309 }
00310 };
00311
00312
00313
00314
00315
00316 TEST_F(GenericTest, ICP_default)
00317 {
00318 validate2dTransformation();
00319 validate3dTransformation();
00320 }
00321
00322
00323
00324
00325 int main(int argc, char **argv)
00326 {
00327 dataPath = "";
00328 for(int i=1; i < argc; i++)
00329 {
00330 if (strcmp(argv[i], "--path") == 0 && i+1 < argc)
00331 dataPath = argv[i+1];
00332 }
00333
00334 if(dataPath == "")
00335 {
00336 cerr << "Missing the flag --path ./path/to/examples/data\n Please give the path to the test data folder which should be included with the source code. The folder is named 'examples/data'." << endl;
00337 return -1;
00338 }
00339
00340
00341 ref2D = DP::load(dataPath + "2D_oneBox.csv");
00342 data2D = DP::load(dataPath + "2D_twoBoxes.csv");
00343 ref3D = DP::load(dataPath + "car_cloud400.csv");
00344 data3D = DP::load(dataPath + "car_cloud401.csv");
00345
00346
00347 validT2d = PM::TransformationParameters(3,3);
00348 validT2d << 0.987498, 0.157629, 0.0859918,
00349 -0.157629, 0.987498, 0.203247,
00350 0, 0, 1;
00351
00352 validT3d = PM::TransformationParameters(4,4);
00353 validT3d << 0.982304, 0.166685, -0.0854066, 0.0446816,
00354 -0.150189, 0.973488, 0.172524, 0.191998,
00355 0.111899, -0.156644, 0.981296, -0.0356313,
00356 0, 0, 0, 1;
00357
00358 testing::GTEST_FLAG(print_time) = true;
00359 testing::InitGoogleTest(&argc, argv);
00360 return RUN_ALL_TESTS();
00361 }
00362
00363
00364