PointMatcher.h
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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.0.2"
00072 
00073 #define POINTMATCHER_VERSION_INT 10002
00074 
00076 namespace PointMatcherSupport
00077 {
00078     // TODO: gather all exceptions
00079 
00081     struct InvalidModuleType: std::runtime_error
00082     {
00083         InvalidModuleType(const std::string& reason);
00084     };
00085 
00087     struct TransformationError: std::runtime_error
00088     {
00090         TransformationError(const std::string& reason);
00091     };
00092 
00094     template<typename S>
00095     struct SharedPtrVector: public std::vector<std::shared_ptr<S>>
00096     {
00098         void push_back(S* v) { std::vector<std::shared_ptr<S>>::push_back(std::shared_ptr<S>(v)); }
00099     };
00100     
00102     struct Logger: public Parametrizable
00103     {
00104         Logger();
00105         Logger(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00106         
00107         virtual ~Logger();
00108         virtual bool hasInfoChannel() const;
00109         virtual void beginInfoEntry(const char *file, unsigned line, const char *func);
00110         virtual std::ostream* infoStream();
00111         virtual void finishInfoEntry(const char *file, unsigned line, const char *func);
00112         virtual bool hasWarningChannel() const;
00113         virtual void beginWarningEntry(const char *file, unsigned line, const char *func);
00114         virtual std::ostream* warningStream();
00115         virtual void finishWarningEntry(const char *file, unsigned line, const char *func);
00116     };
00117     
00118     void setLogger(Logger* newLogger);
00119     
00120     void validateFile(const std::string& fileName);
00121     
00123     typedef std::map<std::string, std::vector<std::string>> CsvElements;
00124 
00125 }
00126 
00128 template<typename T>
00129 struct PointMatcher
00130 {
00131     // ---------------------------------
00132     // macros for constants
00133     // ---------------------------------
00134     
00136     #define ZERO_PLUS_EPS (0. + std::numeric_limits<double>::epsilon())
00137 
00138     #define ONE_MINUS_EPS (1. - std::numeric_limits<double>::epsilon())
00139     
00140     // ---------------------------------
00141     // exceptions
00142     // ---------------------------------
00143 
00144     //TODO: gather exceptions here and in Exceptions.cpp
00145 
00147     struct ConvergenceError: std::runtime_error
00148     {
00149         ConvergenceError(const std::string& reason);
00150     };
00151 
00152 
00153     // ---------------------------------
00154     // eigen and nabo-based types
00155     // ---------------------------------
00156     
00158     typedef T ScalarType;
00160     typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
00162     typedef std::vector<Vector, Eigen::aligned_allocator<Vector> > VectorVector;
00164     typedef typename Eigen::Quaternion<T> Quaternion;
00166     typedef std::vector<Quaternion, Eigen::aligned_allocator<Quaternion> > QuaternionVector;
00168     typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
00170     typedef typename Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic> IntMatrix;
00171     
00173 
00176     typedef Matrix TransformationParameters;
00177     
00178     // alias for scope reasons
00179     typedef PointMatcherSupport::Parametrizable Parametrizable; 
00180     typedef Parametrizable::Parameters Parameters; 
00181     typedef Parametrizable::ParameterDoc ParameterDoc; 
00182     typedef Parametrizable::ParametersDoc ParametersDoc; 
00183     typedef Parametrizable::InvalidParameter InvalidParameter; 
00184     
00185     // ---------------------------------
00186     // input types
00187     // ---------------------------------
00188     
00190 
00201     struct DataPoints
00202     {
00204         typedef Eigen::Block<Matrix> View;
00206         typedef const Eigen::Block<const Matrix> ConstView;
00208         typedef typename Matrix::Index Index;
00209         
00211         struct Label
00212         {
00213             std::string text; 
00214             size_t span; 
00215             Label(const std::string& text = "", const size_t span = 0);
00216             bool operator ==(const Label& that) const;
00217         };
00219         struct Labels: std::vector<Label>
00220         {
00221             typedef typename std::vector<Label>::const_iterator const_iterator; 
00222             Labels();
00223             Labels(const Label& label);
00224             bool contains(const std::string& text) const;
00225             size_t totalDim() const;
00226         };
00227         
00229         struct InvalidField: std::runtime_error
00230         {
00231             InvalidField(const std::string& reason);
00232         };
00233         
00234         DataPoints();
00235         DataPoints(const Labels& featureLabels, const Labels& descriptorLabels, const size_t pointCount);
00236         DataPoints(const Matrix& features, const Labels& featureLabels);
00237         DataPoints(const Matrix& features, const Labels& featureLabels, const Matrix& descriptors, const Labels& descriptorLabels);
00238         bool operator ==(const DataPoints& that) const;
00239         
00240         void save(const std::string& fileName) const;
00241         static DataPoints load(const std::string& fileName);
00242         
00243         void concatenate(const DataPoints& dp);
00244         void conservativeResize(Index pointCount);
00245         DataPoints createSimilarEmpty() const;
00246         DataPoints createSimilarEmpty(Index pointCount) const;
00247         void setColFrom(Index thisCol, const DataPoints& that, Index thatCol);
00248         
00249         void allocateFeature(const std::string& name, const unsigned dim);
00250         void allocateFeatures(const Labels& newLabels);
00251         void addFeature(const std::string& name, const Matrix& newFeature);
00252         Matrix getFeatureCopyByName(const std::string& name) const;
00253         ConstView getFeatureViewByName(const std::string& name) const;
00254         View getFeatureViewByName(const std::string& name);
00255         ConstView getFeatureRowViewByName(const std::string& name, const unsigned row) const;
00256         View getFeatureRowViewByName(const std::string& name, const unsigned row);
00257         bool featureExists(const std::string& name) const;
00258         bool featureExists(const std::string& name, const unsigned dim) const;
00259         unsigned getFeatureDimension(const std::string& name) const;
00260         unsigned getFeatureStartingRow(const std::string& name) const;
00261         
00262         void allocateDescriptor(const std::string& name, const unsigned dim);
00263         void allocateDescriptors(const Labels& newLabels);
00264         void addDescriptor(const std::string& name, const Matrix& newDescriptor);
00265         Matrix getDescriptorCopyByName(const std::string& name) const;
00266         ConstView getDescriptorViewByName(const std::string& name) const;
00267         View getDescriptorViewByName(const std::string& name);
00268         ConstView getDescriptorRowViewByName(const std::string& name, const unsigned row) const;
00269         View getDescriptorRowViewByName(const std::string& name, const unsigned row);
00270         bool descriptorExists(const std::string& name) const;
00271         bool descriptorExists(const std::string& name, const unsigned dim) const;
00272         unsigned getDescriptorDimension(const std::string& name) const;
00273         unsigned getDescriptorStartingRow(const std::string& name) const;
00274         void assertDescriptorConsistency() const;
00275         
00276         Matrix features; 
00277         Labels featureLabels; 
00278         Matrix descriptors; 
00279         Labels descriptorLabels; 
00280     
00281     private:
00282         void allocateFields(const Labels& newLabels, Labels& labels, Matrix& data) const;
00283         void allocateField(const std::string& name, const unsigned dim, Labels& labels, Matrix& data) const;
00284         void addField(const std::string& name, const Matrix& newField, Labels& labels, Matrix& data) const;
00285         ConstView getConstViewByName(const std::string& name, const Labels& labels, const Matrix& data, const int viewRow = -1) const;
00286         View getViewByName(const std::string& name, const Labels& labels, Matrix& data, const int viewRow = -1) const;
00287         bool fieldExists(const std::string& name, const unsigned dim, const Labels& labels) const;
00288         unsigned getFieldDimension(const std::string& name, const Labels& labels) const;
00289         unsigned getFieldStartingRow(const std::string& name, const Labels& labels) const;
00290     };
00291     
00292     static void swapDataPoints(DataPoints& a, DataPoints& b);
00293 
00294     // ---------------------------------
00295     // intermediate types
00296     // ---------------------------------
00297     
00299 
00303     struct Matches
00304     {
00305         typedef Matrix Dists; 
00306         typedef IntMatrix Ids; 
00307     
00308         Matches();
00309         Matches(const Dists& dists, const Ids ids);
00310         Matches(const int knn, const int pointsCount);
00311         
00312         Dists dists; 
00313         Ids ids; 
00314         
00315         T getDistsQuantile(const T quantile) const;
00316     };
00317 
00319 
00322     typedef Matrix OutlierWeights;
00323     
00324     // ---------------------------------
00325     // types of processing bricks
00326     // ---------------------------------
00327     
00329     struct Transformation: public Parametrizable
00330     {
00331         Transformation();
00332         Transformation(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00333         virtual ~Transformation();
00334         
00336         virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const = 0; 
00337 
00339         virtual bool checkParameters(const TransformationParameters& parameters) const = 0;
00340 
00342         virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const = 0;
00343 
00344     };
00345     
00347     struct Transformations: public PointMatcherSupport::SharedPtrVector<Transformation>
00348     {
00349         void apply(DataPoints& cloud, const TransformationParameters& parameters) const;
00350     };
00351     typedef typename Transformations::iterator TransformationsIt; 
00352     typedef typename Transformations::const_iterator TransformationsConstIt; 
00353     
00354     DEF_REGISTRAR(Transformation)
00355     
00356     // ---------------------------------
00357     
00358     
00359 
00362     struct DataPointsFilter: public Parametrizable
00363     {
00364         DataPointsFilter();
00365         DataPointsFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00366         virtual ~DataPointsFilter();
00367         virtual void init();
00368         
00370         virtual DataPoints filter(const DataPoints& input) = 0;
00371     };
00372     
00374     struct DataPointsFilters: public PointMatcherSupport::SharedPtrVector<DataPointsFilter>
00375     {
00376         DataPointsFilters();
00377         DataPointsFilters(std::istream& in);
00378         void init();
00379         void apply(DataPoints& cloud);
00380     };
00381     typedef typename DataPointsFilters::iterator DataPointsFiltersIt; 
00382     typedef typename DataPointsFilters::const_iterator DataPointsFiltersConstIt; 
00383     
00384     DEF_REGISTRAR(DataPointsFilter)
00385     
00386     // ---------------------------------
00387     
00388     
00389 
00392     struct Matcher: public Parametrizable
00393     {
00394         unsigned long visitCounter; 
00395         
00396         Matcher();
00397         Matcher(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00398         virtual ~Matcher();
00399         
00400         void resetVisitCount();
00401         unsigned long getVisitCount() const;
00402         
00404         virtual void init(const DataPoints& filteredReference) = 0;
00406         virtual Matches findClosests(const DataPoints& filteredReading) = 0;
00407     };
00408     
00409     DEF_REGISTRAR(Matcher)
00410     
00411     // ---------------------------------
00412     
00413     
00414 
00418     struct OutlierFilter: public Parametrizable
00419     {
00420         OutlierFilter();
00421         OutlierFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00422         
00423         virtual ~OutlierFilter();
00424         
00426         virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input) = 0;
00427     };
00428     
00429     
00431     struct OutlierFilters: public PointMatcherSupport::SharedPtrVector<OutlierFilter>
00432     {
00433         
00434         OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00435         
00436     };
00437     
00438     typedef typename OutlierFilters::const_iterator OutlierFiltersConstIt; 
00439     typedef typename OutlierFilters::iterator OutlierFiltersIt; 
00440     
00441     DEF_REGISTRAR(OutlierFilter)
00442 
00443     // ---------------------------------
00444     
00445     
00446 
00449     struct ErrorMinimizer: public Parametrizable
00450     {
00452         struct ErrorElements
00453         {
00454             DataPoints reading; 
00455             DataPoints reference; 
00456             OutlierWeights weights; 
00457             Matches matches; 
00458 
00459             ErrorElements(const DataPoints& reading=DataPoints(), const DataPoints reference = DataPoints(), const OutlierWeights weights = OutlierWeights(), const Matches matches = Matches());
00460         };
00461         
00462         ErrorMinimizer();
00463         ErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00464         virtual ~ErrorMinimizer();
00465         
00466         T getPointUsedRatio() const;
00467         T getWeightedPointUsedRatio() const;
00468         virtual T getOverlap() const;
00469         
00471         virtual TransformationParameters compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches) = 0;
00472         
00473         
00474     protected:
00475         // helper functions
00476         static Matrix crossProduct(const Matrix& A, const Matrix& B);
00477         ErrorElements& getMatchedPoints(const DataPoints& reading, const DataPoints& reference, const Matches& matches, const OutlierWeights& outlierWeights);
00478         
00479     protected:
00480         T pointUsedRatio; 
00481         T weightedPointUsedRatio; 
00482         ErrorElements lastErrorElements; 
00483     };
00484     
00485     DEF_REGISTRAR(ErrorMinimizer)
00486     
00487     // ---------------------------------
00488     
00489     
00490 
00494     struct TransformationChecker: public Parametrizable
00495     {
00496     protected:
00497         typedef std::vector<std::string> StringVector; 
00498         Vector limits; 
00499         Vector conditionVariables; 
00500         StringVector limitNames; 
00501         StringVector conditionVariableNames; 
00502 
00503     public:
00504         TransformationChecker();
00505         TransformationChecker(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00506         virtual ~TransformationChecker();
00508         virtual void init(const TransformationParameters& parameters, bool& iterate) = 0;
00510         virtual void check(const TransformationParameters& parameters, bool& iterate) = 0;
00511         
00512         const Vector& getLimits() const;
00513         const Vector& getConditionVariables() const;
00514         const StringVector& getLimitNames() const;
00515         const StringVector& getConditionVariableNames() const;
00516         
00517     protected:
00518         static Vector matrixToAngles(const TransformationParameters& parameters);
00519     };
00520     
00522     struct TransformationCheckers: public PointMatcherSupport::SharedPtrVector<TransformationChecker>
00523     {
00524         void init(const TransformationParameters& parameters, bool& iterate);
00525         void check(const TransformationParameters& parameters, bool& iterate);
00526     };
00527     typedef typename TransformationCheckers::iterator TransformationCheckersIt; 
00528     typedef typename TransformationCheckers::const_iterator TransformationCheckersConstIt; 
00529     
00530     DEF_REGISTRAR(TransformationChecker)
00531 
00532     // ---------------------------------
00533     
00534     
00535     struct Inspector: public Parametrizable
00536     {
00537         
00538         Inspector();
00539         Inspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00540         
00541         // 
00542         virtual ~Inspector();
00543         virtual void init();
00544         
00545         // performance statistics
00546         virtual void addStat(const std::string& name, double data);
00547         virtual void dumpStats(std::ostream& stream);
00548         virtual void dumpStatsHeader(std::ostream& stream);
00549         
00550         // data statistics 
00551         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);
00552         virtual void finish(const size_t iterationCount);
00553     };
00554     
00555     DEF_REGISTRAR(Inspector) 
00556     
00557     // ---------------------------------
00558     
00559     DEF_REGISTRAR_IFACE(Logger, PointMatcherSupport::Logger)
00560 
00561     // ---------------------------------
00562     
00563     // algorithms
00564     
00566     struct ICPChainBase
00567     {
00568     public:
00569         DataPointsFilters readingDataPointsFilters; 
00570         DataPointsFilters readingStepDataPointsFilters; 
00571         DataPointsFilters referenceDataPointsFilters; 
00572         Transformations transformations; 
00573         std::shared_ptr<Matcher> matcher; 
00574         OutlierFilters outlierFilters; 
00575         std::shared_ptr<ErrorMinimizer> errorMinimizer; 
00576         TransformationCheckers transformationCheckers; 
00577         std::shared_ptr<Inspector> inspector; 
00578         
00579         virtual ~ICPChainBase();
00580 
00581         virtual void setDefault();
00582         
00583         void loadFromYaml(std::istream& in);
00584         unsigned getPrefilteredReadingPtsCount() const;
00585         unsigned getPrefilteredReferencePtsCount() const;
00586         
00587     protected:
00588         unsigned prefilteredReadingPtsCount; 
00589         unsigned prefilteredReferencePtsCount; 
00590 
00591         ICPChainBase();
00592         
00593         void cleanup();
00594         
00595         #ifdef HAVE_YAML_CPP
00596         virtual void loadAdditionalYAMLContent(YAML::Node& doc);
00597         
00598         template<typename R>
00599         const std::string& createModulesFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, PointMatcherSupport::SharedPtrVector<typename R::TargetType>& modules);
00600         
00601         template<typename R>
00602         const std::string& createModuleFromRegistrar(const std::string& regName, const YAML::Node& doc, const R& registrar, std::shared_ptr<typename R::TargetType>& module);
00603         
00604         /*template<typename R>
00605         typename R::TargetType* createModuleFromRegistrar(const YAML::Node& module, const R& registrar);*/
00606         #endif // HAVE_YAML_CPP
00607     };
00608     
00610     struct ICP: ICPChainBase
00611     {
00612         TransformationParameters operator()(
00613             const DataPoints& readingIn,
00614             const DataPoints& referenceIn);
00615 
00616         TransformationParameters operator()(
00617             const DataPoints& readingIn,
00618             const DataPoints& referenceIn,
00619             const TransformationParameters& initialTransformationParameters);
00620         
00621         TransformationParameters compute(
00622             const DataPoints& readingIn,
00623             const DataPoints& referenceIn,
00624             const TransformationParameters& initialTransformationParameters);
00625     
00626     protected:
00627         TransformationParameters computeWithTransformedReference(
00628             const DataPoints& readingIn, 
00629             const DataPoints& reference, 
00630             const TransformationParameters& T_refIn_refMean,
00631             const TransformationParameters& initialTransformationParameters);
00632     };
00633     
00635     struct ICPSequence: public ICP
00636     {
00637         TransformationParameters operator()(
00638             const DataPoints& cloudIn);
00639         TransformationParameters operator()(
00640             const DataPoints& cloudIn,
00641             const TransformationParameters& initialTransformationParameters);
00642         TransformationParameters compute(
00643             const DataPoints& cloudIn,
00644             const TransformationParameters& initialTransformationParameters);
00645         
00646         bool hasMap() const;
00647         bool setMap(const DataPoints& map);
00648         void clearMap();
00649         const DataPoints& getInternalMap() const;
00650         const DataPoints getMap() const;
00651         
00652     protected:
00653         DataPoints mapPointCloud; 
00654         TransformationParameters T_refIn_refMean; 
00655     };
00656     
00657     // ---------------------------------
00658     // Instance-related functions
00659     // ---------------------------------
00660     
00661     PointMatcher();
00662     
00663     static const PointMatcher& get();
00664 
00665     
00666 }; // PointMatcher<T>
00667 
00668 #endif // __POINTMATCHER_CORE_H
00669 


libpointmatcher
Author(s): Stéphane Magnenat, François Pomerleau
autogenerated on Thu Jan 2 2014 11:16:06