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 #ifndef __POINTMATCHER_CORE_H
00037 #define __POINTMATCHER_CORE_H
00038
00039 #ifndef EIGEN_USE_NEW_STDVECTOR
00040 #define EIGEN_USE_NEW_STDVECTOR
00041 #endif // EIGEN_USE_NEW_STDVECTOR
00042 #define EIGEN2_SUPPORT
00043 #include "Eigen/StdVector"
00044 #include "Eigen/Core"
00045 #include "Eigen/Geometry"
00046
00047 #include "nabo/nabo.h"
00048
00049 #include <boost/thread/mutex.hpp>
00050
00051 #include <stdexcept>
00052 #include <limits>
00053 #include <iostream>
00054 #include <ostream>
00055 #include <memory>
00056
00057 #include "Parametrizable.h"
00058 #include "Registrar.h"
00059
00060 #if NABO_VERSION_INT < 10001
00061 #error "You need libnabo version 1.0.1 or greater"
00062 #endif
00063
00070
00071 #define POINTMATCHER_VERSION "1.2.1"
00072
00073 #define POINTMATCHER_VERSION_INT 10201
00074
00076 namespace PointMatcherSupport
00077 {
00078 using boost::assign::list_of;
00079 using boost::assign::map_list_of;
00080
00081
00083 struct InvalidModuleType: std::runtime_error
00084 {
00085 InvalidModuleType(const std::string& reason);
00086 };
00087
00089 struct TransformationError: std::runtime_error
00090 {
00092 TransformationError(const std::string& reason);
00093 };
00094
00096 template<typename S>
00097 struct SharedPtrVector: public std::vector<boost::shared_ptr<S> >
00098 {
00100 void push_back(S* v) { std::vector<boost::shared_ptr<S> >::push_back(boost::shared_ptr<S>(v)); }
00101 };
00102
00104 struct Logger: public Parametrizable
00105 {
00106 Logger();
00107 Logger(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00108
00109 virtual ~Logger();
00110 virtual bool hasInfoChannel() const;
00111 virtual void beginInfoEntry(const char *file, unsigned line, const char *func);
00112 virtual std::ostream* infoStream();
00113 virtual void finishInfoEntry(const char *file, unsigned line, const char *func);
00114 virtual bool hasWarningChannel() const;
00115 virtual void beginWarningEntry(const char *file, unsigned line, const char *func);
00116 virtual std::ostream* warningStream();
00117 virtual void finishWarningEntry(const char *file, unsigned line, const char *func);
00118 };
00119
00120 void setLogger(Logger* newLogger);
00121
00122 void validateFile(const std::string& fileName);
00123
00125 typedef std::map<std::string, std::vector<std::string> > CsvElements;
00126 }
00127
00129 template<typename T>
00130 struct PointMatcher
00131 {
00132
00133
00134
00135
00137 #define ZERO_PLUS_EPS (0. + std::numeric_limits<double>::epsilon())
00138
00139 #define ONE_MINUS_EPS (1. - std::numeric_limits<double>::epsilon())
00140
00141
00142
00143
00144
00145
00146
00148 struct ConvergenceError: std::runtime_error
00149 {
00150 ConvergenceError(const std::string& reason);
00151 };
00152
00153
00154
00155
00156
00157
00159 typedef T ScalarType;
00161 typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
00163 typedef std::vector<Vector, Eigen::aligned_allocator<Vector> > VectorVector;
00165 typedef typename Eigen::Quaternion<T> Quaternion;
00167 typedef std::vector<Quaternion, Eigen::aligned_allocator<Quaternion> > QuaternionVector;
00169 typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
00171 typedef typename Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic> IntMatrix;
00172
00174
00177 typedef Matrix TransformationParameters;
00178
00179
00180 typedef PointMatcherSupport::Parametrizable Parametrizable;
00181 typedef Parametrizable::Parameters Parameters;
00182 typedef Parametrizable::ParameterDoc ParameterDoc;
00183 typedef Parametrizable::ParametersDoc ParametersDoc;
00184 typedef Parametrizable::InvalidParameter InvalidParameter;
00185
00186
00187
00188
00189
00191
00202 struct DataPoints
00203 {
00205 typedef Eigen::Block<Matrix> View;
00207 typedef const Eigen::Block<const Matrix> ConstView;
00209 typedef typename Matrix::Index Index;
00210
00212 struct Label
00213 {
00214 std::string text;
00215 size_t span;
00216 Label(const std::string& text = "", const size_t span = 0);
00217 bool operator ==(const Label& that) const;
00218 };
00220 struct Labels: std::vector<Label>
00221 {
00222 typedef typename std::vector<Label>::const_iterator const_iterator;
00223 Labels();
00224 Labels(const Label& label);
00225 bool contains(const std::string& text) const;
00226 size_t totalDim() const;
00227 };
00228
00230 struct InvalidField: std::runtime_error
00231 {
00232 InvalidField(const std::string& reason);
00233 };
00234
00235 DataPoints();
00236 DataPoints(const Labels& featureLabels, const Labels& descriptorLabels, const size_t pointCount);
00237 DataPoints(const Matrix& features, const Labels& featureLabels);
00238 DataPoints(const Matrix& features, const Labels& featureLabels, const Matrix& descriptors, const Labels& descriptorLabels);
00239 bool operator ==(const DataPoints& that) const;
00240
00241 unsigned getNbPoints() const;
00242 unsigned getEuclideanDim() const;
00243 unsigned getHomogeneousDim() const;
00244 unsigned getNbGroupedDescriptors() const;
00245 unsigned getDescriptorDim() const;
00246
00247 void save(const std::string& fileName) const;
00248 static DataPoints load(const std::string& fileName);
00249
00250 void concatenate(const DataPoints& dp);
00251 void conservativeResize(Index pointCount);
00252 DataPoints createSimilarEmpty() const;
00253 DataPoints createSimilarEmpty(Index pointCount) const;
00254 void setColFrom(Index thisCol, const DataPoints& that, Index thatCol);
00255
00256 void allocateFeature(const std::string& name, const unsigned dim);
00257 void allocateFeatures(const Labels& newLabels);
00258 void addFeature(const std::string& name, const Matrix& newFeature);
00259 void removeFeature(const std::string& name);
00260 Matrix getFeatureCopyByName(const std::string& name) const;
00261 ConstView getFeatureViewByName(const std::string& name) const;
00262 View getFeatureViewByName(const std::string& name);
00263 ConstView getFeatureRowViewByName(const std::string& name, const unsigned row) const;
00264 View getFeatureRowViewByName(const std::string& name, const unsigned row);
00265 bool featureExists(const std::string& name) const;
00266 bool featureExists(const std::string& name, const unsigned dim) const;
00267 unsigned getFeatureDimension(const std::string& name) const;
00268 unsigned getFeatureStartingRow(const std::string& name) const;
00269
00270 void allocateDescriptor(const std::string& name, const unsigned dim);
00271 void allocateDescriptors(const Labels& newLabels);
00272 void addDescriptor(const std::string& name, const Matrix& newDescriptor);
00273 void removeDescriptor(const std::string& name);
00274 Matrix getDescriptorCopyByName(const std::string& name) const;
00275 ConstView getDescriptorViewByName(const std::string& name) const;
00276 View getDescriptorViewByName(const std::string& name);
00277 ConstView getDescriptorRowViewByName(const std::string& name, const unsigned row) const;
00278 View getDescriptorRowViewByName(const std::string& name, const unsigned row);
00279 bool descriptorExists(const std::string& name) const;
00280 bool descriptorExists(const std::string& name, const unsigned dim) const;
00281 unsigned getDescriptorDimension(const std::string& name) const;
00282 unsigned getDescriptorStartingRow(const std::string& name) const;
00283 void assertDescriptorConsistency() const;
00284
00285 Matrix features;
00286 Labels featureLabels;
00287 Matrix descriptors;
00288 Labels descriptorLabels;
00289
00290 private:
00291 void allocateFields(const Labels& newLabels, Labels& labels, Matrix& data) const;
00292 void allocateField(const std::string& name, const unsigned dim, Labels& labels, Matrix& data) const;
00293 void addField(const std::string& name, const Matrix& newField, Labels& labels, Matrix& data) const;
00294 void removeField(const std::string& name, Labels& labels, Matrix& data) const;
00295 ConstView getConstViewByName(const std::string& name, const Labels& labels, const Matrix& data, const int viewRow = -1) const;
00296 View getViewByName(const std::string& name, const Labels& labels, Matrix& data, const int viewRow = -1) const;
00297 bool fieldExists(const std::string& name, const unsigned dim, const Labels& labels) const;
00298 unsigned getFieldDimension(const std::string& name, const Labels& labels) const;
00299 unsigned getFieldStartingRow(const std::string& name, const Labels& labels) const;
00300 };
00301
00302 static void swapDataPoints(DataPoints& a, DataPoints& b);
00303
00304
00305
00306
00307
00309
00313 struct Matches
00314 {
00315 typedef Matrix Dists;
00316 typedef IntMatrix Ids;
00317
00318 Matches();
00319 Matches(const Dists& dists, const Ids ids);
00320 Matches(const int knn, const int pointsCount);
00321
00322 Dists dists;
00323 Ids ids;
00324
00325 T getDistsQuantile(const T quantile) const;
00326 };
00327
00329
00332 typedef Matrix OutlierWeights;
00333
00334
00335
00336
00337
00339 struct Transformation: public Parametrizable
00340 {
00341 Transformation();
00342 Transformation(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00343 virtual ~Transformation();
00344
00346 virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const = 0;
00347
00349 virtual bool checkParameters(const TransformationParameters& parameters) const = 0;
00350
00352 virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const = 0;
00353
00354 };
00355
00357 struct Transformations: public PointMatcherSupport::SharedPtrVector<Transformation>
00358 {
00359 void apply(DataPoints& cloud, const TransformationParameters& parameters) const;
00360 };
00361 typedef typename Transformations::iterator TransformationsIt;
00362 typedef typename Transformations::const_iterator TransformationsConstIt;
00363
00364 DEF_REGISTRAR(Transformation)
00365
00366
00367
00368
00369
00372 struct DataPointsFilter: public Parametrizable
00373 {
00374 DataPointsFilter();
00375 DataPointsFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00376 virtual ~DataPointsFilter();
00377 virtual void init();
00378
00380 virtual DataPoints filter(const DataPoints& input) = 0;
00381
00383 virtual void inPlaceFilter(DataPoints& cloud) = 0;
00384 };
00385
00387 struct DataPointsFilters: public PointMatcherSupport::SharedPtrVector<DataPointsFilter>
00388 {
00389 DataPointsFilters();
00390 DataPointsFilters(std::istream& in);
00391 void init();
00392 void apply(DataPoints& cloud);
00393 };
00394 typedef typename DataPointsFilters::iterator DataPointsFiltersIt;
00395 typedef typename DataPointsFilters::const_iterator DataPointsFiltersConstIt;
00396
00397 DEF_REGISTRAR(DataPointsFilter)
00398
00399
00400
00401
00402
00405 struct Matcher: public Parametrizable
00406 {
00407 unsigned long visitCounter;
00408
00409 Matcher();
00410 Matcher(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00411 virtual ~Matcher();
00412
00413 void resetVisitCount();
00414 unsigned long getVisitCount() const;
00415
00417 virtual void init(const DataPoints& filteredReference) = 0;
00419 virtual Matches findClosests(const DataPoints& filteredReading) = 0;
00420 };
00421
00422 DEF_REGISTRAR(Matcher)
00423
00424
00425
00426
00427
00431 struct OutlierFilter: public Parametrizable
00432 {
00433 OutlierFilter();
00434 OutlierFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00435
00436 virtual ~OutlierFilter();
00437
00439 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input) = 0;
00440 };
00441
00442
00444 struct OutlierFilters: public PointMatcherSupport::SharedPtrVector<OutlierFilter>
00445 {
00446
00447 OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00448
00449 };
00450
00451 typedef typename OutlierFilters::const_iterator OutlierFiltersConstIt;
00452 typedef typename OutlierFilters::iterator OutlierFiltersIt;
00453
00454 DEF_REGISTRAR(OutlierFilter)
00455
00456
00457
00458
00459
00462 struct ErrorMinimizer: public Parametrizable
00463 {
00465 struct ErrorElements
00466 {
00467 DataPoints reading;
00468 DataPoints reference;
00469 OutlierWeights weights;
00470 Matches matches;
00471
00472 ErrorElements(const DataPoints& reading=DataPoints(), const DataPoints reference = DataPoints(), const OutlierWeights weights = OutlierWeights(), const Matches matches = Matches());
00473 };
00474
00475 ErrorMinimizer();
00476 ErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00477 virtual ~ErrorMinimizer();
00478
00479 T getPointUsedRatio() const;
00480 T getWeightedPointUsedRatio() const;
00481 virtual T getOverlap() const;
00482 virtual Matrix getCovariance() const;
00483
00485 virtual TransformationParameters compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches) = 0;
00486
00487
00488 protected:
00489
00490 static Matrix crossProduct(const Matrix& A, const Matrix& B);
00491 ErrorElements& getMatchedPoints(const DataPoints& reading, const DataPoints& reference, const Matches& matches, const OutlierWeights& outlierWeights);
00492
00493 protected:
00494 T pointUsedRatio;
00495 T weightedPointUsedRatio;
00496 ErrorElements lastErrorElements;
00497 };
00498
00499 DEF_REGISTRAR(ErrorMinimizer)
00500
00501
00502
00503
00504
00508 struct TransformationChecker: public Parametrizable
00509 {
00510 protected:
00511 typedef std::vector<std::string> StringVector;
00512 Vector limits;
00513 Vector conditionVariables;
00514 StringVector limitNames;
00515 StringVector conditionVariableNames;
00516
00517 public:
00518 TransformationChecker();
00519 TransformationChecker(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00520 virtual ~TransformationChecker();
00522 virtual void init(const TransformationParameters& parameters, bool& iterate) = 0;
00524 virtual void check(const TransformationParameters& parameters, bool& iterate) = 0;
00525
00526 const Vector& getLimits() const;
00527 const Vector& getConditionVariables() const;
00528 const StringVector& getLimitNames() const;
00529 const StringVector& getConditionVariableNames() const;
00530
00531 protected:
00532 static Vector matrixToAngles(const TransformationParameters& parameters);
00533 };
00534
00536 struct TransformationCheckers: public PointMatcherSupport::SharedPtrVector<TransformationChecker>
00537 {
00538 void init(const TransformationParameters& parameters, bool& iterate);
00539 void check(const TransformationParameters& parameters, bool& iterate);
00540 };
00541 typedef typename TransformationCheckers::iterator TransformationCheckersIt;
00542 typedef typename TransformationCheckers::const_iterator TransformationCheckersConstIt;
00543
00544 DEF_REGISTRAR(TransformationChecker)
00545
00546
00547
00548
00549 struct Inspector: public Parametrizable
00550 {
00551
00552 Inspector();
00553 Inspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00554
00555
00556 virtual ~Inspector();
00557 virtual void init();
00558
00559
00560 virtual void addStat(const std::string& name, double data);
00561 virtual void dumpStats(std::ostream& stream);
00562 virtual void dumpStatsHeader(std::ostream& stream);
00563
00564
00565 virtual void dumpIteration(const size_t iterationNumber, const TransformationParameters& parameters, const DataPoints& filteredReference, const DataPoints& reading, const Matches& matches, const OutlierWeights& outlierWeights, const TransformationCheckers& transformationCheckers);
00566 virtual void finish(const size_t iterationCount);
00567 };
00568
00569 DEF_REGISTRAR(Inspector)
00570
00571
00572
00573 DEF_REGISTRAR_IFACE(Logger, PointMatcherSupport::Logger)
00574
00575
00576
00577
00578
00580 struct ICPChainBase
00581 {
00582 public:
00583 DataPointsFilters readingDataPointsFilters;
00584 DataPointsFilters readingStepDataPointsFilters;
00585 DataPointsFilters referenceDataPointsFilters;
00586 Transformations transformations;
00587 boost::shared_ptr<Matcher> matcher;
00588 OutlierFilters outlierFilters;
00589 boost::shared_ptr<ErrorMinimizer> errorMinimizer;
00590 TransformationCheckers transformationCheckers;
00591 boost::shared_ptr<Inspector> inspector;
00592
00593 virtual ~ICPChainBase();
00594
00595 virtual void setDefault();
00596
00597 void loadFromYaml(std::istream& in);
00598 unsigned getPrefilteredReadingPtsCount() const;
00599 unsigned getPrefilteredReferencePtsCount() const;
00600
00601 protected:
00602 unsigned prefilteredReadingPtsCount;
00603 unsigned prefilteredReferencePtsCount;
00604
00605 ICPChainBase();
00606
00607 void cleanup();
00608
00609 virtual void loadAdditionalYAMLContent(YAML::Node& doc);
00610
00611 template<typename R>
00612 const std::string& createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, PointMatcherSupport::SharedPtrVector<typename R::TargetType>& modules);
00613
00614 template<typename R>
00615 const std::string& createModuleFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, boost::shared_ptr<typename R::TargetType>& module);
00616
00617
00618
00619 };
00620
00622 struct ICP: ICPChainBase
00623 {
00624 TransformationParameters operator()(
00625 const DataPoints& readingIn,
00626 const DataPoints& referenceIn);
00627
00628 TransformationParameters operator()(
00629 const DataPoints& readingIn,
00630 const DataPoints& referenceIn,
00631 const TransformationParameters& initialTransformationParameters);
00632
00633 TransformationParameters compute(
00634 const DataPoints& readingIn,
00635 const DataPoints& referenceIn,
00636 const TransformationParameters& initialTransformationParameters);
00637
00638 protected:
00639 TransformationParameters computeWithTransformedReference(
00640 const DataPoints& readingIn,
00641 const DataPoints& reference,
00642 const TransformationParameters& T_refIn_refMean,
00643 const TransformationParameters& initialTransformationParameters);
00644 };
00645
00647 struct ICPSequence: public ICP
00648 {
00649 TransformationParameters operator()(
00650 const DataPoints& cloudIn);
00651 TransformationParameters operator()(
00652 const DataPoints& cloudIn,
00653 const TransformationParameters& initialTransformationParameters);
00654 TransformationParameters compute(
00655 const DataPoints& cloudIn,
00656 const TransformationParameters& initialTransformationParameters);
00657
00658 bool hasMap() const;
00659 bool setMap(const DataPoints& map);
00660 void clearMap();
00661 const DataPoints& getInternalMap() const;
00662 const DataPoints getMap() const;
00663
00664 protected:
00665 DataPoints mapPointCloud;
00666 TransformationParameters T_refIn_refMean;
00667 };
00668
00669
00670
00671
00672
00673 PointMatcher();
00674
00675 static const PointMatcher& get();
00676
00677
00678 };
00679
00680 #endif // __POINTMATCHER_CORE_H
00681