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 using namespace std;
00050 using namespace PointMatcherSupport;
00051
00053 InvalidModuleType::InvalidModuleType(const std::string& reason):
00054 runtime_error(reason)
00055 {}
00056
00058 template<typename T>
00059 PointMatcher<T>::ICPChainBase::ICPChainBase():
00060 prefilteredReadingPtsCount(0),
00061 prefilteredReferencePtsCount(0)
00062 {}
00063
00065 template<typename T>
00066 PointMatcher<T>::ICPChainBase::~ICPChainBase()
00067 {
00068 }
00069
00071 template<typename T>
00072 void PointMatcher<T>::ICPChainBase::cleanup()
00073 {
00074 transformations.clear();
00075 readingDataPointsFilters.clear();
00076 readingStepDataPointsFilters.clear();
00077 referenceDataPointsFilters.clear();
00078 matcher.reset();
00079 outlierFilters.clear();
00080 errorMinimizer.reset();
00081 transformationCheckers.clear();
00082 inspector.reset();
00083 }
00084
00085 #ifdef HAVE_YAML_CPP
00086
00088 template<typename T>
00089 void PointMatcher<T>::ICPChainBase::loadAdditionalYAMLContent(YAML::Node& doc)
00090 {
00091 }
00092
00093 #endif // HAVE_YAML_CPP
00094
00096 template<typename T>
00097 void PointMatcher<T>::ICPChainBase::setDefault()
00098 {
00099 this->cleanup();
00100
00101 this->transformations.push_back(new typename TransformationsImpl<T>::RigidTransformation());
00102 this->readingDataPointsFilters.push_back(new typename DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter());
00103 this->referenceDataPointsFilters.push_back(new typename DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter());
00104 this->outlierFilters.push_back(new typename OutlierFiltersImpl<T>::TrimmedDistOutlierFilter());
00105 this->matcher.reset(new typename MatchersImpl<T>::KDTreeMatcher());
00106 this->errorMinimizer.reset(new typename ErrorMinimizersImpl<T>::PointToPlaneErrorMinimizer());
00107 this->transformationCheckers.push_back(new typename TransformationCheckersImpl<T>::CounterTransformationChecker());
00108 this->transformationCheckers.push_back(new typename TransformationCheckersImpl<T>::DifferentialTransformationChecker());
00109 this->inspector.reset(new typename InspectorsImpl<T>::NullInspector);
00110 }
00111
00113 template<typename T>
00114 void PointMatcher<T>::ICPChainBase::loadFromYaml(std::istream& in)
00115 {
00116 #ifdef HAVE_YAML_CPP
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 #else // HAVE_YAML_CPP
00163 throw runtime_error("Yaml support not compiled in. Install yaml-cpp, configure build and recompile.");
00164 #endif // HAVE_YAML_CPP
00165 }
00166
00168 template<typename T>
00169 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReadingPtsCount() const
00170 {
00171 return prefilteredReadingPtsCount;
00172 }
00173
00175 template<typename T>
00176 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReferencePtsCount() const
00177 {
00178 return prefilteredReferencePtsCount;
00179 }
00180
00181 #ifdef HAVE_YAML_CPP
00182
00184 template<typename T>
00185 template<typename R>
00186 const std::string& PointMatcher<T>::ICPChainBase::createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, PointMatcherSupport::SharedPtrVector<typename R::TargetType>& modules)
00187 {
00188 const YAML::Node *reg = doc.FindValue(regName);
00189 if (reg)
00190 {
00191
00192 for(YAML::Iterator moduleIt = reg->begin(); moduleIt != reg->end(); ++moduleIt)
00193 {
00194 const YAML::Node& module(*moduleIt);
00195 modules.push_back(registrar.createFromYAML(module));
00196 }
00197 }
00198 return regName;
00199 }
00200
00202 template<typename T>
00203 template<typename R>
00204 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)
00205 {
00206 const YAML::Node *reg = doc.FindValue(regName);
00207 if (reg)
00208 {
00209
00210 module.reset(registrar.createFromYAML(*reg));
00211 }
00212 else
00213 module.reset();
00214 return regName;
00215 }
00216
00217 #endif // HAVE_YAML_CPP
00218
00219 template struct PointMatcher<float>::ICPChainBase;
00220 template struct PointMatcher<double>::ICPChainBase;
00221
00222
00224 template<typename T>
00225 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00226 const DataPoints& readingIn,
00227 const DataPoints& referenceIn)
00228 {
00229 const int dim = readingIn.features.rows();
00230 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00231 return this->compute(readingIn, referenceIn, identity);
00232 }
00233
00235 template<typename T>
00236 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00237 const DataPoints& readingIn,
00238 const DataPoints& referenceIn,
00239 const TransformationParameters& initialTransformationParameters)
00240 {
00241 return this->compute(readingIn, referenceIn, initialTransformationParameters);
00242 }
00243
00245 template<typename T>
00246 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::compute(
00247 const DataPoints& readingIn,
00248 const DataPoints& referenceIn,
00249 const TransformationParameters& T_refIn_dataIn)
00250 {
00251
00252 if (!this->matcher)
00253 throw runtime_error("You must setup a matcher before running ICP");
00254 if (!this->errorMinimizer)
00255 throw runtime_error("You must setup an error minimizer before running ICP");
00256 if (!this->inspector)
00257 throw runtime_error("You must setup an inspector before running ICP");
00258
00259 this->inspector->init();
00260
00261 timer t;
00262 const int dim(referenceIn.features.rows());
00263
00264
00265
00266 DataPoints reference(referenceIn);
00267 this->referenceDataPointsFilters.init();
00268 this->referenceDataPointsFilters.apply(reference);
00269
00270
00271
00272 const int nbPtsReference = referenceIn.features.cols();
00273 const Vector meanReference = referenceIn.features.rowwise().sum() / nbPtsReference;
00274 TransformationParameters T_refIn_refMean(Matrix::Identity(dim, dim));
00275 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanReference.head(dim-1);
00276
00277
00278
00279
00280 reference.features.topRows(dim-1).colwise() -= meanReference.head(dim-1);
00281
00282
00283 this->matcher->init(reference);
00284
00285
00286 this->inspector->addStat("ReferencePreprocessingDuration", t.elapsed());
00287 this->inspector->addStat("ReferenceInPointCount", referenceIn.features.cols());
00288 this->inspector->addStat("ReferencePointCount", reference.features.cols());
00289 LOG_INFO_STREAM("PointMatcher::icp - reference pre-processing took " << t.elapsed() << " [s]");
00290 this->prefilteredReferencePtsCount = reference.features.cols();
00291
00292 return computeWithTransformedReference(readingIn, reference, T_refIn_refMean, T_refIn_dataIn);
00293
00294 }
00295
00297 template<typename T>
00298 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::computeWithTransformedReference(
00299 const DataPoints& readingIn,
00300 const DataPoints& reference,
00301 const TransformationParameters& T_refIn_refMean,
00302 const TransformationParameters& T_refIn_dataIn)
00303 {
00304 timer t;
00305
00306
00307
00308 DataPoints reading(readingIn);
00309
00310 this->readingDataPointsFilters.init();
00311 this->readingDataPointsFilters.apply(reading);
00312
00313
00314
00315 TransformationParameters
00316 T_refMean_dataIn = T_refIn_refMean.inverse() * T_refIn_dataIn;
00317 this->transformations.apply(reading, T_refMean_dataIn);
00318
00319
00320 this->readingStepDataPointsFilters.init();
00321
00322
00323
00324 const int dim(reference.features.rows());
00325 TransformationParameters T_iter = Matrix::Identity(dim, dim);
00326
00327 bool iterate(true);
00328 this->transformationCheckers.init(T_iter, iterate);
00329
00330 size_t iterationCount(0);
00331
00332
00333 this->inspector->addStat("ReadingPreprocessingDuration", t.elapsed());
00334 this->inspector->addStat("ReadingInPointCount", readingIn.features.cols());
00335 this->inspector->addStat("ReadingPointCount", reading.features.cols());
00336 LOG_INFO_STREAM("PointMatcher::icp - reading pre-processing took " << t.elapsed() << " [s]");
00337 this->prefilteredReadingPtsCount = reading.features.cols();
00338 t.restart();
00339
00340
00341 while (iterate)
00342 {
00343 DataPoints stepReading(reading);
00344
00345
00346
00347 this->readingStepDataPointsFilters.apply(stepReading);
00348
00349
00350
00351 this->transformations.apply(stepReading, T_iter);
00352
00353
00354
00355 const Matches matches(
00356 this->matcher->findClosests(stepReading)
00357 );
00358
00359
00360
00361 const OutlierWeights outlierWeights(
00362 this->outlierFilters.compute(stepReading, reference, matches)
00363 );
00364
00365 assert(outlierWeights.rows() == matches.ids.rows());
00366 assert(outlierWeights.cols() == matches.ids.cols());
00367
00368
00369
00370
00371
00372
00373 this->inspector->dumpIteration(
00374 iterationCount, T_iter, reference, stepReading, matches, outlierWeights, this->transformationCheckers
00375 );
00376
00377
00378
00379
00380
00381 T_iter = this->errorMinimizer->compute(
00382 stepReading, reference, outlierWeights, matches) * T_iter;
00383
00384
00385
00386
00387
00388
00389
00390 this->transformationCheckers.check(T_iter, iterate);
00391
00392 ++iterationCount;
00393 }
00394
00395 this->inspector->addStat("IterationsCount", iterationCount);
00396 this->inspector->addStat("PointCountTouched", this->matcher->getVisitCount());
00397 this->matcher->resetVisitCount();
00398 this->inspector->addStat("OverlapRatio", this->errorMinimizer->getWeightedPointUsedRatio());
00399 this->inspector->addStat("ConvergenceDuration", t.elapsed());
00400 this->inspector->finish(iterationCount);
00401
00402 LOG_INFO_STREAM("PointMatcher::icp - " << iterationCount << " iterations took " << t.elapsed() << " [s]");
00403
00404
00405
00406
00407
00408
00409
00410
00411 return (T_refIn_refMean * T_iter * T_refMean_dataIn);
00412 }
00413
00414 template struct PointMatcher<float>::ICP;
00415 template struct PointMatcher<double>::ICP;
00416
00417
00419 template<typename T>
00420 bool PointMatcher<T>::ICPSequence::hasMap() const
00421 {
00422 return (mapPointCloud.features.cols() != 0);
00423 }
00424
00426 template<typename T>
00427 bool PointMatcher<T>::ICPSequence::setMap(const DataPoints& inputCloud)
00428 {
00429
00430 if (!this->matcher)
00431 throw runtime_error("You must setup a matcher before running ICP");
00432 if (!this->inspector)
00433 throw runtime_error("You must setup an inspector before running ICP");
00434
00435 timer t;
00436 const int dim(inputCloud.features.rows());
00437 const int ptCount(inputCloud.features.cols());
00438
00439
00440 if (ptCount == 0)
00441 {
00442 LOG_WARNING_STREAM("Ignoring attempt to create a map from an empty cloud");
00443 return false;
00444 }
00445
00446 this->inspector->addStat("MapPointCount", inputCloud.features.cols());
00447
00448
00449 mapPointCloud = inputCloud;
00450
00451
00452
00453 const Vector meanMap = mapPointCloud.features.rowwise().sum() / ptCount;
00454 T_refIn_refMean = Matrix::Identity(dim, dim);
00455 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanMap.head(dim-1);
00456
00457
00458
00459
00460 mapPointCloud.features.topRows(dim-1).colwise() -= meanMap.head(dim-1);
00461
00462 this->matcher->init(mapPointCloud);
00463
00464 this->inspector->addStat("SetMapDuration", t.elapsed());
00465
00466 return true;
00467 }
00468
00470 template<typename T>
00471 void PointMatcher<T>::ICPSequence::clearMap()
00472 {
00473 const int dim(mapPointCloud.features.rows());
00474 T_refIn_refMean = Matrix::Identity(dim, dim);
00475 mapPointCloud = DataPoints();
00476 }
00477
00479 template<typename T>
00480 const typename PointMatcher<T>::DataPoints PointMatcher<T>::ICPSequence::getMap() const
00481 {
00482 DataPoints globalMap(mapPointCloud);
00483 const int dim(mapPointCloud.features.rows());
00484 const Vector meanMapNonHomo(T_refIn_refMean.block(0,dim-1, dim-1, 1));
00485 globalMap.features.topRows(dim-1).colwise() += meanMapNonHomo;
00486 return globalMap;
00487 }
00488
00490 template<typename T>
00491 const typename PointMatcher<T>::DataPoints& PointMatcher<T>::ICPSequence::getInternalMap() const
00492 {
00493 return mapPointCloud;
00494 }
00495
00497 template<typename T>
00498 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00499 const DataPoints& cloudIn)
00500 {
00501 const int dim = cloudIn.features.rows();
00502 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00503 return this->compute(cloudIn, identity);
00504 }
00505
00507 template<typename T>
00508 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00509 const DataPoints& cloudIn, const TransformationParameters& T_dataInOld_dataInNew)
00510 {
00511 return this->compute(cloudIn, T_dataInOld_dataInNew);
00512 }
00513
00515 template<typename T>
00516 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::compute(
00517 const DataPoints& cloudIn, const TransformationParameters& T_refIn_dataIn)
00518 {
00519
00520 if (!hasMap())
00521 {
00522 const int dim(cloudIn.features.rows());
00523 LOG_WARNING_STREAM("Ignoring attempt to perform ICP with an empty map");
00524 return Matrix::Identity(dim, dim);
00525 }
00526
00527 this->inspector->init();
00528
00529 return this->computeWithTransformedReference(cloudIn, mapPointCloud, T_refIn_refMean, T_refIn_dataIn);
00530 }
00531
00532 template struct PointMatcher<float>::ICPSequence;
00533 template struct PointMatcher<double>::ICPSequence;