icp.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/Bibliography.h"
00038 
00039 #include "boost/filesystem.hpp"
00040 
00041 #include <cassert>
00042 #include <fstream>
00043 #include <iostream>
00044 #include <algorithm>
00045 
00046 using namespace std;
00047 
00048 typedef PointMatcher<float> PM;
00049 typedef PM::DataPoints DP;
00050 typedef PM::Parameters Parameters;
00051 typedef PointMatcherSupport::CurrentBibliography CurrentBibliography;
00052 
00053 void listModules();
00054 int validateArgs(const int argc, const char *argv[],
00055                                  bool& isTransfoSaved,
00056                                  string& configFile,
00057                                  string& outputBaseFile,
00058                                  string& initTranslation, string& initRotation);
00059 PM::TransformationParameters parseTranslation(string& translation,
00060                                                                                           const int cloudDimension);
00061 PM::TransformationParameters parseRotation(string& rotation,
00062                                                                                    const int cloudDimension);
00063 void usage(const char *argv[]);
00064 
00072 int main(int argc, const char *argv[])
00073 {
00074         bool isTransfoSaved = false;
00075         string configFile;
00076         string outputBaseFile("test");
00077         string initTranslation("0,0,0");
00078         string initRotation("1,0,0;0,1,0;0,0,1");
00079         const int ret = validateArgs(argc, argv, isTransfoSaved, configFile,
00080                                                                  outputBaseFile, initTranslation, initRotation);
00081         if (ret != 0)
00082         {
00083                 return ret;
00084         }
00085         const char *refFile(argv[argc-2]);
00086         const char *dataFile(argv[argc-1]);
00087 
00088         // Load point clouds
00089         const DP ref(DP::load(refFile));
00090         const DP data(DP::load(dataFile));
00091 
00092         // Create the default ICP algorithm
00093         PM::ICP icp;
00094 
00095         if (configFile.empty())
00096         {
00097                 // See the implementation of setDefault() to create a custom ICP algorithm
00098                 icp.setDefault();
00099         }
00100         else
00101         {
00102                 // load YAML config
00103                 ifstream ifs(configFile.c_str());
00104                 if (!ifs.good())
00105                 {
00106                         cerr << "Cannot open config file " << configFile << ", usage:"; usage(argv); exit(1);
00107                 }
00108                 icp.loadFromYaml(ifs);
00109         }
00110 
00111         int cloudDimension = ref.getEuclideanDim();
00112         
00113         if (!(cloudDimension == 2 || cloudDimension == 3)) 
00114         {
00115                 cerr << "Invalid input point clouds dimension" << endl;
00116                 exit(1);
00117         }
00118 
00119         PM::TransformationParameters translation =
00120                         parseTranslation(initTranslation, cloudDimension);
00121         PM::TransformationParameters rotation =
00122                         parseRotation(initRotation, cloudDimension);
00123         PM::TransformationParameters initTransfo = translation*rotation;
00124 
00125         PM::Transformation* rigidTrans;
00126         rigidTrans = PM::get().REG(Transformation).create("RigidTransformation");
00127 
00128         if (!rigidTrans->checkParameters(initTransfo)) {
00129                 cerr << endl
00130                          << "Initial transformation is not rigid, identiy will be used"
00131                          << endl;
00132                 initTransfo = PM::TransformationParameters::Identity(
00133                                         cloudDimension+1,cloudDimension+1);
00134         }
00135 
00136         const DP initializedData = rigidTrans->compute(data, initTransfo);
00137 
00138         // Compute the transformation to express data in ref
00139         PM::TransformationParameters T = icp(initializedData, ref);
00140         cout << "match ratio: " << icp.errorMinimizer->getWeightedPointUsedRatio() << endl;
00141 
00142         // Transform data to express it in ref
00143         DP data_out(initializedData);
00144         icp.transformations.apply(data_out, T);
00145 
00146         // Safe files to see the results
00147         ref.save(outputBaseFile + "_ref.vtk");
00148         data.save(outputBaseFile + "_data_in.vtk");
00149         data_out.save(outputBaseFile + "_data_out.vtk");
00150         if(isTransfoSaved) {
00151                 ofstream transfoFile;
00152                 string initFileName = outputBaseFile + "_init_transfo.txt";
00153                 string icpFileName = outputBaseFile + "_icp_transfo.txt";
00154                 string completeFileName = outputBaseFile + "_complete_transfo.txt";
00155 
00156                 transfoFile.open(initFileName.c_str());
00157                 if(transfoFile.is_open()) {
00158                         transfoFile << initTransfo << endl;
00159                         transfoFile.close();
00160                 } else {
00161                         cout << "Unable to write the initial transformation file\n" << endl;
00162                 }
00163 
00164                 transfoFile.open(icpFileName.c_str());
00165                 if(transfoFile.is_open()) {
00166                         transfoFile << T << endl;
00167                         transfoFile.close();
00168                 } else {
00169                         cout << "Unable to write the ICP transformation file\n" << endl;
00170                 }
00171 
00172                 transfoFile.open(completeFileName.c_str());
00173                 if(transfoFile.is_open()) {
00174                         transfoFile << T*initTransfo << endl;
00175                         transfoFile.close();
00176                 } else {
00177                         cout << "Unable to write the complete transformation file\n" << endl;
00178                 }
00179         }
00180         else {
00181                 cout << "ICP transformation:" << endl << T << endl;
00182         }
00183 
00184         return 0;
00185 }
00186 
00187 // The following code allows to dump all existing modules
00188 template<typename R>
00189 void dumpRegistrar(const PM& pm, const R& registrar, const std::string& name,
00190                                    CurrentBibliography& bib)
00191 {
00192         cout << "* " << name << " *\n" << endl;
00193         for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it)
00194         {
00195                 cout << it->first << endl;
00196                 cout << getAndReplaceBibEntries(it->second->description(), bib) << endl;
00197                 cout << it->second->availableParameters() << endl;
00198         }
00199         cout << endl;
00200 }
00201 
00202 #define DUMP_REGISTRAR_CONTENT(pm, name, bib) \
00203         dumpRegistrar(pm, pm.REG(name), # name, bib);
00204 
00205 void listModules()
00206 {
00207         CurrentBibliography bib;
00208 
00209         DUMP_REGISTRAR_CONTENT(PM::get(), Transformation, bib)
00210                         DUMP_REGISTRAR_CONTENT(PM::get(), DataPointsFilter, bib)
00211                         DUMP_REGISTRAR_CONTENT(PM::get(), Matcher, bib)
00212                         DUMP_REGISTRAR_CONTENT(PM::get(), OutlierFilter, bib)
00213                         DUMP_REGISTRAR_CONTENT(PM::get(), ErrorMinimizer, bib)
00214                         DUMP_REGISTRAR_CONTENT(PM::get(), TransformationChecker, bib)
00215                         DUMP_REGISTRAR_CONTENT(PM::get(), Inspector, bib)
00216                         DUMP_REGISTRAR_CONTENT(PM::get(), Logger, bib)
00217 
00218                         cout << "* Bibliography *" << endl << endl;
00219         bib.dump(cout);
00220 }
00221 
00222 // Make sure that the command arguments make sense
00223 int validateArgs(const int argc, const char *argv[],
00224                                  bool& isTransfoSaved,
00225                                  string& configFile,
00226                                  string& outputBaseFile,
00227                                  string& initTranslation, string& initRotation)
00228 {
00229         if (argc == 1)
00230         {
00231                 cerr << "Not enough arguments, usage:";
00232                 usage(argv);
00233                 return 1;
00234         }
00235         else if (argc == 2)
00236         {
00237                 if (string(argv[1]) == "-l")
00238                 {
00239                         listModules();
00240                         return -1; // we use -1 to say that we wish to quit but in a normal way
00241                 }
00242                 else
00243                 {
00244                         cerr << "Wrong option, usage:";
00245                         usage(argv);
00246                         return 2;
00247                 }
00248         }
00249 
00250         const int endOpt(argc - 2);
00251         for (int i = 1; i < endOpt; i += 2)
00252         {
00253                 const string opt(argv[i]);
00254                 if (i + 1 > endOpt)
00255                 {
00256                         cerr << "Missing value for option " << opt << ", usage:"; usage(argv); exit(1);
00257                 }
00258                 if (opt == "--isTransfoSaved") {
00259                         if (strcmp(argv[i+1], "1") == 0 || strcmp(argv[i+1], "true") == 0) {
00260                                 isTransfoSaved = true;
00261                         }
00262                         else if (strcmp(argv[i+1], "0") == 0
00263                                          || strcmp(argv[i+1],"false") == 0) {
00264                                 isTransfoSaved = false;
00265                         }
00266                         else {
00267                                 cerr << "Invalid value for parameter isTransfoSaved." << endl
00268                                          << "Value must be true or false or 1 or 0." << endl
00269                                          << "Default value will be used." << endl;
00270                         }
00271                 }
00272                 else if (opt == "--config") {
00273                         configFile = argv[i+1];
00274                 }
00275                 else if (opt == "--output") {
00276                         outputBaseFile = argv[i+1];
00277                 }
00278                 else if (opt == "--initTranslation") {
00279                         initTranslation = argv[i+1];
00280                 }
00281                 else if (opt == "--initRotation") {
00282                         initRotation = argv[i+1];
00283                 }
00284                 else
00285                 {
00286                         cerr << "Unknown option " << opt << ", usage:"; usage(argv); exit(1);
00287                 }
00288         }
00289         return 0;
00290 }
00291 
00292 PM::TransformationParameters parseTranslation(string& translation,
00293                                                                                           const int cloudDimension) {
00294         PM::TransformationParameters parsedTranslation;
00295         parsedTranslation = PM::TransformationParameters::Identity(
00296                                 cloudDimension+1,cloudDimension+1);
00297 
00298         translation.erase(std::remove(translation.begin(), translation.end(), '['),
00299                                           translation.end());
00300         translation.erase(std::remove(translation.begin(), translation.end(), ']'),
00301                                           translation.end());
00302         std::replace( translation.begin(), translation.end(), ',', ' ');
00303         std::replace( translation.begin(), translation.end(), ';', ' ');
00304 
00305         float translationValues[3] = {0};
00306         stringstream translationStringStream(translation);
00307         for( int i = 0; i < cloudDimension; i++) {
00308                 if(!(translationStringStream >> translationValues[i])) {
00309                         cerr << "An error occured while trying to parse the initial "
00310                                  << "translation." << endl
00311                                  << "No initial translation will be used" << endl;
00312                         return parsedTranslation;
00313                 }
00314         }
00315         float extraOutput = 0;
00316         if((translationStringStream >> extraOutput)) {
00317                 cerr << "Wrong initial translation size" << endl
00318                          << "No initial translation will be used" << endl;
00319                 return parsedTranslation;
00320         }
00321 
00322         for( int i = 0; i < cloudDimension; i++) {
00323                 parsedTranslation(i,cloudDimension) = translationValues[i];
00324         }
00325 
00326         return parsedTranslation;
00327 }
00328 
00329 PM::TransformationParameters parseRotation(string &rotation,
00330                                                                                    const int cloudDimension){
00331         PM::TransformationParameters parsedRotation;
00332         parsedRotation = PM::TransformationParameters::Identity(
00333                                 cloudDimension+1,cloudDimension+1);
00334 
00335         rotation.erase(std::remove(rotation.begin(), rotation.end(), '['),
00336                                    rotation.end());
00337         rotation.erase(std::remove(rotation.begin(), rotation.end(), ']'),
00338                                    rotation.end());
00339         std::replace( rotation.begin(), rotation.end(), ',', ' ');
00340         std::replace( rotation.begin(), rotation.end(), ';', ' ');
00341 
00342         float rotationMatrix[9] = {0};
00343         stringstream rotationStringStream(rotation);
00344         for( int i = 0; i < cloudDimension*cloudDimension; i++) {
00345                 if(!(rotationStringStream >> rotationMatrix[i])) {
00346                         cerr << "An error occured while trying to parse the initial "
00347                                  << "rotation." << endl
00348                                  << "No initial rotation will be used" << endl;
00349                         return parsedRotation;
00350                 }
00351         }
00352         float extraOutput = 0;
00353         if((rotationStringStream >> extraOutput)) {
00354                 cerr << "Wrong initial rotation size" << endl
00355                          << "No initial rotation will be used" << endl;
00356                 return parsedRotation;
00357         }
00358 
00359         for( int i = 0; i < cloudDimension*cloudDimension; i++) {
00360                 parsedRotation(i/cloudDimension,i%cloudDimension) = rotationMatrix[i];
00361         }
00362 
00363         return parsedRotation;
00364 }
00365 
00366 // Dump command-line help
00367 void usage(const char *argv[])
00368 {
00369         //TODO: add new options --isTransfoSaved, --initTranslation, --initRotation
00370         cerr << endl << endl;
00371         cerr << "* To list modules:" << endl;
00372         cerr << "  " << argv[0] << " -l" << endl;
00373         cerr << endl;
00374         cerr << "* To run ICP:" << endl;
00375         cerr << "  " << argv[0] << " [OPTIONS] reference.csv reading.csv" << endl;
00376         cerr << endl;
00377         cerr << "OPTIONS can be a combination of:" << endl;
00378         cerr << "--config YAML_CONFIG_FILE  Load the config from a YAML file (default: default parameters)" << endl;
00379         cerr << "--output BASEFILENAME      Name of output files (default: test)" << endl;
00380         cerr << "--initTranslation [x,y,z]  Add an initial 3D translation before applying ICP (default: 0,0,0)" << endl;
00381         cerr << "--initTranslation [x,y]    Add an initial 2D translation before applying ICP (default: 0,0)" << endl;
00382         cerr << "--initRotation [r00,r01,r02,r10,r11,r12,r20,r21,r22]" << endl;
00383         cerr << "                           Add an initial 3D rotation before applying ICP (default: 1,0,0,0,1,0,0,0,1)" << endl;
00384         cerr << "--initRotation [r00,r01,r10,r11]" << endl;
00385         cerr << "                           Add an initial 2D rotation before applying ICP (default: 1,0,0,1)" << endl;
00386         cerr << "--isTransfoSaved BOOL      Save transformation matrix in three different files:" << endl;
00387         cerr << "                             - BASEFILENAME_inti_transfo.txt" << endl;
00388         cerr << "                             - BASEFILENAME_icp_transfo.txt" << endl;
00389         cerr << "                             - BASEFILENAME_complete_transfo.txt" << endl;
00390         cerr << "                           (default: false)" << endl;
00391         cerr << endl;
00392         cerr << "Running this program with a VTKFileInspector as Inspector will create three" << endl;
00393         cerr << "vtk ouptput files: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl;
00394         cerr << endl << "2D Example:" << endl;
00395         cerr << "  " << argv[0] << " ../examples/data/2D_twoBoxes.csv ../examples/data/2D_oneBox.csv" << endl;
00396         cerr << endl << "3D Example:" << endl;
00397         cerr << "  " << argv[0] << " ../examples/data/car_cloud400.csv ../examples/data/car_cloud401.csv" << endl;
00398         cerr << endl;
00399 }


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