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 loadAdditionalYAMLContent(doc);
00149
00150
00151 for(YAML::Iterator moduleTypeIt = doc.begin(); moduleTypeIt != doc.end(); ++moduleTypeIt)
00152 {
00153 string moduleType;
00154 moduleTypeIt.first() >> moduleType;
00155 if (usedModuleTypes.find(moduleType) == usedModuleTypes.end())
00156 throw InvalidModuleType(
00157 (boost::format("Module type %1% does not exist") % moduleType).str()
00158 );
00159 }
00160
00161 #else // HAVE_YAML_CPP
00162 throw runtime_error("Yaml support not compiled in. Install yaml-cpp, configure build and recompile.");
00163 #endif // HAVE_YAML_CPP
00164 }
00165
00167 template<typename T>
00168 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReadingPtsCount() const
00169 {
00170 return prefilteredReadingPtsCount;
00171 }
00172
00174 template<typename T>
00175 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReferencePtsCount() const
00176 {
00177 return prefilteredReferencePtsCount;
00178 }
00179
00180 #ifdef HAVE_YAML_CPP
00181
00183 template<typename T>
00184 template<typename R>
00185 const std::string& PointMatcher<T>::ICPChainBase::createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, PointMatcherSupport::SharedPtrVector<typename R::TargetType>& modules)
00186 {
00187 const YAML::Node *reg = doc.FindValue(regName);
00188 if (reg)
00189 {
00190
00191 for(YAML::Iterator moduleIt = reg->begin(); moduleIt != reg->end(); ++moduleIt)
00192 {
00193 const YAML::Node& module(*moduleIt);
00194 modules.push_back(registrar.createFromYAML(module));
00195 }
00196 }
00197 return regName;
00198 }
00199
00201 template<typename T>
00202 template<typename R>
00203 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)
00204 {
00205 const YAML::Node *reg = doc.FindValue(regName);
00206 if (reg)
00207 {
00208
00209 module.reset(registrar.createFromYAML(*reg));
00210 }
00211 else
00212 module.reset();
00213 return regName;
00214 }
00215
00216 #endif // HAVE_YAML_CPP
00217
00218 template struct PointMatcher<float>::ICPChainBase;
00219 template struct PointMatcher<double>::ICPChainBase;
00220
00221
00223 template<typename T>
00224 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00225 const DataPoints& readingIn,
00226 const DataPoints& referenceIn)
00227 {
00228 const int dim = readingIn.features.rows();
00229 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00230 return this->compute(readingIn, referenceIn, identity);
00231 }
00232
00234 template<typename T>
00235 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00236 const DataPoints& readingIn,
00237 const DataPoints& referenceIn,
00238 const TransformationParameters& initialTransformationParameters)
00239 {
00240 return this->compute(readingIn, referenceIn, initialTransformationParameters);
00241 }
00242
00244 template<typename T>
00245 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::compute(
00246 const DataPoints& readingIn,
00247 const DataPoints& referenceIn,
00248 const TransformationParameters& T_refIn_dataIn)
00249 {
00250
00251 if (!this->matcher)
00252 throw runtime_error("You must setup a matcher before running ICP");
00253 if (!this->errorMinimizer)
00254 throw runtime_error("You must setup an error minimizer before running ICP");
00255 if (!this->inspector)
00256 throw runtime_error("You must setup an inspector before running ICP");
00257
00258 this->inspector->init();
00259
00260 timer t;
00261 const int dim(referenceIn.features.rows());
00262
00263
00264
00265 DataPoints reference(referenceIn);
00266 this->referenceDataPointsFilters.init();
00267 this->referenceDataPointsFilters.apply(reference);
00268
00269
00270
00271 const int nbPtsReference = referenceIn.features.cols();
00272 const Vector meanReference = referenceIn.features.rowwise().sum() / nbPtsReference;
00273 TransformationParameters T_refIn_refMean(Matrix::Identity(dim, dim));
00274 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanReference.head(dim-1);
00275
00276
00277
00278
00279 reference.features.topRows(dim-1).colwise() -= meanReference.head(dim-1);
00280
00281
00282 this->matcher->init(reference);
00283
00284
00285 this->inspector->addStat("ReferencePreprocessingDuration", t.elapsed());
00286 this->inspector->addStat("ReferenceInPointCount", referenceIn.features.cols());
00287 this->inspector->addStat("ReferencePointCount", reference.features.cols());
00288 LOG_INFO_STREAM("PointMatcher::icp - reference pre-processing took " << t.elapsed() << " [s]");
00289 this->prefilteredReferencePtsCount = reference.features.cols();
00290
00291 return computeWithTransformedReference(readingIn, reference, T_refIn_refMean, T_refIn_dataIn);
00292
00293 }
00294
00296 template<typename T>
00297 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::computeWithTransformedReference(
00298 const DataPoints& readingIn,
00299 const DataPoints& reference,
00300 const TransformationParameters& T_refIn_refMean,
00301 const TransformationParameters& T_refIn_dataIn)
00302 {
00303 timer t;
00304
00305
00306
00307 DataPoints reading(readingIn);
00308
00309 this->readingDataPointsFilters.init();
00310 this->readingDataPointsFilters.apply(reading);
00311
00312
00313
00314 TransformationParameters
00315 T_refMean_dataIn = T_refIn_refMean.inverse() * T_refIn_dataIn;
00316 this->transformations.apply(reading, T_refMean_dataIn);
00317
00318
00319 this->readingStepDataPointsFilters.init();
00320
00321
00322
00323 const int dim(reference.features.rows());
00324 TransformationParameters T_iter = Matrix::Identity(dim, dim);
00325
00326 bool iterate(true);
00327 this->transformationCheckers.init(T_iter, iterate);
00328
00329 size_t iterationCount(0);
00330
00331
00332 this->inspector->addStat("ReadingPreprocessingDuration", t.elapsed());
00333 this->inspector->addStat("ReadingInPointCount", readingIn.features.cols());
00334 this->inspector->addStat("ReadingPointCount", reading.features.cols());
00335 LOG_INFO_STREAM("PointMatcher::icp - reading pre-processing took " << t.elapsed() << " [s]");
00336 this->prefilteredReadingPtsCount = reading.features.cols();
00337 t.restart();
00338
00339
00340 while (iterate)
00341 {
00342 DataPoints stepReading(reading);
00343
00344
00345
00346 this->readingStepDataPointsFilters.apply(stepReading);
00347
00348
00349
00350 this->transformations.apply(stepReading, T_iter);
00351
00352
00353
00354 const Matches matches(
00355 this->matcher->findClosests(stepReading)
00356 );
00357
00358
00359
00360 const OutlierWeights outlierWeights(
00361 this->outlierFilters.compute(stepReading, reference, matches)
00362 );
00363
00364 assert(outlierWeights.rows() == matches.ids.rows());
00365 assert(outlierWeights.cols() == matches.ids.cols());
00366
00367
00368
00369
00370
00371
00372 this->inspector->dumpIteration(
00373 iterationCount, T_iter, reference, stepReading, matches, outlierWeights, this->transformationCheckers
00374 );
00375
00376
00377
00378
00379
00380 T_iter = this->errorMinimizer->compute(
00381 stepReading, reference, outlierWeights, matches) * T_iter;
00382
00383
00384
00385
00386
00387
00388
00389 this->transformationCheckers.check(T_iter, iterate);
00390
00391 ++iterationCount;
00392 }
00393
00394 this->inspector->addStat("IterationsCount", iterationCount);
00395 this->inspector->addStat("PointCountTouched", this->matcher->getVisitCount());
00396 this->matcher->resetVisitCount();
00397 this->inspector->addStat("OverlapRatio", this->errorMinimizer->getWeightedPointUsedRatio());
00398 this->inspector->addStat("ConvergenceDuration", t.elapsed());
00399 this->inspector->finish(iterationCount);
00400
00401 LOG_INFO_STREAM("PointMatcher::icp - " << iterationCount << " iterations took " << t.elapsed() << " [s]");
00402
00403
00404
00405
00406
00407
00408
00409
00410 return (T_refIn_refMean * T_iter * T_refMean_dataIn);
00411 }
00412
00413 template struct PointMatcher<float>::ICP;
00414 template struct PointMatcher<double>::ICP;
00415
00416
00418 template<typename T>
00419 bool PointMatcher<T>::ICPSequence::hasMap() const
00420 {
00421 return (mapPointCloud.features.cols() != 0);
00422 }
00423
00425 template<typename T>
00426 bool PointMatcher<T>::ICPSequence::setMap(const DataPoints& inputCloud)
00427 {
00428
00429 if (!this->matcher)
00430 throw runtime_error("You must setup a matcher before running ICP");
00431 if (!this->inspector)
00432 throw runtime_error("You must setup an inspector before running ICP");
00433
00434 timer t;
00435 const int dim(inputCloud.features.rows());
00436 const int ptCount(inputCloud.features.cols());
00437
00438
00439 if (ptCount == 0)
00440 {
00441 LOG_WARNING_STREAM("Ignoring attempt to create a map from an empty cloud");
00442 return false;
00443 }
00444
00445 this->inspector->addStat("MapPointCount", inputCloud.features.cols());
00446
00447
00448 mapPointCloud = inputCloud;
00449
00450
00451
00452 const Vector meanMap = mapPointCloud.features.rowwise().sum() / ptCount;
00453 T_refIn_refMean = Matrix::Identity(dim, dim);
00454 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanMap.head(dim-1);
00455
00456
00457
00458
00459 mapPointCloud.features.topRows(dim-1).colwise() -= meanMap.head(dim-1);
00460
00461 this->matcher->init(mapPointCloud);
00462
00463 this->inspector->addStat("SetMapDuration", t.elapsed());
00464
00465 return true;
00466 }
00467
00469 template<typename T>
00470 void PointMatcher<T>::ICPSequence::clearMap()
00471 {
00472 const int dim(mapPointCloud.features.rows());
00473 T_refIn_refMean = Matrix::Identity(dim, dim);
00474 mapPointCloud = DataPoints();
00475 }
00476
00478 template<typename T>
00479 const typename PointMatcher<T>::DataPoints PointMatcher<T>::ICPSequence::getMap() const
00480 {
00481 DataPoints globalMap(mapPointCloud);
00482 const int dim(mapPointCloud.features.rows());
00483 const Vector meanMapNonHomo(T_refIn_refMean.block(0,dim-1, dim-1, 1));
00484 globalMap.features.topRows(dim-1).colwise() += meanMapNonHomo;
00485 return globalMap;
00486 }
00487
00489 template<typename T>
00490 const typename PointMatcher<T>::DataPoints& PointMatcher<T>::ICPSequence::getInternalMap() const
00491 {
00492 return mapPointCloud;
00493 }
00494
00496 template<typename T>
00497 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00498 const DataPoints& cloudIn)
00499 {
00500 const int dim = cloudIn.features.rows();
00501 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00502 return this->compute(cloudIn, identity);
00503 }
00504
00506 template<typename T>
00507 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00508 const DataPoints& cloudIn, const TransformationParameters& T_dataInOld_dataInNew)
00509 {
00510 return this->compute(cloudIn, T_dataInOld_dataInNew);
00511 }
00512
00514 template<typename T>
00515 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::compute(
00516 const DataPoints& cloudIn, const TransformationParameters& T_refIn_dataIn)
00517 {
00518
00519 if (!hasMap())
00520 {
00521 const int dim(cloudIn.features.rows());
00522 LOG_WARNING_STREAM("Ignoring attempt to perform ICP with an empty map");
00523 return Matrix::Identity(dim, dim);
00524 }
00525
00526 this->inspector->init();
00527
00528 return this->computeWithTransformedReference(cloudIn, mapPointCloud, T_refIn_refMean, T_refIn_dataIn);
00529 }
00530
00531 template struct PointMatcher<float>::ICPSequence;
00532 template struct PointMatcher<double>::ICPSequence;