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