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 
00055 int main(int argc, char *argv[])
00056 {
00057         validateArgs(argc, argv);
00058 
00059         typedef PointMatcher<float> PM;
00060         typedef PointMatcherIO<float> PMIO;
00061         typedef PM::TransformationParameters TP;
00062         typedef PM::DataPoints DP;
00063         typedef Parametrizable::Parameter Parameter;
00064         
00065         const int maxMapPointCount = 200000;
00066 
00067         string outputFileName(argv[0]);
00068         
00069         // Main algorithm definition
00070         PM::ICP icp;
00071 
00072         // load YAML config
00073         ifstream ifs(argv[1]);
00074         validateFile(argv[1]);
00075         icp.loadFromYaml(ifs);
00076 
00077         PMIO::FileInfoVector list(argv[2]);
00078 
00079         PM::DataPoints mapPointCloud, newCloud;
00080         TP tp;
00081 
00082         for(unsigned i=0; i < list.size(); i++)
00083         {
00084                 cout << "---------------------\nLoading: " << list[i].readingFileName << endl; 
00085                 newCloud = DP::load(list[i].readingFileName);
00086                 
00087                 if(mapPointCloud.features.rows() == 0)
00088                 {
00089                         mapPointCloud = newCloud;
00090                 }
00091                 else
00092                 {
00093 
00094                         // call ICP
00095                         try 
00096                         {
00097                                 tp = icp(mapPointCloud, newCloud);
00098                                 //tp = icp.getDeltaTransform();
00099                                 //cout << "Transformation: "<< tp << endl;
00100                                 cout << "match ratio: " << icp.errorMinimizer->getWeightedPointUsedRatio() << endl;
00101                                 
00102                                 newCloud.features = tp.inverse()*newCloud.features;
00103                         
00104                                 PM::DataPointsFilter* densityFilter(
00105                                         PM::get().DataPointsFilterRegistrar.create(
00106                                                 "SurfaceNormalDataPointsFilter",
00107                                                 map_list_of
00108                                                         ("binSize", "10")
00109                                                         ("epsilon", "5") 
00110                                                         ("keepNormals", "0")
00111                                                         ("keepDensities", "1")
00112                                         )
00113                                 );
00114 
00115                                 PM::DataPointsFilter* maxDensitySubsample(
00116                                         PM::get().DataPointsFilterRegistrar.create(
00117                                                 "MaxDensityDataPointsFilter",
00118                                                 map_list_of
00119                                                         ("maxDensity", toParam(30))
00120                                         )
00121                                 );
00122                                 
00123                                 // Merge point clouds to map
00124                                 mapPointCloud.concatenate(newCloud);
00125                                 mapPointCloud = densityFilter->filter(mapPointCloud);
00126                                 mapPointCloud = maxDensitySubsample->filter(mapPointCloud);
00127 
00128                                 // Controle the size of the point cloud
00129                                 const double probToKeep = maxMapPointCount/(double)mapPointCloud.features.cols();
00130                                 if(probToKeep < 1.0)
00131                                 {
00132                                         PM::DataPointsFilter* randSubsample(
00133                                                 PM::get().DataPointsFilterRegistrar.create(
00134                                                         "RandomSamplingDataPointsFilter",
00135                                                         map_list_of
00136                                                                 ("prob", toParam(probToKeep))
00137                                                 )
00138                                         );
00139                                         mapPointCloud = randSubsample->filter(mapPointCloud);
00140                                 }
00141                         }
00142                         catch (PM::ConvergenceError& error)
00143                         {
00144                                 cout << "ERROR PM::ICP failed to converge: " << endl;
00145                                 cout << "   " << error.what() << endl;
00146                                 //cout << "Reseting tracking" << endl;
00147                                 //icp.resetTracking(newCloud);
00148                         }
00149 
00150                         stringstream outputFileNameIter;
00151                         outputFileNameIter << outputFileName << "_" << i;
00152                         
00153                         cout << "outputFileName: " << outputFileNameIter.str() << endl;
00154                         mapPointCloud.save(outputFileNameIter.str());
00155                 }
00156         }
00157 
00158         return 0;
00159 }
00160 
00161 void validateArgs(int argc, char *argv[])
00162 {
00163         if (!(argc == 3))
00164         {
00165                 cerr << "Error in command line, usage " << argv[0] << " icpConfiguration.yaml listOfFiles.csv" << endl;
00166                 cerr << endl << "Example:" << endl;
00167                 cerr << argv[0] << " ../examples/data/default.yaml ../examples/data/carCloudList.csv" << endl << endl;
00168 
00169                 abort();
00170         }
00171 }
00172 
00173 


upstream_src
Author(s):
autogenerated on Mon Oct 6 2014 10:27:39