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


libpointmatcher
Author(s):
autogenerated on Sun Dec 22 2024 03:21:53