icp_advance_api.cpp
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2012,
6 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
7 You can contact the authors at <f dot pomerleau at gmail dot com> and
8 <stephane at magnenat dot net>
9 
10 All rights reserved.
11 
12 Redistribution and use in source and binary forms, with or without
13 modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of the <organization> nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
27 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 
34 */
35 
38 
39 #include "boost/filesystem.hpp"
40 
41 #include <cassert>
42 #include <fstream>
43 #include <iostream>
44 #include <algorithm>
45 
46 using namespace std;
47 using namespace PointMatcherSupport;
48 
52 
53 void listModules();
54 int validateArgs(const int argc, const char *argv[],
55  bool& isTransfoSaved,
56  string& configFile,
57  string& outputBaseFile,
58  string& initTranslation, string& initRotation);
60  const int cloudDimension);
62  const int cloudDimension);
63 void usage(const char *argv[]);
64 
72 int main(int argc, const char *argv[])
73 {
74  bool isTransfoSaved = false;
75  string configFile;
76  string outputBaseFile("test");
77  string initTranslation("0,0,0");
78  string initRotation("1,0,0;0,1,0;0,0,1");
79  const int ret = validateArgs(argc, argv, isTransfoSaved, configFile,
80  outputBaseFile, initTranslation, initRotation);
81  if (ret != 0)
82  {
83  return ret;
84  }
85  const char *refFile(argv[argc-2]);
86  const char *dataFile(argv[argc-1]);
87 
88  // Load point clouds
89  const DP ref(DP::load(refFile));
90  const DP data(DP::load(dataFile));
91 
92  // Create the default ICP algorithm
93  PM::ICP icp;
94 
95  if (configFile.empty())
96  {
97  // See the implementation of setDefault() to create a custom ICP algorithm
98  icp.setDefault();
99  }
100  else
101  {
102  // load YAML config
103  ifstream ifs(configFile.c_str());
104  if (!ifs.good())
105  {
106  cerr << "Cannot open config file " << configFile << ", usage:"; usage(argv); exit(1);
107  }
108  icp.loadFromYaml(ifs);
109  }
110 
111  int cloudDimension = ref.getEuclideanDim();
112 
113  if (!(cloudDimension == 2 || cloudDimension == 3))
114  {
115  cerr << "Invalid input point clouds dimension" << endl;
116  exit(1);
117  }
118 
120  parseTranslation(initTranslation, cloudDimension);
122  parseRotation(initRotation, cloudDimension);
123  PM::TransformationParameters initTransfo = translation*rotation;
124 
125  std::shared_ptr<PM::Transformation> rigidTrans;
126  rigidTrans = PM::get().REG(Transformation).create("RigidTransformation");
127 
128  if (!rigidTrans->checkParameters(initTransfo)) {
129  cerr << endl
130  << "Initial transformation is not rigid, identiy will be used"
131  << endl;
132  initTransfo = PM::TransformationParameters::Identity(
133  cloudDimension+1,cloudDimension+1);
134  }
135 
136  const DP initializedData = rigidTrans->compute(data, initTransfo);
137 
138  // Compute the transformation to express data in ref
139  PM::TransformationParameters T = icp(initializedData, ref);
140  float matchRatio = icp.errorMinimizer->getWeightedPointUsedRatio();
141  cout << "match ratio: " << matchRatio << endl;
142 
143 
144 
145  // Transform data to express it in ref
146  DP data_out(initializedData);
147  icp.transformations.apply(data_out, T);
148 
149  cout << endl << "------------------" << endl;
150 
151  // START demo 1
152  // Test for retrieving Haussdorff distance (with outliers). We generate new matching module
153  // specifically for this purpose.
154  //
155  // INPUTS:
156  // ref: point cloud used as reference
157  // data_out: aligned point cloud (using the transformation outputted by icp)
158  // icp: icp object used to aligned the point clouds
159 
160 
161  // Structure to hold future match results
163 
165  params["knn"] = toParam(1); // for Hausdorff distance, we only need the first closest point
166  params["epsilon"] = toParam(0);
167 
168  std::shared_ptr<PM::Matcher> matcherHausdorff = PM::get().MatcherRegistrar.create("KDTreeMatcher", params);
169 
170  // max. distance from reading to reference
171  matcherHausdorff->init(ref);
172  matches = matcherHausdorff->findClosests(data_out);
173  float maxDist1 = matches.getDistsQuantile(1.0);
174  float maxDistRobust1 = matches.getDistsQuantile(0.85);
175 
176  // max. distance from reference to reading
177  matcherHausdorff->init(data_out);
178  matches = matcherHausdorff->findClosests(ref);
179  float maxDist2 = matches.getDistsQuantile(1.0);
180  float maxDistRobust2 = matches.getDistsQuantile(0.85);
181 
182  float haussdorffDist = std::max(maxDist1, maxDist2);
183  float haussdorffQuantileDist = std::max(maxDistRobust1, maxDistRobust2);
184 
185  cout << "Haussdorff distance: " << std::sqrt(haussdorffDist) << " m" << endl;
186  cout << "Haussdorff quantile distance: " << std::sqrt(haussdorffQuantileDist) << " m" << endl;
187 
188  // START demo 2
189  // Test for retrieving paired point mean distance without outliers. We reuse the same module used for
190  // the icp object.
191  //
192  // INPUTS:
193  // ref: point cloud used as reference
194  // data_out: aligned point cloud (using the transformation outputted by icp)
195  // icp: icp object used to aligned the point clouds
196 
197  // initiate the matching with unfiltered point cloud
198  icp.matcher->init(ref);
199 
200  // extract closest points
201  matches = icp.matcher->findClosests(data_out);
202 
203  // weight paired points
204  const PM::OutlierWeights outlierWeights = icp.outlierFilters.compute(data_out, ref, matches);
205 
206  // generate tuples of matched points and remove pairs with zero weight
207  const PM::ErrorMinimizer::ErrorElements matchedPoints( data_out, ref, outlierWeights, matches);
208 
209  // extract relevant information for convenience
210  const int dim = matchedPoints.reading.getEuclideanDim();
211  const int nbMatchedPoints = matchedPoints.reading.getNbPoints();
212  const PM::Matrix matchedRead = matchedPoints.reading.features.topRows(dim);
213  const PM::Matrix matchedRef = matchedPoints.reference.features.topRows(dim);
214 
215  // compute mean distance
216  const PM::Matrix dist = (matchedRead - matchedRef).colwise().norm(); // replace that by squaredNorm() to save computation time
217  const float meanDist = dist.sum()/nbMatchedPoints;
218  cout << "Robust mean distance: " << meanDist << " m" << endl;
219 
220  // END demo
221 
222  cout << "------------------" << endl << endl;
223 
224 
225  // Safe files to see the results
226  ref.save(outputBaseFile + "_ref.vtk");
227  data.save(outputBaseFile + "_data_in.vtk");
228  data_out.save(outputBaseFile + "_data_out.vtk");
229  if(isTransfoSaved) {
230  ofstream transfoFile;
231  string initFileName = outputBaseFile + "_init_transfo.txt";
232  string icpFileName = outputBaseFile + "_icp_transfo.txt";
233  string completeFileName = outputBaseFile + "_complete_transfo.txt";
234 
235  transfoFile.open(initFileName.c_str());
236  if(transfoFile.is_open()) {
237  transfoFile << initTransfo << endl;
238  transfoFile.close();
239  } else {
240  cout << "Unable to write the initial transformation file\n" << endl;
241  }
242 
243  transfoFile.open(icpFileName.c_str());
244  if(transfoFile.is_open()) {
245  transfoFile << T << endl;
246  transfoFile.close();
247  } else {
248  cout << "Unable to write the ICP transformation file\n" << endl;
249  }
250 
251  transfoFile.open(completeFileName.c_str());
252  if(transfoFile.is_open()) {
253  transfoFile << T*initTransfo << endl;
254  transfoFile.close();
255  } else {
256  cout << "Unable to write the complete transformation file\n" << endl;
257  }
258  }
259  else {
260  cout << "ICP transformation:" << endl << T << endl;
261  }
262 
263  return 0;
264 }
265 
266 // The following code allows to dump all existing modules
267 template<typename R>
268 void dumpRegistrar(const PM& pm, const R& registrar, const std::string& name,
269  CurrentBibliography& bib)
270 {
271  cout << "* " << name << " *\n" << endl;
272  for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it)
273  {
274  cout << it->first << endl;
275  cout << getAndReplaceBibEntries(it->second->description(), bib) << endl;
276  cout << it->second->availableParameters() << endl;
277  }
278  cout << endl;
279 }
280 
281 #define DUMP_REGISTRAR_CONTENT(pm, name, bib) \
282  dumpRegistrar(pm, pm.REG(name), # name, bib);
283 
285 {
287 
296 
297  cout << "* Bibliography *" << endl << endl;
298  bib.dump(cout);
299 }
300 
301 // Make sure that the command arguments make sense
302 int validateArgs(const int argc, const char *argv[],
303  bool& isTransfoSaved,
304  string& configFile,
305  string& outputBaseFile,
306  string& initTranslation, string& initRotation)
307 {
308  if (argc == 1)
309  {
310  cerr << "Not enough arguments, usage:";
311  usage(argv);
312  return 1;
313  }
314  else if (argc == 2)
315  {
316  if (string(argv[1]) == "-l")
317  {
318  listModules();
319  return -1; // we use -1 to say that we wish to quit but in a normal way
320  }
321  else
322  {
323  cerr << "Wrong option, usage:";
324  usage(argv);
325  return 2;
326  }
327  }
328 
329  const int endOpt(argc - 2);
330  for (int i = 1; i < endOpt; i += 2)
331  {
332  const string opt(argv[i]);
333  if (i + 1 > endOpt)
334  {
335  cerr << "Missing value for option " << opt << ", usage:"; usage(argv); exit(1);
336  }
337  if (opt == "--isTransfoSaved") {
338  if (strcmp(argv[i+1], "1") == 0 || strcmp(argv[i+1], "true") == 0) {
339  isTransfoSaved = true;
340  }
341  else if (strcmp(argv[i+1], "0") == 0
342  || strcmp(argv[i+1],"false") == 0) {
343  isTransfoSaved = false;
344  }
345  else {
346  cerr << "Invalid value for parameter isTransfoSaved." << endl
347  << "Value must be true or false or 1 or 0." << endl
348  << "Default value will be used." << endl;
349  }
350  }
351  else if (opt == "--config") {
352  configFile = argv[i+1];
353  }
354  else if (opt == "--output") {
355  outputBaseFile = argv[i+1];
356  }
357  else if (opt == "--initTranslation") {
358  initTranslation = argv[i+1];
359  }
360  else if (opt == "--initRotation") {
361  initRotation = argv[i+1];
362  }
363  else
364  {
365  cerr << "Unknown option " << opt << ", usage:"; usage(argv); exit(1);
366  }
367  }
368  return 0;
369 }
370 
372  const int cloudDimension) {
373  PM::TransformationParameters parsedTranslation;
374  parsedTranslation = PM::TransformationParameters::Identity(
375  cloudDimension+1,cloudDimension+1);
376 
377  translation.erase(std::remove(translation.begin(), translation.end(), '['),
378  translation.end());
379  translation.erase(std::remove(translation.begin(), translation.end(), ']'),
380  translation.end());
381  std::replace( translation.begin(), translation.end(), ',', ' ');
382  std::replace( translation.begin(), translation.end(), ';', ' ');
383 
384  float translationValues[3] = {0};
385  stringstream translationStringStream(translation);
386  for( int i = 0; i < cloudDimension; i++) {
387  if(!(translationStringStream >> translationValues[i])) {
388  cerr << "An error occured while trying to parse the initial "
389  << "translation." << endl
390  << "No initial translation will be used" << endl;
391  return parsedTranslation;
392  }
393  }
394  float extraOutput = 0;
395  if((translationStringStream >> extraOutput)) {
396  cerr << "Wrong initial translation size" << endl
397  << "No initial translation will be used" << endl;
398  return parsedTranslation;
399  }
400 
401  for( int i = 0; i < cloudDimension; i++) {
402  parsedTranslation(i,cloudDimension) = translationValues[i];
403  }
404 
405  return parsedTranslation;
406 }
407 
409  const int cloudDimension){
410  PM::TransformationParameters parsedRotation;
411  parsedRotation = PM::TransformationParameters::Identity(
412  cloudDimension+1,cloudDimension+1);
413 
414  rotation.erase(std::remove(rotation.begin(), rotation.end(), '['),
415  rotation.end());
416  rotation.erase(std::remove(rotation.begin(), rotation.end(), ']'),
417  rotation.end());
418  std::replace( rotation.begin(), rotation.end(), ',', ' ');
419  std::replace( rotation.begin(), rotation.end(), ';', ' ');
420 
421  float rotationMatrix[9] = {0};
422  stringstream rotationStringStream(rotation);
423  for( int i = 0; i < cloudDimension*cloudDimension; i++) {
424  if(!(rotationStringStream >> rotationMatrix[i])) {
425  cerr << "An error occured while trying to parse the initial "
426  << "rotation." << endl
427  << "No initial rotation will be used" << endl;
428  return parsedRotation;
429  }
430  }
431  float extraOutput = 0;
432  if((rotationStringStream >> extraOutput)) {
433  cerr << "Wrong initial rotation size" << endl
434  << "No initial rotation will be used" << endl;
435  return parsedRotation;
436  }
437 
438  for( int i = 0; i < cloudDimension*cloudDimension; i++) {
439  parsedRotation(i/cloudDimension,i%cloudDimension) = rotationMatrix[i];
440  }
441 
442  return parsedRotation;
443 }
444 
445 // Dump command-line help
446 void usage(const char *argv[])
447 {
448  //TODO: add new options --isTransfoSaved, --initTranslation, --initRotation
449  cerr << endl << endl;
450  cerr << "* To list modules:" << endl;
451  cerr << " " << argv[0] << " -l" << endl;
452  cerr << endl;
453  cerr << "* To run ICP:" << endl;
454  cerr << " " << argv[0] << " [OPTIONS] reference.csv reading.csv" << endl;
455  cerr << endl;
456  cerr << "OPTIONS can be a combination of:" << endl;
457  cerr << "--config YAML_CONFIG_FILE Load the config from a YAML file (default: default parameters)" << endl;
458  cerr << "--output BASEFILENAME Name of output files (default: test)" << endl;
459  cerr << "--initTranslation [x,y,z] Add an initial 3D translation before applying ICP (default: 0,0,0)" << endl;
460  cerr << "--initTranslation [x,y] Add an initial 2D translation before applying ICP (default: 0,0)" << endl;
461  cerr << "--initRotation [r00,r01,r02,r10,r11,r12,r20,r21,r22]" << endl;
462  cerr << " Add an initial 3D rotation before applying ICP (default: 1,0,0,0,1,0,0,0,1)" << endl;
463  cerr << "--initRotation [r00,r01,r10,r11]" << endl;
464  cerr << " Add an initial 2D rotation before applying ICP (default: 1,0,0,1)" << endl;
465  cerr << "--isTransfoSaved BOOL Save transformation matrix in three different files:" << endl;
466  cerr << " - BASEFILENAME_inti_transfo.txt" << endl;
467  cerr << " - BASEFILENAME_icp_transfo.txt" << endl;
468  cerr << " - BASEFILENAME_complete_transfo.txt" << endl;
469  cerr << " (default: false)" << endl;
470  cerr << endl;
471  cerr << "Running this program with a VTKFileInspector as Inspector will create three" << endl;
472  cerr << "vtk ouptput files: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl;
473  cerr << endl << "2D Example:" << endl;
474  cerr << " " << argv[0] << " ../examples/data/2D_twoBoxes.csv ../examples/data/2D_oneBox.csv" << endl;
475  cerr << endl << "3D Example:" << endl;
476  cerr << " " << argv[0] << " ../examples/data/car_cloud400.csv ../examples/data/car_cloud401.csv" << endl;
477  cerr << endl;
478 }
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
Definition: PointMatcher.h:397
PM::Parameters Parameters
public interface
void listModules()
The logger interface, used to output warnings and informations.
Definition: PointMatcher.h:104
std::string toParam(const S &value)
Return the a string value using lexical_cast.
std::string getAndReplaceBibEntries(const std::string &text, CurrentBibliography &curBib)
#define DUMP_REGISTRAR_CONTENT(pm, name, bib)
data_out
Definition: icp.py:93
PM::DataPoints DataPoints
::std::string string
Definition: gtest.h:1979
rotation
Definition: icp.py:74
data
Definition: icp.py:50
PM::DataPoints DP
PM::Inspector Inspector
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
Definition: PointMatcher.h:530
A function that transforms points and their descriptors given a transformation matrix.
Definition: PointMatcher.h:404
Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
Parametrizable::Parameters Parameters
alias
Definition: PointMatcher.h:186
void dumpRegistrar(const PM &pm, const R &registrar, const std::string &name, CurrentBibliography &bib)
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Functions and classes that are not dependant on scalar type are defined in this namespace.
ref
Definition: icp.py:49
static const PointMatcher & get()
Return instances.
Definition: Registry.cpp:145
int validateArgs(const int argc, const char *argv[], bool &isTransfoSaved, string &configFile, string &outputBaseFile, string &initTranslation, string &initRotation)
PM::TransformationParameters parseTranslation(string &translation, const int cloudDimension)
int main(int argc, const char *argv[])
void dump(std::ostream &os) const
translation
Definition: icp.py:73
PM::TransformationChecker TransformationChecker
PointMatcher< float > PM
void usage(const char *argv[])
void save(const std::string &fileName, bool binary=false) const
Save a point cloud to a file, determine format from extension.
PM::ICP ICP
static DataPoints load(const std::string &fileName)
Load a point cloud from a file, determine format from extension.
PM::Matches Matches
PM::DataPointsFilter DataPointsFilter
unsigned getEuclideanDim() const
Return the dimension of the point cloud.
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182
PM::OutlierFilter OutlierFilter
PM::TransformationParameters parseRotation(string &rotation, const int cloudDimension)
PM::Matcher Matcher
ErrorMinimizer::ErrorElements ErrorElements


libpointmatcher
Author(s):
autogenerated on Sat May 27 2023 02:38:02