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 
00044 using namespace std;
00045 
00046 typedef PointMatcher<float> PM;
00047 typedef PM::DataPoints DP;
00048 typedef PM::Parameters Parameters;
00049 typedef PointMatcherSupport::CurrentBibliography CurrentBibliography;
00050 
00051 void listModules();
00052 int validateArgs(const int argc, const char *argv[], bool& isCSV, string&, string&);
00053 void usage(const char *argv[]);
00054 
00062 int main(int argc, const char *argv[])
00063 {
00064         bool isCSV = true;
00065         string configFile;
00066         string outputBaseFile("test");
00067         const int ret = validateArgs(argc, argv, isCSV, configFile, outputBaseFile);
00068         if (ret != 0)
00069                 return ret;
00070         const char *refFile(argv[argc-2]);
00071         const char *dataFile(argv[argc-1]);
00072         
00073         // Load point clouds
00074         const DP ref(DP::load(refFile));
00075         const DP data(DP::load(dataFile));
00076 
00077         // Create the default ICP algorithm
00078         PM::ICP icp;
00079         
00080         if (configFile.empty())
00081         {
00082                 // See the implementation of setDefault() to create a custom ICP algorithm
00083                 icp.setDefault();
00084         }
00085         else
00086         {
00087                 // load YAML config
00088                 ifstream ifs(configFile.c_str());
00089                 if (!ifs.good())
00090                 {
00091                         cerr << "Cannot open config file " << configFile << ", usage:"; usage(argv); exit(1);
00092                 }
00093                 icp.loadFromYaml(ifs);
00094         }
00095 
00096         // Compute the transformation to express data in ref
00097         PM::TransformationParameters T = icp(data, ref);
00098         cout << "match ratio: " << icp.errorMinimizer->getWeightedPointUsedRatio() << endl;
00099 
00100         // Transform data to express it in ref
00101         DP data_out(data);
00102         icp.transformations.apply(data_out, T);
00103         
00104         // Safe files to see the results
00105         ref.save(outputBaseFile + "_ref.vtk");
00106         data.save(outputBaseFile + "_data_in.vtk");
00107         data_out.save(outputBaseFile + "_data_out.vtk");
00108         cout << "Final transformation:" << endl << T << endl;
00109 
00110         return 0;
00111 }
00112 
00113 // The following code allows to dump all existing modules
00114 template<typename R>
00115 void dumpRegistrar(const PM& pm, const R& registrar, const std::string& name, CurrentBibliography& bib)
00116 {
00117         cout << "* " << name << " *\n" << endl;
00118         for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it)
00119         {
00120                 cout << it->first << endl;
00121                 cout << getAndReplaceBibEntries(it->second->description(), bib) << endl;
00122                 cout << it->second->availableParameters() << endl;
00123         }
00124         cout << endl;
00125 }
00126 
00127 #define DUMP_REGISTRAR_CONTENT(pm, name, bib) \
00128         dumpRegistrar(pm, pm.REG(name), # name, bib);
00129 
00130 void listModules()
00131 {
00132         CurrentBibliography bib;
00133         
00134         DUMP_REGISTRAR_CONTENT(PM::get(), Transformation, bib)
00135         DUMP_REGISTRAR_CONTENT(PM::get(), DataPointsFilter, bib)
00136         DUMP_REGISTRAR_CONTENT(PM::get(), Matcher, bib)
00137         DUMP_REGISTRAR_CONTENT(PM::get(), OutlierFilter, bib)
00138         DUMP_REGISTRAR_CONTENT(PM::get(), ErrorMinimizer, bib)
00139         DUMP_REGISTRAR_CONTENT(PM::get(), TransformationChecker, bib)
00140         DUMP_REGISTRAR_CONTENT(PM::get(), Inspector, bib)
00141         DUMP_REGISTRAR_CONTENT(PM::get(), Logger, bib)
00142         
00143         cout << "* Bibliography *" << endl << endl;
00144         bib.dump(cout);
00145 }
00146 
00147 // Make sure that the command arguments make sense
00148 int validateArgs(const int argc, const char *argv[], bool& isCSV, string& configFile, string& outputBaseFile)
00149 {
00150         if (argc == 1)
00151         {
00152                 cerr << "Not enough arguments, usage:";
00153                 usage(argv);
00154                 return 1;
00155         }
00156         else if (argc == 2)
00157         {
00158                 if (string(argv[1]) == "-l")
00159                 {
00160                         listModules();
00161                         return -1; // we use -1 to say that we wish to quit but in a normal way
00162                 }
00163                 else
00164                 {
00165                         cerr << "Wrong option, usage:";
00166                         usage(argv);
00167                         return 2;
00168                 }
00169         }
00170         
00171         const int endOpt(argc - 2);
00172         for (int i = 1; i < endOpt; i += 2)
00173         {
00174                 const string opt(argv[i]);
00175                 if (i + 1 > endOpt)
00176                 {
00177                         cerr << "Missing value for option " << opt << ", usage:"; usage(argv); exit(1);
00178                 }
00179                 if (opt == "--config")
00180                         configFile = argv[i+1];
00181                 else if (opt == "--output")
00182                         outputBaseFile = argv[i+1];
00183                 else
00184                 {
00185                         cerr << "Unknown option " << opt << ", usage:"; usage(argv); exit(1);
00186                 }
00187         }
00188         return 0;
00189 }
00190 
00191 // Dump command-line help
00192 void usage(const char *argv[])
00193 {
00194         cerr << endl << endl;
00195         cerr << "* To list modules:" << endl;
00196         cerr << "  " << argv[0] << " -l" << endl;
00197         cerr << endl;
00198         cerr << "* To run ICP:" << endl;
00199         cerr << "  " << argv[0] << " [OPTIONS] reference.csv reading.csv" << endl;
00200         cerr << endl;
00201         cerr << "OPTIONS can be a combination of:" << endl;
00202         cerr << "--config YAML_CONFIG_FILE  Load the config from a YAML file (default: default parameters)" << endl;
00203         cerr << "--output FILENAME          Name of output files (default: test)" << endl;
00204         cerr << endl;
00205         cerr << "Running this program with a VTKFileInspector as Inspector will create three" << endl;
00206         cerr << "vtk ouptput files: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl;
00207         cerr << endl << "2D Example:" << endl;
00208         cerr << "  " << argv[0] << " examples/data/2D_twoBoxes.csv examples/data/2D_oneBox.csv" << endl;
00209         cerr << endl << "3D Example:" << endl;
00210         cerr << "  " << argv[0] << " examples/data/car_cloud400.csv examples/data/car_cloud401.csv" << endl;
00211         cerr << endl;
00212 }


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