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 maxNumIterationsReached(false)
00069 {}
00070
00072 template<typename T>
00073 PointMatcher<T>::ICPChainBase::~ICPChainBase()
00074 {
00075 }
00076
00078 template<typename T>
00079 void PointMatcher<T>::ICPChainBase::cleanup()
00080 {
00081 transformations.clear();
00082 readingDataPointsFilters.clear();
00083 readingStepDataPointsFilters.clear();
00084 referenceDataPointsFilters.clear();
00085 matcher.reset();
00086 outlierFilters.clear();
00087 errorMinimizer.reset();
00088 transformationCheckers.clear();
00089 inspector.reset();
00090 }
00091
00093 template<typename T>
00094 void PointMatcher<T>::ICPChainBase::loadAdditionalYAMLContent(YAML::Node& doc)
00095 {
00096 }
00097
00099 template<typename T>
00100 void PointMatcher<T>::ICPChainBase::setDefault()
00101 {
00102 this->cleanup();
00103
00104 this->transformations.push_back(std::make_shared<typename TransformationsImpl<T>::RigidTransformation>());
00105 this->readingDataPointsFilters.push_back(std::make_shared<typename DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter>());
00106 this->referenceDataPointsFilters.push_back(std::make_shared<typename DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter>());
00107 this->outlierFilters.push_back(std::make_shared<typename OutlierFiltersImpl<T>::TrimmedDistOutlierFilter>());
00108 this->matcher = std::make_shared<typename MatchersImpl<T>::KDTreeMatcher>();
00109 this->errorMinimizer = std::make_shared<PointToPlaneErrorMinimizer<T> >();
00110 this->transformationCheckers.push_back(std::make_shared<typename TransformationCheckersImpl<T>::CounterTransformationChecker>());
00111 this->transformationCheckers.push_back(std::make_shared<typename TransformationCheckersImpl<T>::DifferentialTransformationChecker>());
00112 this->inspector = std::make_shared<typename InspectorsImpl<T>::NullInspector>();
00113 }
00114
00116 template<typename T>
00117 void PointMatcher<T>::ICPChainBase::loadFromYaml(std::istream& in)
00118 {
00119 this->cleanup();
00120
00121 YAML::Parser parser(in);
00122 YAML::Node doc;
00123 parser.GetNextDocument(doc);
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 usedModuleTypes.insert(createModuleFromRegistrar("matcher", doc, pm.REG(Matcher), matcher));
00141 usedModuleTypes.insert(createModulesFromRegistrar("outlierFilters", doc, pm.REG(OutlierFilter), outlierFilters));
00142 usedModuleTypes.insert(createModuleFromRegistrar("errorMinimizer", doc, pm.REG(ErrorMinimizer), errorMinimizer));
00143
00144
00145 if (nodeVal("errorMinimizer", doc) != "PointToPointSimilarityErrorMinimizer")
00146 this->transformations.push_back(std::make_shared<typename TransformationsImpl<T>::RigidTransformation>());
00147 else
00148 this->transformations.push_back(std::make_shared<typename TransformationsImpl<T>::SimilarityTransformation>());
00149
00150 usedModuleTypes.insert(createModulesFromRegistrar("transformationCheckers", doc, pm.REG(TransformationChecker), transformationCheckers));
00151 usedModuleTypes.insert(createModuleFromRegistrar("inspector", doc, pm.REG(Inspector),inspector));
00152
00153
00154
00155
00156
00157
00158 for(YAML::Iterator moduleTypeIt = doc.begin(); moduleTypeIt != doc.end(); ++moduleTypeIt)
00159 {
00160 string moduleType;
00161 moduleTypeIt.first() >> moduleType;
00162 if (usedModuleTypes.find(moduleType) == usedModuleTypes.end())
00163 throw InvalidModuleType(
00164 (boost::format("Module type %1% does not exist") % moduleType).str()
00165 );
00166 }
00167 }
00168
00170 template<typename T>
00171 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReadingPtsCount() const
00172 {
00173 return prefilteredReadingPtsCount;
00174 }
00175
00177 template<typename T>
00178 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReferencePtsCount() const
00179 {
00180 return prefilteredReferencePtsCount;
00181 }
00182
00184 template<typename T>
00185 bool PointMatcher<T>::ICPChainBase::getMaxNumIterationsReached() const
00186 {
00187 return maxNumIterationsReached;
00188 }
00189
00191 template<typename T>
00192 template<typename R>
00193 const std::string& PointMatcher<T>::ICPChainBase::createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, std::vector<std::shared_ptr<typename R::TargetType> >& modules)
00194 {
00195 const YAML::Node *reg = doc.FindValue(regName);
00196 if (reg)
00197 {
00198
00199 for(YAML::Iterator moduleIt = reg->begin(); moduleIt != reg->end(); ++moduleIt)
00200 {
00201 const YAML::Node& module(*moduleIt);
00202 modules.push_back(registrar.createFromYAML(module));
00203 }
00204 }
00205 return regName;
00206 }
00207
00209 template<typename T>
00210 template<typename R>
00211 const std::string& PointMatcher<T>::ICPChainBase::createModuleFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, std::shared_ptr<typename R::TargetType>& module)
00212 {
00213 const YAML::Node *reg = doc.FindValue(regName);
00214 if (reg)
00215 {
00216
00217 module = registrar.createFromYAML(*reg);
00218 }
00219 else
00220 module.reset();
00221 return regName;
00222 }
00223
00224 template<typename T>
00225 std::string PointMatcher<T>::ICPChainBase::nodeVal(const std::string& regName, const PointMatcherSupport::YAML::Node& doc)
00226 {
00227 const YAML::Node *reg = doc.FindValue(regName);
00228 if (reg)
00229 {
00230 std::string name;
00231 Parametrizable::Parameters params;
00232 PointMatcherSupport::getNameParamsFromYAML(*reg, name, params);
00233 return name;
00234 }
00235 return "";
00236 }
00237
00238 template struct PointMatcher<float>::ICPChainBase;
00239 template struct PointMatcher<double>::ICPChainBase;
00240
00241
00243 template<typename T>
00244 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00245 const DataPoints& readingIn,
00246 const DataPoints& referenceIn)
00247 {
00248 const int dim = readingIn.features.rows();
00249 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00250 return this->compute(readingIn, referenceIn, identity);
00251 }
00252
00254 template<typename T>
00255 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00256 const DataPoints& readingIn,
00257 const DataPoints& referenceIn,
00258 const TransformationParameters& initialTransformationParameters)
00259 {
00260 return this->compute(readingIn, referenceIn, initialTransformationParameters);
00261 }
00262
00264 template<typename T>
00265 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::compute(
00266 const DataPoints& readingIn,
00267 const DataPoints& referenceIn,
00268 const TransformationParameters& T_refIn_dataIn)
00269 {
00270
00271 if (!this->matcher)
00272 throw runtime_error("You must setup a matcher before running ICP");
00273 if (!this->errorMinimizer)
00274 throw runtime_error("You must setup an error minimizer before running ICP");
00275 if (!this->inspector)
00276 throw runtime_error("You must setup an inspector before running ICP");
00277
00278 this->inspector->init();
00279
00280 timer t;
00281 const int dim(referenceIn.features.rows());
00282
00283
00284
00285 DataPoints reference(referenceIn);
00286 this->referenceDataPointsFilters.init();
00287 this->referenceDataPointsFilters.apply(reference);
00288
00289
00290
00291 const int nbPtsReference = reference.features.cols();
00292 const Vector meanReference = reference.features.rowwise().sum() / nbPtsReference;
00293 TransformationParameters T_refIn_refMean(Matrix::Identity(dim, dim));
00294 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanReference.head(dim-1);
00295
00296
00297
00298
00299 reference.features.topRows(dim-1).colwise() -= meanReference.head(dim-1);
00300
00301
00302 this->matcher->init(reference);
00303
00304
00305 this->inspector->addStat("ReferencePreprocessingDuration", t.elapsed());
00306 this->inspector->addStat("ReferenceInPointCount", referenceIn.features.cols());
00307 this->inspector->addStat("ReferencePointCount", reference.features.cols());
00308 LOG_INFO_STREAM("PointMatcher::icp - reference pre-processing took " << t.elapsed() << " [s]");
00309 this->prefilteredReferencePtsCount = reference.features.cols();
00310
00311 return computeWithTransformedReference(readingIn, reference, T_refIn_refMean, T_refIn_dataIn);
00312
00313 }
00314
00316 template<typename T>
00317 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::computeWithTransformedReference(
00318 const DataPoints& readingIn,
00319 const DataPoints& reference,
00320 const TransformationParameters& T_refIn_refMean,
00321 const TransformationParameters& T_refIn_dataIn)
00322 {
00323 const int dim(reference.features.rows());
00324
00325 if (T_refIn_dataIn.cols() != T_refIn_dataIn.rows()) {
00326 throw runtime_error("The initial transformation matrix must be squared.");
00327 }
00328 if (dim != T_refIn_dataIn.cols()) {
00329 throw runtime_error("The shape of initial transformation matrix must be NxN. "
00330 "Where N is the number of rows in the read/reference scans.");
00331 }
00332
00333 timer t;
00334
00335
00336
00337 DataPoints reading(readingIn);
00338
00339 this->readingDataPointsFilters.init();
00340 this->readingDataPointsFilters.apply(reading);
00341 readingFiltered = reading;
00342
00343
00344
00345 TransformationParameters
00346 T_refMean_dataIn = T_refIn_refMean.inverse() * T_refIn_dataIn;
00347 this->transformations.apply(reading, T_refMean_dataIn);
00348
00349
00350 this->readingStepDataPointsFilters.init();
00351
00352
00353
00354 TransformationParameters T_iter = Matrix::Identity(dim, dim);
00355
00356 bool iterate(true);
00357 this->maxNumIterationsReached = false;
00358 this->transformationCheckers.init(T_iter, iterate);
00359
00360 size_t iterationCount(0);
00361
00362
00363 this->inspector->addStat("ReadingPreprocessingDuration", t.elapsed());
00364 this->inspector->addStat("ReadingInPointCount", readingIn.features.cols());
00365 this->inspector->addStat("ReadingPointCount", reading.features.cols());
00366 LOG_INFO_STREAM("PointMatcher::icp - reading pre-processing took " << t.elapsed() << " [s]");
00367 this->prefilteredReadingPtsCount = reading.features.cols();
00368 t.restart();
00369
00370
00371 while (iterate)
00372 {
00373 DataPoints stepReading(reading);
00374
00375
00376
00377 this->readingStepDataPointsFilters.apply(stepReading);
00378
00379
00380
00381 this->transformations.apply(stepReading, T_iter);
00382
00383
00384
00385 const Matches matches(
00386 this->matcher->findClosests(stepReading)
00387 );
00388
00389
00390
00391 const OutlierWeights outlierWeights(
00392 this->outlierFilters.compute(stepReading, reference, matches)
00393 );
00394
00395 assert(outlierWeights.rows() == matches.ids.rows());
00396 assert(outlierWeights.cols() == matches.ids.cols());
00397
00398
00399
00400
00401
00402
00403 this->inspector->dumpIteration(
00404 iterationCount, T_iter, reference, stepReading, matches, outlierWeights, this->transformationCheckers
00405 );
00406
00407
00408
00409
00410
00411 T_iter = this->errorMinimizer->compute(
00412 stepReading, reference, outlierWeights, matches) * T_iter;
00413
00414
00415
00416
00417
00418
00419 try
00420 {
00421 this->transformationCheckers.check(T_iter, iterate);
00422 }
00423 catch(const typename TransformationCheckersImpl<T>::CounterTransformationChecker::MaxNumIterationsReached & e)
00424 {
00425 iterate = false;
00426 this->maxNumIterationsReached = true;
00427 }
00428
00429 ++iterationCount;
00430 }
00431
00432 this->inspector->addStat("IterationsCount", iterationCount);
00433 this->inspector->addStat("PointCountTouched", this->matcher->getVisitCount());
00434 this->matcher->resetVisitCount();
00435 this->inspector->addStat("OverlapRatio", this->errorMinimizer->getWeightedPointUsedRatio());
00436 this->inspector->addStat("ConvergenceDuration", t.elapsed());
00437 this->inspector->finish(iterationCount);
00438
00439 LOG_INFO_STREAM("PointMatcher::icp - " << iterationCount << " iterations took " << t.elapsed() << " [s]");
00440
00441
00442
00443
00444
00445
00446
00447
00448 return (T_refIn_refMean * T_iter * T_refMean_dataIn);
00449 }
00450
00451 template struct PointMatcher<float>::ICP;
00452 template struct PointMatcher<double>::ICP;
00453
00454
00456 template<typename T>
00457 bool PointMatcher<T>::ICPSequence::hasMap() const
00458 {
00459 return (mapPointCloud.features.cols() != 0);
00460 }
00461
00463 template<typename T>
00464 bool PointMatcher<T>::ICPSequence::setMap(const DataPoints& inputCloud)
00465 {
00466
00467 if (!this->matcher)
00468 throw runtime_error("You must setup a matcher before running ICP");
00469 if (!this->inspector)
00470 throw runtime_error("You must setup an inspector before running ICP");
00471
00472 timer t;
00473 const int dim(inputCloud.features.rows());
00474 const int ptCount(inputCloud.features.cols());
00475
00476
00477 if (ptCount == 0)
00478 {
00479 LOG_WARNING_STREAM("Ignoring attempt to create a map from an empty cloud");
00480 return false;
00481 }
00482
00483 this->inspector->addStat("MapPointCount", inputCloud.features.cols());
00484
00485
00486 mapPointCloud = inputCloud;
00487
00488
00489
00490 const Vector meanMap = mapPointCloud.features.rowwise().sum() / ptCount;
00491 T_refIn_refMean = Matrix::Identity(dim, dim);
00492 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanMap.head(dim-1);
00493
00494
00495
00496
00497 mapPointCloud.features.topRows(dim-1).colwise() -= meanMap.head(dim-1);
00498
00499
00500 this->referenceDataPointsFilters.init();
00501 this->referenceDataPointsFilters.apply(mapPointCloud);
00502
00503 this->matcher->init(mapPointCloud);
00504
00505 this->inspector->addStat("SetMapDuration", t.elapsed());
00506
00507 return true;
00508 }
00509
00511 template<typename T>
00512 void PointMatcher<T>::ICPSequence::clearMap()
00513 {
00514 const int dim(mapPointCloud.features.rows());
00515 T_refIn_refMean = Matrix::Identity(dim, dim);
00516 mapPointCloud = DataPoints();
00517 }
00518
00520 template<typename T>
00521 const typename PointMatcher<T>::DataPoints PointMatcher<T>::ICPSequence::getPrefilteredMap() const
00522 {
00523 DataPoints globalMap(mapPointCloud);
00524 if(this->hasMap())
00525 {
00526 const int dim(mapPointCloud.features.rows());
00527 const Vector meanMapNonHomo(T_refIn_refMean.block(0,dim-1, dim-1, 1));
00528 globalMap.features.topRows(dim-1).colwise() += meanMapNonHomo;
00529 }
00530
00531 return globalMap;
00532 }
00533
00535 template<typename T>
00536 const typename PointMatcher<T>::DataPoints PointMatcher<T>::ICPSequence::getMap() const {
00537 return PointMatcher<T>::ICPSequence::getPrefilteredMap();
00538 }
00539
00541 template<typename T>
00542 const typename PointMatcher<T>::DataPoints& PointMatcher<T>::ICPSequence::getPrefilteredInternalMap() const
00543 {
00544 return mapPointCloud;
00545 }
00546
00548 template<typename T>
00549 const typename PointMatcher<T>::DataPoints& PointMatcher<T>::ICPSequence::getInternalMap() const {
00550 return PointMatcher<T>::ICPSequence::getPrefilteredInternalMap();
00551 }
00552
00554 template<typename T>
00555 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00556 const DataPoints& cloudIn)
00557 {
00558 const int dim = cloudIn.features.rows();
00559 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00560 return this->compute(cloudIn, identity);
00561 }
00562
00564 template<typename T>
00565 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00566 const DataPoints& cloudIn, const TransformationParameters& T_dataInOld_dataInNew)
00567 {
00568 return this->compute(cloudIn, T_dataInOld_dataInNew);
00569 }
00570
00572 template<typename T>
00573 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::compute(
00574 const DataPoints& cloudIn, const TransformationParameters& T_refIn_dataIn)
00575 {
00576
00577 if (!hasMap())
00578 {
00579 const int dim(cloudIn.features.rows());
00580 LOG_WARNING_STREAM("Ignoring attempt to perform ICP with an empty map");
00581 return Matrix::Identity(dim, dim);
00582 }
00583
00584 this->inspector->init();
00585
00586 return this->computeWithTransformedReference(cloudIn, mapPointCloud, T_refIn_refMean, T_refIn_dataIn);
00587 }
00588
00589 template struct PointMatcher<float>::ICPSequence;
00590 template struct PointMatcher<double>::ICPSequence;