76   Eigen::Map<Eigen::VectorXf> v(A.data(),A.size());
 
   77   std::sort(v.data(), v.data() + v.size());
 
   86         namespace fs = boost::filesystem;
 
   87         fs::path config_dir(
dataPath + 
"icp_data");
 
   88         EXPECT_TRUE( fs::exists(config_dir) && fs::is_directory(config_dir) );
 
   90         fs::directory_iterator end_iter;
 
   91         for( fs::directory_iterator 
d(config_dir); 
d != end_iter; ++
d)
 
   93                 if (!fs::is_regular_file(
d->status()) ) 
continue;
 
   95                 std::cout << 
"Testing file " << 
d->path().string() << std::endl;
 
   99                 if (fs::extension(config_file) != 
".yaml") 
continue;
 
  100                 std::ifstream ifs(config_file.c_str());
 
  101                 EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << 
"This error was caused by the test file:" << endl << 
"   " << config_file;
 
  108                 fs::path cur_file = 
d->path();
 
  109                 cur_file.replace_extension(
".cur_trans");
 
  111                 std::ofstream otfs(cur_file.c_str());
 
  117                 fs::path ref_file = 
d->path();
 
  118                 ref_file.replace_extension(
".ref_trans");
 
  121                 std::ifstream itfs(ref_file.c_str());
 
  122                 EXPECT_TRUE(itfs.good()) << 
"Could not find " << ref_file
 
  123                                          << 
". If this is the first time this test is run, " 
  124                                          << 
"create it as a copy of " << cur_file; 
 
  126                 for (
int row = 0; row < refT.cols(); row++)
 
  128                         for (
int col = 0; col < refT.cols(); col++)
 
  130                                 itfs >>refT(row, col);
 
  147                 Eigen::MatrixXf AbsDiff = (curT*data.
features - refT*data.
features).array().abs();
 
  151                 Eigen::MatrixXf Data = (curT*data.
features).array().abs();
 
  155                 double rel_err = median_diff/median_data;
 
  158                 EXPECT_LT(rel_err, 0.03) << 
"This error was caused by the test file:" << endl << 
"   " << config_file;
 
  168         const size_t nX = 10, nY = nX;
 
  169         Eigen::MatrixXf points(4, nX * nY);
 
  171         const float oX = -(nX * 
d / 2), oY = -(nY * 
d / 2);
 
  173         for(
size_t x = 0; 
x < nX; 
x++){
 
  174                 for(
size_t y = 0; y < nY; y++){
 
  175                         points.col( 
x * nY + y) << 
d * 
x + oX, 
d * y + oY, 0, 1;
 
  182         points.row(2).setOnes();
 
  187         EXPECT_TRUE(boost::filesystem::exists(config_file));
 
  189         std::ifstream ifs(config_file.c_str());
 
  190         EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << 
"This error was caused by the test file:" << endl << 
"   " << config_file;
 
  195         PM::Matrix expectedT = PM::Matrix::Identity(4,4);
 
  197         EXPECT_TRUE(expectedT.isApprox(curT)) << 
"Expecting pure translation in z-direction of unit distance." << endl;
 
  211         EXPECT_TRUE(boost::filesystem::exists(config_file));
 
  213         std::ifstream ifs(config_file.c_str());
 
  214         EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << 
"This error was caused by the test file:" << endl << 
"   " << config_file;
 
  219         EXPECT_TRUE(curT.isApprox(PM::Matrix::Identity(4, 4), 
epsilon)) << 
"Expecting identity transform." << endl;
 
  222 TEST(icpTest, similarityTransform)
 
  230         std::string config_file = 
dataPath + 
"icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.yaml";
 
  231         EXPECT_TRUE(boost::filesystem::exists(config_file));
 
  233         std::ifstream ifs(config_file.c_str());
 
  234         EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << 
"This error was caused by the test file:" << endl << 
"   " << config_file;
 
  240         double scale = 
pow(curT.determinant(), 1.0/3.0);
 
  241         EXPECT_LT( std::abs(scale - 1.04), 0.001)
 
  242           << 
"Expecting the similarity transform scale to be 1.04.";
 
  253         PM::ICPSequence icpSequence;
 
  255         std::ifstream ifs((
dataPath + 
"default.yaml").c_str());
 
  256         icpSequence.loadFromYaml(ifs);
 
  260         DP map = icpSequence.getPrefilteredInternalMap();
 
  264         map = icpSequence.getPrefilteredMap();
 
  268         icpSequence.setMap(pts0);
 
  269         map = icpSequence.getPrefilteredInternalMap();
 
  274         Ticp = icpSequence(pts1);
 
  275         map = icpSequence.getPrefilteredMap();
 
  280         Ticp = icpSequence(pts2);
 
  281         map = icpSequence.getPrefilteredMap();
 
  286         icpSequence.clearMap();
 
  287         map = icpSequence.getPrefilteredInternalMap();
 
  318         validate2dTransformation();
 
  319         validate3dTransformation();
 
  325 int main(
int argc, 
char **argv)
 
  328         for(
int i=1; i < argc; i++)
 
  330                 if (strcmp(argv[i], 
"--path") == 0 && i+1 < argc)
 
  336                 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;
 
  348         validT2d <<  0.987498,  0.157629, 0.0859918,
 
  349                                 -0.157629,  0.987498,  0.203247,
 
  353         validT3d <<   0.982304,   0.166685,  -0.0854066,  0.0446816,
 
  354                                  -0.150189,   0.973488,   0.172524,   0.191998,
 
  355                                   0.111899,  -0.156644,   0.981296,  -0.0356313,