align_sequence.cpp
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 #include "pointmatcher/PointMatcher.h"
00037 #include "pointmatcher/IO.h"
00038 #include <cassert>
00039 #include <iostream>
00040 #include <fstream>
00041 #include <boost/format.hpp>
00042 #include <boost/filesystem/path.hpp>
00043 #include <boost/filesystem/operations.hpp>
00044 
00045 
00046 using namespace std;
00047 using namespace PointMatcherSupport;
00048 
00049 void validateArgs(int argc, char *argv[]);
00050 
00057 int main(int argc, char *argv[])
00058 {
00059         validateArgs(argc, argv);
00060 
00061         typedef PointMatcher<float> PM;
00062         typedef PointMatcherIO<float> PMIO;
00063         typedef PM::TransformationParameters TP;
00064         typedef PM::DataPoints DP;
00065         
00066         string outputFileName(argv[0]);
00067         
00068         // Rigid transformation
00069         std::shared_ptr<PM::Transformation> rigidTrans;
00070         rigidTrans = PM::get().REG(Transformation).create("RigidTransformation");
00071 
00072         // Create filters manually to clean the global map
00073         std::shared_ptr<PM::DataPointsFilter> densityFilter =
00074                                         PM::get().DataPointsFilterRegistrar.create(
00075                                                 "SurfaceNormalDataPointsFilter",
00076                                                 {
00077                                                         {"knn", "10"},
00078                                                         {"epsilon", "5"},
00079                                                         {"keepNormals", "0"},
00080                                                         {"keepDensities", "1"}
00081                                                 }
00082                     );
00083 
00084         std::shared_ptr<PM::DataPointsFilter> maxDensitySubsample =
00085                                         PM::get().DataPointsFilterRegistrar.create(
00086                                                 "MaxDensityDataPointsFilter",
00087                                                 {{"maxDensity", toParam(30)}}
00088                     );
00089         // Main algorithm definition
00090         PM::ICP icp;
00091 
00092         // load YAML config
00093         ifstream ifs(argv[1]);
00094         validateFile(argv[1]);
00095         icp.loadFromYaml(ifs);
00096 
00097         PMIO::FileInfoVector list(argv[2]);
00098 
00099         PM::DataPoints mapPointCloud, newCloud;
00100         TP T_to_map_from_new = TP::Identity(4,4); // assumes 3D
00101 
00102         for(unsigned i=0; i < list.size(); i++)
00103         {
00104                 cout << "---------------------\nLoading: " << list[i].readingFileName << endl; 
00105 
00106                 // It is assume that the point cloud is express in sensor frame
00107                 newCloud = DP::load(list[i].readingFileName);
00108                 
00109                 if(mapPointCloud.getNbPoints()  == 0)
00110                 {
00111                         mapPointCloud = newCloud;
00112                         continue;
00113                 }
00114 
00115                 // call ICP
00116                 try 
00117                 {
00118                         // We use the last transformation as a prior
00119                         // this assumes that the point clouds were recorded in 
00120                         // sequence. 
00121                         const TP prior = T_to_map_from_new;
00122 
00123                         T_to_map_from_new = icp(newCloud, mapPointCloud, prior);
00124                 }
00125                 catch (PM::ConvergenceError& error)
00126                 {
00127                         cout << "ERROR PM::ICP failed to converge: " << endl;
00128                         cout << "   " << error.what() << endl;
00129                         continue;
00130                 }
00131 
00132                 // This is not necessary in this example, but could be
00133                 // useful if the same matrix is composed in the loop.
00134                 T_to_map_from_new = rigidTrans->correctParameters(T_to_map_from_new);
00135 
00136                 // Move the new point cloud in the map reference
00137                 newCloud = rigidTrans->compute(newCloud, T_to_map_from_new);
00138 
00139                 // Merge point clouds to map
00140                 mapPointCloud.concatenate(newCloud);
00141 
00142                 // Clean the map
00143                 mapPointCloud = densityFilter->filter(mapPointCloud);
00144                 mapPointCloud = maxDensitySubsample->filter(mapPointCloud);
00145 
00146                 // Save the map at each iteration
00147                 stringstream outputFileNameIter;
00148                 outputFileNameIter << outputFileName << "_" << i << ".vtk";
00149 
00150                 cout << "outputFileName: " << outputFileNameIter.str() << endl;
00151                 mapPointCloud.save(outputFileNameIter.str());
00152         }
00153 
00154         return 0;
00155 }
00156 
00157 void validateArgs(int argc, char *argv[])
00158 {
00159         if (!(argc == 3))
00160         {
00161                 cerr << "Error in command line, usage " << argv[0] << " icpConfiguration.yaml listOfFiles.csv" << endl;
00162                 cerr << endl << "Example:" << endl;
00163                 cerr << argv[0] << " ../examples/data/default.yaml ../examples/data/carCloudList.csv" << endl;
00164                 cerr << endl << " - or - " << endl << endl;
00165                 cerr << argv[0] << " ../examples/data/default.yaml ../examples/data/cloudList.csv" << endl << endl;
00166 
00167                 abort();
00168         }
00169 }
00170 
00171 


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:29