build_map.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 #include <boost/lexical_cast.hpp>
00045 
00046 using namespace std;
00047 using namespace PointMatcherSupport;
00048 
00049 void validateArgs(int argc, char *argv[]);
00050 void setupArgs(int argc, char *argv[], unsigned int& startId, unsigned int& endId, string& extension);
00051 vector<string> loadYamlFile(string listFileName);
00052 
00060 int main(int argc, char *argv[])
00061 {
00062         validateArgs(argc, argv);
00063 
00064         typedef PointMatcher<float> PM;
00065         typedef PointMatcherIO<float> PMIO;
00066         typedef PM::TransformationParameters TP;
00067         typedef PM::DataPoints DP;
00068 
00069         // Process arguments
00070         PMIO::FileInfoVector list(argv[1]);
00071         const unsigned totalPointCount = boost::lexical_cast<unsigned>(argv[2]);        
00072         string outputFileName(argv[3]);
00073         
00074         
00075         setLogger(PM::get().LoggerRegistrar.create("FileLogger"));
00076         
00077         PM::DataPoints mapCloud;
00078 
00079         PM::DataPoints lastCloud, newCloud;
00080         TP T = TP::Identity(4,4);
00081 
00082         // Define transformation chain
00083         PM::Transformation* transformation;
00084         transformation = PM::get().REG(Transformation).create("RigidTransformation");
00085 
00086         // This filter will remove a sphere of 1 m radius. Easy way to remove the sensor self-scanning.
00087         PM::DataPointsFilter* removeScanner(
00088                 PM::get().DataPointsFilterRegistrar.create(
00089                         "MinDistDataPointsFilter", 
00090                         map_list_of
00091                                 ("minDist", "1.0")
00092                 )
00093         );
00094         
00095         // This filter will randomly remove 35% of the points.
00096         PM::DataPointsFilter* randSubsample(
00097                 PM::get().DataPointsFilterRegistrar.create(
00098                         "RandomSamplingDataPointsFilter", 
00099                         map_list_of
00100                                 ("prob", toParam(0.65))
00101                 )
00102         );
00103 
00104         // For a complete description of filter, see 
00105         // https://github.com/ethz-asl/libpointmatcher/blob/master/doc/Datafilters.md
00106         PM::DataPointsFilter* normalFilter(
00107                 PM::get().DataPointsFilterRegistrar.create(
00108                         "SurfaceNormalDataPointsFilter",
00109                         map_list_of
00110                                 ("knn", toParam(10))
00111                                 ("epsilon", toParam(5)) 
00112                                 ("keepNormals",toParam(1))
00113                                 ("keepDensities",toParam(0))
00114                 )
00115         );
00116 
00117         PM::DataPointsFilter* densityFilter(
00118                 PM::get().DataPointsFilterRegistrar.create(
00119                         "SurfaceNormalDataPointsFilter",
00120                         map_list_of
00121                                 ("knn", "10")
00122                                 ("epsilon", "5") 
00123                                 ("keepNormals","0")
00124                                 ("keepDensities","1")
00125                 )
00126         );
00127         
00128         PM::DataPointsFilter* observationDirectionFilter(
00129                 PM::get().DataPointsFilterRegistrar.create(
00130                         "ObservationDirectionDataPointsFilter"
00131                 )
00132         );
00133         
00134         PM::DataPointsFilter* orientNormalFilter(
00135                 PM::get().DataPointsFilterRegistrar.create(
00136                         "OrientNormalsDataPointsFilter",
00137                         map_list_of
00138                                 ("towardCenter", "1")
00139                 )
00140         );
00141         
00142         PM::DataPointsFilter* uniformSubsample(
00143                 PM::get().DataPointsFilterRegistrar.create(
00144                         "MaxDensityDataPointsFilter",
00145                         map_list_of
00146                                 ("maxDensity", toParam(30))
00147                 )
00148         );
00149         
00150         PM::DataPointsFilter* shadowFilter(
00151                 PM::get().DataPointsFilterRegistrar.create(
00152                         "ShadowDataPointsFilter"
00153                 )
00154         );
00155 
00156         for(unsigned i=0; i < list.size(); i++)
00157         {
00158                 cout << endl << "-----------------------------" << endl;
00159                 cout << "Loading " << list[i].readingFileName;
00160                 newCloud = DP::load(list[i].readingFileName);
00161 
00162                 cout << " found " << newCloud.getNbPoints() << " points. " << endl;
00163 
00164         
00165                 if(list[i].groundTruthTransformation.rows() != 0)
00166                         T = list[i].groundTruthTransformation;
00167                 else
00168                 {
00169                         cout << "ERROR: the field gTXX (ground truth) is required" << endl;
00170                         abort();
00171                 }
00172 
00173                 PM::Parameters params;
00174                 
00175                 // Remove the scanner
00176                 newCloud = removeScanner->filter(newCloud);
00177 
00178 
00179                 // Accelerate the process and dissolve lines
00180                 newCloud = randSubsample->filter(newCloud);
00181                 
00182                 // Build filter to remove shadow points and down-sample
00183                 newCloud = normalFilter->filter(newCloud);
00184                 newCloud = observationDirectionFilter->filter(newCloud);
00185                 newCloud = orientNormalFilter->filter(newCloud);
00186                 newCloud = shadowFilter->filter(newCloud);
00187 
00188                 // Transforme pointCloud
00189                 cout << "Transformation matrix: " << endl << T << endl;
00190                 newCloud = transformation->compute(newCloud, T);
00191 
00192                 if(i==0)
00193                 {
00194                         mapCloud = newCloud;
00195                 }
00196                 else
00197                 {
00198                         mapCloud.concatenate(newCloud);
00199                         
00200                         // Control point cloud size
00201                         double probToKeep = totalPointCount/(double)mapCloud.features.cols();
00202                         if(probToKeep < 1)
00203                         {
00204                                 
00205                                 mapCloud = densityFilter->filter(mapCloud);
00206                                 mapCloud = uniformSubsample->filter(mapCloud);
00207 
00208                                 probToKeep = totalPointCount/(double)mapCloud.features.cols();
00209                                 
00210                                 if(probToKeep < 1)
00211                                 {
00212                                         cout << "Randomly keep " << probToKeep*100 << "\% points" << endl; 
00213                                         randSubsample = PM::get().DataPointsFilterRegistrar.create(
00214                                                 "RandomSamplingDataPointsFilter", 
00215                                                 map_list_of
00216                                                         ("prob", toParam(probToKeep))
00217                                         );
00218                                         mapCloud = randSubsample->filter(mapCloud);
00219                                 }
00220                         }
00221                 }
00222 
00223                 stringstream outputFileNameIter;
00224                 outputFileNameIter << boost::filesystem::path(outputFileName).stem().c_str() << "_" << i << ".vtk";
00225                 
00226                 mapCloud.save(outputFileNameIter.str());
00227         }
00228         
00229         mapCloud = densityFilter->filter(mapCloud);
00230         mapCloud = uniformSubsample->filter(mapCloud);
00231         
00232         mapCloud = densityFilter->filter(mapCloud);
00233 
00234         cout << endl ;
00235         cout <<  "-----------------------------" << endl;
00236         cout <<  "-----------------------------" << endl;
00237         cout << "Final number of points in the map: " << mapCloud.getNbPoints() << endl;
00238         mapCloud.save(outputFileName);
00239         cout << endl ;
00240 
00241         return 0;
00242 }
00243 
00244 void validateArgs(int argc, char *argv[])
00245 {
00246         if (!(argc == 4))
00247         {
00248                 cerr << endl;
00249                 cerr << "Error in command line, usage " << argv[0] << " listOfFiles.csv maxPoint outputFileName.{vtk,csv,ply}" << endl;
00250                 cerr << endl;
00251                 cerr << "   example using file from example/data: " << endl;
00252                 cerr << "        " << argv[0] << " carCloudList.csv 30000 test.vtk" << endl;
00253                 cerr << endl;
00254                 cerr << "Note: the file listOfFiles.csv need to include a serialize transformation matrix. For example:" << endl;
00255                 cerr << "      fileName1.vtk, T00, T01, T02, T03, T10, T11, T12, T13, T20, T21, T22, T23, T30, T31, T32" << endl;
00256                 cerr << endl;
00257                 cerr << "Where Txy would be a 4x4 transformation matrix:" << endl;
00258                 cerr << "      [T00 T01 T02 T03] " << endl;
00259                 cerr << "      [T10 T11 T12 T13] " << endl;
00260                 cerr << "      [T20 T21 T22 T23] " << endl;
00261                 cerr << "      [T30 T31 T32 T33] (i.e., 0,0,0,1)" << endl;
00262                 cerr << endl;
00263                 cerr << "For more data visit:" << endl;
00264                 cerr << "      http://projects.asl.ethz.ch/datasets/doku.php?id=laserregistration:laserregistration" << endl;
00265                 cerr << endl;
00266 
00267                 abort();
00268         }
00269 }
00270 
00271 
00272 


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