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


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