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 namespace YAML = YAML_PM;
00054 #endif // HAVE_YAML_CPP
00055
00056 using namespace std;
00057 using namespace PointMatcherSupport;
00058
00060 InvalidModuleType::InvalidModuleType(const std::string& reason):
00061 runtime_error(reason)
00062 {}
00063
00065 template<typename T>
00066 PointMatcher<T>::ICPChainBase::ICPChainBase():
00067 prefilteredReadingPtsCount(0),
00068 prefilteredReferencePtsCount(0)
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(new typename TransformationsImpl<T>::RigidTransformation());
00105 this->readingDataPointsFilters.push_back(new typename DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter());
00106 this->referenceDataPointsFilters.push_back(new typename DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter());
00107 this->outlierFilters.push_back(new typename OutlierFiltersImpl<T>::TrimmedDistOutlierFilter());
00108 this->matcher.reset(new typename MatchersImpl<T>::KDTreeMatcher());
00109 this->errorMinimizer.reset(new typename ErrorMinimizersImpl<T>::PointToPlaneErrorMinimizer());
00110 this->transformationCheckers.push_back(new typename TransformationCheckersImpl<T>::CounterTransformationChecker());
00111 this->transformationCheckers.push_back(new typename TransformationCheckersImpl<T>::DifferentialTransformationChecker());
00112 this->inspector.reset(new 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
00125 typedef set<string> StringSet;
00126 StringSet usedModuleTypes;
00127
00128
00129
00130 const PointMatcher & pm = PointMatcher::get();
00131
00132 {
00133
00134 boost::mutex::scoped_lock lock(loggerMutex);
00135 usedModuleTypes.insert(createModuleFromRegistrar("logger", doc, pm.REG(Logger), logger));
00136 }
00137 usedModuleTypes.insert(createModulesFromRegistrar("readingDataPointsFilters", doc, pm.REG(DataPointsFilter), readingDataPointsFilters));
00138 usedModuleTypes.insert(createModulesFromRegistrar("readingStepDataPointsFilters", doc, pm.REG(DataPointsFilter), readingStepDataPointsFilters));
00139 usedModuleTypes.insert(createModulesFromRegistrar("referenceDataPointsFilters", doc, pm.REG(DataPointsFilter), referenceDataPointsFilters));
00140
00141 this->transformations.push_back(new typename TransformationsImpl<T>::RigidTransformation());
00142 usedModuleTypes.insert(createModuleFromRegistrar("matcher", doc, pm.REG(Matcher), matcher));
00143 usedModuleTypes.insert(createModulesFromRegistrar("outlierFilters", doc, pm.REG(OutlierFilter), outlierFilters));
00144 usedModuleTypes.insert(createModuleFromRegistrar("errorMinimizer", doc, pm.REG(ErrorMinimizer), errorMinimizer));
00145 usedModuleTypes.insert(createModulesFromRegistrar("transformationCheckers", doc, pm.REG(TransformationChecker), transformationCheckers));
00146 usedModuleTypes.insert(createModuleFromRegistrar("inspector", doc, pm.REG(Inspector),inspector));
00147
00148
00149
00150
00151
00152
00153 for(YAML::Iterator moduleTypeIt = doc.begin(); moduleTypeIt != doc.end(); ++moduleTypeIt)
00154 {
00155 string moduleType;
00156 moduleTypeIt.first() >> moduleType;
00157 if (usedModuleTypes.find(moduleType) == usedModuleTypes.end())
00158 throw InvalidModuleType(
00159 (boost::format("Module type %1% does not exist") % moduleType).str()
00160 );
00161 }
00162 }
00163
00165 template<typename T>
00166 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReadingPtsCount() const
00167 {
00168 return prefilteredReadingPtsCount;
00169 }
00170
00172 template<typename T>
00173 unsigned PointMatcher<T>::ICPChainBase::getPrefilteredReferencePtsCount() const
00174 {
00175 return prefilteredReferencePtsCount;
00176 }
00177
00179 template<typename T>
00180 template<typename R>
00181 const std::string& PointMatcher<T>::ICPChainBase::createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, PointMatcherSupport::SharedPtrVector<typename R::TargetType>& modules)
00182 {
00183 const YAML::Node *reg = doc.FindValue(regName);
00184 if (reg)
00185 {
00186
00187 for(YAML::Iterator moduleIt = reg->begin(); moduleIt != reg->end(); ++moduleIt)
00188 {
00189 const YAML::Node& module(*moduleIt);
00190 modules.push_back(registrar.createFromYAML(module));
00191 }
00192 }
00193 return regName;
00194 }
00195
00197 template<typename T>
00198 template<typename R>
00199 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)
00200 {
00201 const YAML::Node *reg = doc.FindValue(regName);
00202 if (reg)
00203 {
00204
00205 module.reset(registrar.createFromYAML(*reg));
00206 }
00207 else
00208 module.reset();
00209 return regName;
00210 }
00211
00212 template struct PointMatcher<float>::ICPChainBase;
00213 template struct PointMatcher<double>::ICPChainBase;
00214
00215
00217 template<typename T>
00218 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00219 const DataPoints& readingIn,
00220 const DataPoints& referenceIn)
00221 {
00222 const int dim = readingIn.features.rows();
00223 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00224 return this->compute(readingIn, referenceIn, identity);
00225 }
00226
00228 template<typename T>
00229 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::operator ()(
00230 const DataPoints& readingIn,
00231 const DataPoints& referenceIn,
00232 const TransformationParameters& initialTransformationParameters)
00233 {
00234 return this->compute(readingIn, referenceIn, initialTransformationParameters);
00235 }
00236
00238 template<typename T>
00239 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::compute(
00240 const DataPoints& readingIn,
00241 const DataPoints& referenceIn,
00242 const TransformationParameters& T_refIn_dataIn)
00243 {
00244
00245 if (!this->matcher)
00246 throw runtime_error("You must setup a matcher before running ICP");
00247 if (!this->errorMinimizer)
00248 throw runtime_error("You must setup an error minimizer before running ICP");
00249 if (!this->inspector)
00250 throw runtime_error("You must setup an inspector before running ICP");
00251
00252 this->inspector->init();
00253
00254 timer t;
00255 const int dim(referenceIn.features.rows());
00256
00257
00258
00259 DataPoints reference(referenceIn);
00260 this->referenceDataPointsFilters.init();
00261 this->referenceDataPointsFilters.apply(reference);
00262
00263
00264
00265 const int nbPtsReference = referenceIn.features.cols();
00266 const Vector meanReference = referenceIn.features.rowwise().sum() / nbPtsReference;
00267 TransformationParameters T_refIn_refMean(Matrix::Identity(dim, dim));
00268 T_refIn_refMean.block(0,dim-1, dim-1, 1) = meanReference.head(dim-1);
00269
00270
00271
00272
00273 reference.features.topRows(dim-1).colwise() -= meanReference.head(dim-1);
00274
00275
00276 this->matcher->init(reference);
00277
00278
00279 this->inspector->addStat("ReferencePreprocessingDuration", t.elapsed());
00280 this->inspector->addStat("ReferenceInPointCount", referenceIn.features.cols());
00281 this->inspector->addStat("ReferencePointCount", reference.features.cols());
00282 LOG_INFO_STREAM("PointMatcher::icp - reference pre-processing took " << t.elapsed() << " [s]");
00283 this->prefilteredReferencePtsCount = reference.features.cols();
00284
00285 return computeWithTransformedReference(readingIn, reference, T_refIn_refMean, T_refIn_dataIn);
00286
00287 }
00288
00290 template<typename T>
00291 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICP::computeWithTransformedReference(
00292 const DataPoints& readingIn,
00293 const DataPoints& reference,
00294 const TransformationParameters& T_refIn_refMean,
00295 const TransformationParameters& T_refIn_dataIn)
00296 {
00297 timer t;
00298
00299
00300
00301 DataPoints reading(readingIn);
00302
00303 this->readingDataPointsFilters.init();
00304 this->readingDataPointsFilters.apply(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 const int dim(mapPointCloud.features.rows());
00477 const Vector meanMapNonHomo(T_refIn_refMean.block(0,dim-1, dim-1, 1));
00478 globalMap.features.topRows(dim-1).colwise() += meanMapNonHomo;
00479 return globalMap;
00480 }
00481
00483 template<typename T>
00484 const typename PointMatcher<T>::DataPoints& PointMatcher<T>::ICPSequence::getInternalMap() const
00485 {
00486 return mapPointCloud;
00487 }
00488
00490 template<typename T>
00491 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00492 const DataPoints& cloudIn)
00493 {
00494 const int dim = cloudIn.features.rows();
00495 const TransformationParameters identity = TransformationParameters::Identity(dim, dim);
00496 return this->compute(cloudIn, identity);
00497 }
00498
00500 template<typename T>
00501 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::operator ()(
00502 const DataPoints& cloudIn, const TransformationParameters& T_dataInOld_dataInNew)
00503 {
00504 return this->compute(cloudIn, T_dataInOld_dataInNew);
00505 }
00506
00508 template<typename T>
00509 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ICPSequence::compute(
00510 const DataPoints& cloudIn, const TransformationParameters& T_refIn_dataIn)
00511 {
00512
00513 if (!hasMap())
00514 {
00515 const int dim(cloudIn.features.rows());
00516 LOG_WARNING_STREAM("Ignoring attempt to perform ICP with an empty map");
00517 return Matrix::Identity(dim, dim);
00518 }
00519
00520 this->inspector->init();
00521
00522 return this->computeWithTransformedReference(cloudIn, mapPointCloud, T_refIn_refMean, T_refIn_dataIn);
00523 }
00524
00525 template struct PointMatcher<float>::ICPSequence;
00526 template struct PointMatcher<double>::ICPSequence;