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


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