00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "PointMatcher.h"
00037 #include "PointMatcherPrivate.h"
00038 #include "Timer.h"
00039
00040 #include "LoggerImpl.h"
00041 #include "TransformationsImpl.h"
00042 #include "DataPointsFiltersImpl.h"
00043 #include "MatchersImpl.h"
00044 #include "OutlierFiltersImpl.h"
00045 #include "ErrorMinimizersImpl.h"
00046 #include "TransformationCheckersImpl.h"
00047 #include "InspectorsImpl.h"
00048
00049 #ifdef SYSTEM_YAML_CPP
00050 #include "yaml-cpp/yaml.h"
00051 #else
00052 #include "yaml-cpp-pm/yaml.h"
00053 #endif // HAVE_YAML_CPP
00054
00055 using namespace std;
00056 using namespace PointMatcherSupport;
00057
00059 InvalidModuleType::InvalidModuleType(const std::string& reason):
00060 runtime_error(reason)
00061 {}
00062
00064 template<typename T>
00065 PointMatcher<T>::ICPChainBase::ICPChainBase():
00066 prefilteredReadingPtsCount(0),
00067 prefilteredReferencePtsCount(0)
00068 {}
00069
00071 template<typename T>
00072 PointMatcher<T>::ICPChainBase::~ICPChainBase()
00073 {
00074 }
00075
00077 template<typename T>
00078 void PointMatcher<T>::ICPChainBase::cleanup()
00079 {
00080 transformations.clear();
00081 readingDataPointsFilters.clear();
00082 readingStepDataPointsFilters.clear();
00083 referenceDataPointsFilters.clear();
00084 matcher.reset();
00085 outlierFilters.clear();
00086 errorMinimizer.reset();
00087 transformationCheckers.clear();
00088 inspector.reset();
00089 }
00090
00092 template<typename T>
00093 void PointMatcher<T>::ICPChainBase::loadAdditionalYAMLContent(YAML::Node& doc)
00094 {
00095 }
00096
00098 template<typename T>
00099 void PointMatcher<T>::ICPChainBase::setDefault()
00100 {
00101 this->cleanup();
00102
00103 this->transformations.push_back(new typename TransformationsImpl<T>::RigidTransformation());
00104 this->readingDataPointsFilters.push_back(new typename DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter());
00105 this->referenceDataPointsFilters.push_back(new typename DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter());
00106 this->outlierFilters.push_back(new typename OutlierFiltersImpl<T>::TrimmedDistOutlierFilter());
00107 this->matcher.reset(new typename MatchersImpl<T>::KDTreeMatcher());
00108 this->errorMinimizer.reset(new typename ErrorMinimizersImpl<T>::PointToPlaneErrorMinimizer());
00109 this->transformationCheckers.push_back(new typename TransformationCheckersImpl<T>::CounterTransformationChecker());
00110 this->transformationCheckers.push_back(new typename TransformationCheckersImpl<T>::DifferentialTransformationChecker());
00111 this->inspector.reset(new typename InspectorsImpl<T>::NullInspector);
00112 }
00113
00115 template<typename T>
00116 void PointMatcher<T>::ICPChainBase::loadFromYaml(std::istream& in)
00117 {
00118 this->cleanup();
00119
00120 YAML::Parser parser(in);
00121 YAML::Node doc;
00122 parser.GetNextDocument(doc);
00123
00124 typedef set<string> StringSet;
00125 StringSet usedModuleTypes;
00126
00127
00128
00129 const PointMatcher & pm = PointMatcher::get();
00130
00131 {
00132
00133 boost::mutex::scoped_lock lock(loggerMutex);
00134 usedModuleTypes.insert(createModuleFromRegistrar("logger", doc, pm.REG(Logger), logger));
00135 }
00136 usedModuleTypes.insert(createModulesFromRegistrar("readingDataPointsFilters", doc, pm.REG(DataPointsFilter), readingDataPointsFilters));
00137 usedModuleTypes.insert(createModulesFromRegistrar("readingStepDataPointsFilters", doc, pm.REG(DataPointsFilter), readingStepDataPointsFilters));
00138 usedModuleTypes.insert(createModulesFromRegistrar("referenceDataPointsFilters", doc, pm.REG(DataPointsFilter), referenceDataPointsFilters));
00139
00140 this->transformations.push_back(new typename TransformationsImpl<T>::RigidTransformation());
00141 usedModuleTypes.insert(createModuleFromRegistrar("matcher", doc, pm.REG(Matcher), matcher));
00142 usedModuleTypes.insert(createModulesFromRegistrar("outlierFilters", doc, pm.REG(OutlierFilter), outlierFilters));
00143 usedModuleTypes.insert(createModuleFromRegistrar("errorMinimizer", doc, pm.REG(ErrorMinimizer), errorMinimizer));
00144 usedModuleTypes.insert(createModulesFromRegistrar("transformationCheckers", doc, pm.REG(TransformationChecker), transformationCheckers));
00145 usedModuleTypes.insert(createModuleFromRegistrar("inspector", doc, pm.REG(Inspector),inspector));
00146
00147
00148
00149
00150
00151
00152 for(YAML::Iterator moduleTypeIt = doc.begin(); moduleTypeIt != doc.end(); ++moduleTypeIt)
00153 {
00154 string moduleType;
00155 moduleTypeIt.first() >> moduleType;
00156 if (usedModuleTypes.find(moduleType) == usedModuleTypes.end())
00157 throw InvalidModuleType(
00158 (boost::format("Module type %1% does not exist") % moduleType).str()
00159 );
00160 }
00161 }
00162
00164 template<typename T>
00165 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReadingPtsCount() const
00166 {
00167 return prefilteredReadingPtsCount;
00168 }
00169
00171 template<typename T>
00172 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReferencePtsCount() const
00173 {
00174 return prefilteredReferencePtsCount;
00175 }
00176
00178 template<typename T>
00179 template<typename R>
00180 const std::string& PointMatcher<T>::ICPChainBase::createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, PointMatcherSupport::SharedPtrVector<typename R::TargetType>& modules)
00181 {
00182 const YAML::Node *reg = doc.FindValue(regName);
00183 if (reg)
00184 {
00185
00186 for(YAML::Iterator moduleIt = reg->begin(); moduleIt != reg->end(); ++moduleIt)
00187 {
00188 const YAML::Node& module(*moduleIt);
00189 modules.push_back(registrar.createFromYAML(module));
00190 }
00191 }
00192 return regName;
00193 }
00194
00196 template<typename T>
00197 template<typename R>
00198 const std::string& PointMatcher<T>::ICPChainBase::createModuleFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, boost::shared_ptr<typename R::TargetType>& module)
00199 {
00200 const YAML::Node *reg = doc.FindValue(regName);
00201 if (reg)
00202 {
00203
00204 module.reset(registrar.createFromYAML(*reg));
00205 }
00206 else
00207 module.reset();
00208 return regName;
00209 }
00210
00211 template struct PointMatcher<float>::ICPChainBase;
00212 template struct PointMatcher<double>::ICPChainBase;
00213
00214
00216 template<typename T>
00217 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00218 const DataPoints& readingIn,
00219 const DataPoints& referenceIn)
00220 {
00221 const int dim = readingIn.features.rows();
00222 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00223 return this->compute(readingIn, referenceIn, identity);
00224 }
00225
00227 template<typename T>
00228 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00229 const DataPoints& readingIn,
00230 const DataPoints& referenceIn,
00231 const TransformationParameters& initialTransformationParameters)
00232 {
00233 return this->compute(readingIn, referenceIn, initialTransformationParameters);
00234 }
00235
00237 template<typename T>
00238 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::compute(
00239 const DataPoints& readingIn,
00240 const DataPoints& referenceIn,
00241 const TransformationParameters& T_refIn_dataIn)
00242 {
00243
00244 if (!this->matcher)
00245 throw runtime_error("You must setup a matcher before running ICP");
00246 if (!this->errorMinimizer)
00247 throw runtime_error("You must setup an error minimizer before running ICP");
00248 if (!this->inspector)
00249 throw runtime_error("You must setup an inspector before running ICP");
00250
00251 this->inspector->init();
00252
00253 timer t;
00254 const int dim(referenceIn.features.rows());
00255
00256
00257
00258 DataPoints reference(referenceIn);
00259 this->referenceDataPointsFilters.init();
00260 this->referenceDataPointsFilters.apply(reference);
00261
00262
00263
00264 const int nbPtsReference = referenceIn.features.cols();
00265 const Vector meanReference = referenceIn.features.rowwise().sum() / nbPtsReference;
00266 TransformationParameters T_refIn_refMean(Matrix::Identity(dim, dim));
00267 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanReference.head(dim-1);
00268
00269
00270
00271
00272 reference.features.topRows(dim-1).colwise() -= meanReference.head(dim-1);
00273
00274
00275 this->matcher->init(reference);
00276
00277
00278 this->inspector->addStat("ReferencePreprocessingDuration", t.elapsed());
00279 this->inspector->addStat("ReferenceInPointCount", referenceIn.features.cols());
00280 this->inspector->addStat("ReferencePointCount", reference.features.cols());
00281 LOG_INFO_STREAM("PointMatcher::icp - reference pre-processing took " << t.elapsed() << " [s]");
00282 this->prefilteredReferencePtsCount = reference.features.cols();
00283
00284 return computeWithTransformedReference(readingIn, reference, T_refIn_refMean, T_refIn_dataIn);
00285
00286 }
00287
00289 template<typename T>
00290 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::computeWithTransformedReference(
00291 const DataPoints& readingIn,
00292 const DataPoints& reference,
00293 const TransformationParameters& T_refIn_refMean,
00294 const TransformationParameters& T_refIn_dataIn)
00295 {
00296 timer t;
00297
00298
00299
00300 DataPoints reading(readingIn);
00301
00302 this->readingDataPointsFilters.init();
00303 this->readingDataPointsFilters.apply(reading);
00304 readingFiltered = reading;
00305
00306
00307
00308 TransformationParameters
00309 T_refMean_dataIn = T_refIn_refMean.inverse() * T_refIn_dataIn;
00310 this->transformations.apply(reading, T_refMean_dataIn);
00311
00312
00313 this->readingStepDataPointsFilters.init();
00314
00315
00316
00317 const int dim(reference.features.rows());
00318 TransformationParameters T_iter = Matrix::Identity(dim, dim);
00319
00320 bool iterate(true);
00321 this->transformationCheckers.init(T_iter, iterate);
00322
00323 size_t iterationCount(0);
00324
00325
00326 this->inspector->addStat("ReadingPreprocessingDuration", t.elapsed());
00327 this->inspector->addStat("ReadingInPointCount", readingIn.features.cols());
00328 this->inspector->addStat("ReadingPointCount", reading.features.cols());
00329 LOG_INFO_STREAM("PointMatcher::icp - reading pre-processing took " << t.elapsed() << " [s]");
00330 this->prefilteredReadingPtsCount = reading.features.cols();
00331 t.restart();
00332
00333
00334 while (iterate)
00335 {
00336 DataPoints stepReading(reading);
00337
00338
00339
00340 this->readingStepDataPointsFilters.apply(stepReading);
00341
00342
00343
00344 this->transformations.apply(stepReading, T_iter);
00345
00346
00347
00348 const Matches matches(
00349 this->matcher->findClosests(stepReading)
00350 );
00351
00352
00353
00354 const OutlierWeights outlierWeights(
00355 this->outlierFilters.compute(stepReading, reference, matches)
00356 );
00357
00358 assert(outlierWeights.rows() == matches.ids.rows());
00359 assert(outlierWeights.cols() == matches.ids.cols());
00360
00361
00362
00363
00364
00365
00366 this->inspector->dumpIteration(
00367 iterationCount, T_iter, reference, stepReading, matches, outlierWeights, this->transformationCheckers
00368 );
00369
00370
00371
00372
00373
00374 T_iter = this->errorMinimizer->compute(
00375 stepReading, reference, outlierWeights, matches) * T_iter;
00376
00377
00378
00379
00380
00381
00382
00383 this->transformationCheckers.check(T_iter, iterate);
00384
00385 ++iterationCount;
00386 }
00387
00388 this->inspector->addStat("IterationsCount", iterationCount);
00389 this->inspector->addStat("PointCountTouched", this->matcher->getVisitCount());
00390 this->matcher->resetVisitCount();
00391 this->inspector->addStat("OverlapRatio", this->errorMinimizer->getWeightedPointUsedRatio());
00392 this->inspector->addStat("ConvergenceDuration", t.elapsed());
00393 this->inspector->finish(iterationCount);
00394
00395 LOG_INFO_STREAM("PointMatcher::icp - " << iterationCount << " iterations took " << t.elapsed() << " [s]");
00396
00397
00398
00399
00400
00401
00402
00403
00404 return (T_refIn_refMean * T_iter * T_refMean_dataIn);
00405 }
00406
00407 template struct PointMatcher<float>::ICP;
00408 template struct PointMatcher<double>::ICP;
00409
00410
00412 template<typename T>
00413 bool PointMatcher<T>::ICPSequence::hasMap() const
00414 {
00415 return (mapPointCloud.features.cols() != 0);
00416 }
00417
00419 template<typename T>
00420 bool PointMatcher<T>::ICPSequence::setMap(const DataPoints& inputCloud)
00421 {
00422
00423 if (!this->matcher)
00424 throw runtime_error("You must setup a matcher before running ICP");
00425 if (!this->inspector)
00426 throw runtime_error("You must setup an inspector before running ICP");
00427
00428 timer t;
00429 const int dim(inputCloud.features.rows());
00430 const int ptCount(inputCloud.features.cols());
00431
00432
00433 if (ptCount == 0)
00434 {
00435 LOG_WARNING_STREAM("Ignoring attempt to create a map from an empty cloud");
00436 return false;
00437 }
00438
00439 this->inspector->addStat("MapPointCount", inputCloud.features.cols());
00440
00441
00442 mapPointCloud = inputCloud;
00443
00444
00445
00446 const Vector meanMap = mapPointCloud.features.rowwise().sum() / ptCount;
00447 T_refIn_refMean = Matrix::Identity(dim, dim);
00448 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanMap.head(dim-1);
00449
00450
00451
00452
00453 mapPointCloud.features.topRows(dim-1).colwise() -= meanMap.head(dim-1);
00454
00455 this->matcher->init(mapPointCloud);
00456
00457 this->inspector->addStat("SetMapDuration", t.elapsed());
00458
00459 return true;
00460 }
00461
00463 template<typename T>
00464 void PointMatcher<T>::ICPSequence::clearMap()
00465 {
00466 const int dim(mapPointCloud.features.rows());
00467 T_refIn_refMean = Matrix::Identity(dim, dim);
00468 mapPointCloud = DataPoints();
00469 }
00470
00472 template<typename T>
00473 const typename PointMatcher<T>::DataPoints PointMatcher<T>::ICPSequence::getMap() const
00474 {
00475 DataPoints globalMap(mapPointCloud);
00476 if(this->hasMap())
00477 {
00478 const int dim(mapPointCloud.features.rows());
00479 const Vector meanMapNonHomo(T_refIn_refMean.block(0,dim-1, dim-1, 1));
00480 globalMap.features.topRows(dim-1).colwise() += meanMapNonHomo;
00481 }
00482
00483 return globalMap;
00484 }
00485
00487 template<typename T>
00488 const typename PointMatcher<T>::DataPoints& PointMatcher<T>::ICPSequence::getInternalMap() const
00489 {
00490 return mapPointCloud;
00491 }
00492
00494 template<typename T>
00495 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00496 const DataPoints& cloudIn)
00497 {
00498 const int dim = cloudIn.features.rows();
00499 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00500 return this->compute(cloudIn, identity);
00501 }
00502
00504 template<typename T>
00505 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00506 const DataPoints& cloudIn, const TransformationParameters& T_dataInOld_dataInNew)
00507 {
00508 return this->compute(cloudIn, T_dataInOld_dataInNew);
00509 }
00510
00512 template<typename T>
00513 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::compute(
00514 const DataPoints& cloudIn, const TransformationParameters& T_refIn_dataIn)
00515 {
00516
00517 if (!hasMap())
00518 {
00519 const int dim(cloudIn.features.rows());
00520 LOG_WARNING_STREAM("Ignoring attempt to perform ICP with an empty map");
00521 return Matrix::Identity(dim, dim);
00522 }
00523
00524 this->inspector->init();
00525
00526
00527
00528 DataPoints reference(mapPointCloud);
00529 this->referenceDataPointsFilters.init();
00530 this->referenceDataPointsFilters.apply(reference);
00531
00532 this->matcher->init(reference);
00533
00534 return this->computeWithTransformedReference(cloudIn, reference, T_refIn_refMean, T_refIn_dataIn);
00535 }
00536
00537 template struct PointMatcher<float>::ICPSequence;
00538 template struct PointMatcher<double>::ICPSequence;