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 Francois 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 
00044 //TODO: investigate if that causes more problems down the road
00045 #define EIGEN_NO_DEBUG
00046 
00047 #include "Eigen/StdVector"
00048 #include "Eigen/Core"
00049 #include "Eigen/Geometry"
00050 
00051 
00052 #include <boost/thread/mutex.hpp>
00053 
00054 #include <stdexcept>
00055 #include <limits>
00056 #include <iostream>
00057 #include <ostream>
00058 #include <memory>
00059 //#include <cstdint>
00060 #include <boost/cstdint.hpp>
00061 
00062 #include "DeprecationWarnings.h"
00063 #include "Parametrizable.h"
00064 #include "Registrar.h"
00065  
00072 
00073 #define POINTMATCHER_VERSION "1.3.1"
00074 
00075 #define POINTMATCHER_VERSION_INT 10301
00076 
00078 namespace PointMatcherSupport
00079 {
00080         // TODO: gather all exceptions
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         struct Logger: public Parametrizable
00097         {
00098                 Logger();
00099                 Logger(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00100                 
00101                 virtual ~Logger();
00102                 virtual bool hasInfoChannel() const;
00103                 virtual void beginInfoEntry(const char *file, unsigned line, const char *func);
00104                 virtual std::ostream* infoStream();
00105                 virtual void finishInfoEntry(const char *file, unsigned line, const char *func);
00106                 virtual bool hasWarningChannel() const;
00107                 virtual void beginWarningEntry(const char *file, unsigned line, const char *func);
00108                 virtual std::ostream* warningStream();
00109                 virtual void finishWarningEntry(const char *file, unsigned line, const char *func);
00110         };
00111         
00112         void setLogger(std::shared_ptr<Logger> newLogger);
00113         
00114         void validateFile(const std::string& fileName);
00115         
00117         typedef std::map<std::string, std::vector<std::string> > CsvElements;
00118 }
00119 
00121 template<typename T>
00122 struct PointMatcher
00123 {
00124         // ---------------------------------
00125         // macros for constants
00126         // ---------------------------------
00127         
00129         #define ZERO_PLUS_EPS (0. + std::numeric_limits<double>::epsilon())
00130 
00131         #define ONE_MINUS_EPS (1. - std::numeric_limits<double>::epsilon())
00132         
00133         // ---------------------------------
00134         // exceptions
00135         // ---------------------------------
00136 
00137         //TODO: gather exceptions here and in Exceptions.cpp
00138 
00140         struct ConvergenceError: std::runtime_error
00141         {
00142                 ConvergenceError(const std::string& reason);
00143         };
00144 
00145 
00146         // ---------------------------------
00147         // eigen and nabo-based types
00148         // ---------------------------------
00149         
00151         typedef T ScalarType;
00153         typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
00155         typedef std::vector<Vector, Eigen::aligned_allocator<Vector> > VectorVector;
00157         typedef typename Eigen::Quaternion<T> Quaternion;
00159         typedef std::vector<Quaternion, Eigen::aligned_allocator<Quaternion> > QuaternionVector;
00161         typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
00163         typedef typename Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic> IntMatrix;
00165         typedef typename Eigen::Matrix<std::int64_t, Eigen::Dynamic, Eigen::Dynamic> Int64Matrix;
00167         typedef typename Eigen::Array<T, Eigen::Dynamic, Eigen::Dynamic> Array;
00168 
00169 
00171 
00174         typedef Matrix TransformationParameters;
00175         
00176         // alias for scope reasons
00177         typedef PointMatcherSupport::Parametrizable Parametrizable; 
00178         typedef Parametrizable::Parameters Parameters; 
00179         typedef Parametrizable::ParameterDoc ParameterDoc; 
00180         typedef Parametrizable::ParametersDoc ParametersDoc; 
00181         typedef Parametrizable::InvalidParameter InvalidParameter; 
00182         
00183         // ---------------------------------
00184         // input types
00185         // ---------------------------------
00186         
00188 
00199         struct DataPoints
00200         {
00202                 typedef Eigen::Block<Matrix> View;
00204                 typedef Eigen::Block<Int64Matrix> TimeView;
00206                 typedef const Eigen::Block<const Matrix> ConstView;
00208                 typedef const Eigen::Block<const Int64Matrix> TimeConstView;
00210                 typedef typename Matrix::Index Index;
00211                 
00213                 struct Label
00214                 {
00215                         std::string text; 
00216                         size_t span; 
00217                         Label(const std::string& text = "", const size_t span = 0);
00218                         bool operator ==(const Label& that) const;
00219                 };
00221                 struct Labels: std::vector<Label>
00222                 {
00223                         typedef typename std::vector<Label>::const_iterator const_iterator; 
00224                         Labels();
00225                         Labels(const Label& label);
00226                         bool contains(const std::string& text) const;
00227                         size_t totalDim() const;
00228                         friend std::ostream& operator<< (std::ostream& stream, const Labels& labels)
00229                         {
00230                                 for(size_t i=0; i<labels.size(); i++)
00231                                 {
00232                                         stream << labels[i].text;
00233                                         if(i != (labels.size() -1))
00234                                                 stream << ", ";
00235                                 }
00236 
00237                                 return stream;
00238                         };
00239                 };
00240                 
00242                 struct InvalidField: std::runtime_error
00243                 {
00244                         InvalidField(const std::string& reason);
00245                 };
00246                 
00247                 // Constructors from descriptions (reserve memory)
00248                 DataPoints();
00249                 DataPoints(const Labels& featureLabels, const Labels& descriptorLabels, const size_t pointCount);
00250                 DataPoints(const Labels& featureLabels, const Labels& descriptorLabels, const Labels& timeLabels, const size_t pointCount);
00251 
00252                 // Copy constructors from partial data
00253                 DataPoints(const Matrix& features, const Labels& featureLabels);
00254                 DataPoints(const Matrix& features, const Labels& featureLabels, const Matrix& descriptors, const Labels& descriptorLabels);
00255                 DataPoints(const Matrix& features, const Labels& featureLabels, const Matrix& descriptors, const Labels& descriptorLabels, const Int64Matrix& times, const Labels& timeLabels);
00256                 
00257                 bool operator ==(const DataPoints& that) const;
00258         
00259                 unsigned getNbPoints() const;
00260                 unsigned getEuclideanDim() const;
00261                 unsigned getHomogeneousDim() const;
00262                 unsigned getNbGroupedDescriptors() const;
00263                 unsigned getDescriptorDim() const;
00264                 unsigned getTimeDim() const;
00265 
00266                 void save(const std::string& fileName, bool binary = false) const;
00267                 static DataPoints load(const std::string& fileName);
00268                 
00269                 void concatenate(const DataPoints& dp);
00270                 void conservativeResize(Index pointCount);
00271                 DataPoints createSimilarEmpty() const;
00272                 DataPoints createSimilarEmpty(Index pointCount) const;
00273                 void setColFrom(Index thisCol, const DataPoints& that, Index thatCol);
00274                 void swapCols(Index iCol,Index jCol);
00275                 
00276                 // methods related to features
00277                 void allocateFeature(const std::string& name, const unsigned dim);
00278                 void allocateFeatures(const Labels& newLabels);
00279                 void addFeature(const std::string& name, const Matrix& newFeature);
00280                 void removeFeature(const std::string& name);
00281                 Matrix getFeatureCopyByName(const std::string& name) const;
00282                 ConstView getFeatureViewByName(const std::string& name) const;
00283                 View getFeatureViewByName(const std::string& name);
00284                 ConstView getFeatureRowViewByName(const std::string& name, const unsigned row) const;
00285                 View getFeatureRowViewByName(const std::string& name, const unsigned row);
00286                 bool featureExists(const std::string& name) const;
00287                 bool featureExists(const std::string& name, const unsigned dim) const;
00288                 unsigned getFeatureDimension(const std::string& name) const;
00289                 unsigned getFeatureStartingRow(const std::string& name) const;
00290                 
00291                 // methods related to descriptors
00292                 void allocateDescriptor(const std::string& name, const unsigned dim);
00293                 void allocateDescriptors(const Labels& newLabels);
00294                 void addDescriptor(const std::string& name, const Matrix& newDescriptor);
00295                 void removeDescriptor(const std::string& name);
00296                 Matrix getDescriptorCopyByName(const std::string& name) const;
00297                 ConstView getDescriptorViewByName(const std::string& name) const;
00298                 View getDescriptorViewByName(const std::string& name);
00299                 ConstView getDescriptorRowViewByName(const std::string& name, const unsigned row) const;
00300                 View getDescriptorRowViewByName(const std::string& name, const unsigned row);
00301                 bool descriptorExists(const std::string& name) const;
00302                 bool descriptorExists(const std::string& name, const unsigned dim) const;
00303                 unsigned getDescriptorDimension(const std::string& name) const;
00304                 unsigned getDescriptorStartingRow(const std::string& name) const;
00305                 void assertDescriptorConsistency() const;
00306                 
00307                 // methods related to times
00308                 void allocateTime(const std::string& name, const unsigned dim);
00309                 void allocateTimes(const Labels& newLabels);
00310                 void addTime(const std::string& name, const Int64Matrix& newTime);
00311                 void removeTime(const std::string& name);
00312                 Int64Matrix getTimeCopyByName(const std::string& name) const;
00313                 TimeConstView getTimeViewByName(const std::string& name) const;
00314                 TimeView getTimeViewByName(const std::string& name);
00315                 TimeConstView getTimeRowViewByName(const std::string& name, const unsigned row) const;
00316                 TimeView getTimeRowViewByName(const std::string& name, const unsigned row);
00317                 bool timeExists(const std::string& name) const;
00318                 bool timeExists(const std::string& name, const unsigned dim) const;
00319                 unsigned getTimeDimension(const std::string& name) const;
00320                 unsigned getTimeStartingRow(const std::string& name) const;
00321                 void assertTimesConsistency() const;
00322 
00323                 Matrix features; 
00324                 Labels featureLabels; 
00325                 Matrix descriptors; 
00326                 Labels descriptorLabels; 
00327                 Int64Matrix times; 
00328                 Labels timeLabels; 
00329         
00330         private:
00331                 void assertConsistency(const std::string& dataName, const int dataRows, const int dataCols, const Labels& labels) const;
00332                 template<typename MatrixType> 
00333                 void allocateFields(const Labels& newLabels, Labels& labels, MatrixType& data) const;
00334                 template<typename MatrixType> 
00335                 void allocateField(const std::string& name, const unsigned dim, Labels& labels, MatrixType& data) const;
00336                 template<typename MatrixType> 
00337                 void addField(const std::string& name, const MatrixType& newField, Labels& labels, MatrixType& data) const;
00338                 template<typename MatrixType>
00339                 void removeField(const std::string& name, Labels& labels, MatrixType& data) const;
00340                 template<typename MatrixType>
00341                 const Eigen::Block<const MatrixType> getConstViewByName(const std::string& name, const Labels& labels, const MatrixType& data, const int viewRow = -1) const;
00342                 template<typename MatrixType>
00343                 Eigen::Block<MatrixType> getViewByName(const std::string& name, const Labels& labels, MatrixType& data, const int viewRow = -1) const;
00344                 bool fieldExists(const std::string& name, const unsigned dim, const Labels& labels) const;
00345                 unsigned getFieldDimension(const std::string& name, const Labels& labels) const;
00346                 unsigned getFieldStartingRow(const std::string& name, const Labels& labels) const;
00347 
00348                 template<typename MatrixType>
00349                 void concatenateLabelledMatrix(Labels* labels, MatrixType* data, const Labels extraLabels, const MatrixType extraData);
00350         };
00351         
00352         static void swapDataPoints(DataPoints& a, DataPoints& b);
00353 
00354         // ---------------------------------
00355         // intermediate types
00356         // ---------------------------------
00357         
00359 
00363         struct Matches
00364         {
00365                 typedef Matrix Dists; 
00366                 typedef IntMatrix Ids; 
00367         
00368 
00369                 static constexpr int InvalidId = -1; 
00370                 static constexpr T InvalidDist = std::numeric_limits<T>::infinity(); 
00371 
00372                 Matches();
00373                 Matches(const Dists& dists, const Ids ids);
00374                 Matches(const int knn, const int pointsCount);
00375                 
00376                 Dists dists; 
00377                 Ids ids; 
00378                 
00379                 T getDistsQuantile(const T quantile) const;
00380                 T getMedianAbsDeviation() const;
00381                 T getStandardDeviation() const;
00382 
00383         };
00384 
00386 
00389         typedef Matrix OutlierWeights;
00390         
00391         // ---------------------------------
00392         // types of processing bricks
00393         // ---------------------------------
00394         
00396         struct Transformation: public Parametrizable
00397         {
00398                 Transformation();
00399                 Transformation(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00400                 virtual ~Transformation();
00401                 
00403                 virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const = 0; 
00404 
00406                 virtual bool checkParameters(const TransformationParameters& parameters) const = 0;
00407 
00409                 virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const = 0;
00410 
00411         };
00412         
00414         struct Transformations: public std::vector<std::shared_ptr<Transformation> >
00415         {
00416                 void apply(DataPoints& cloud, const TransformationParameters& parameters) const;
00417         };
00418         typedef typename Transformations::iterator TransformationsIt; 
00419         typedef typename Transformations::const_iterator TransformationsConstIt; 
00420         
00421         DEF_REGISTRAR(Transformation)
00422         
00423         // ---------------------------------
00424         
00425         
00426 
00429         struct DataPointsFilter: public Parametrizable
00430         {
00431                 DataPointsFilter();
00432                 DataPointsFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00433                 virtual ~DataPointsFilter();
00434                 virtual void init();
00435 
00437                 virtual DataPoints filter(const DataPoints& input) = 0;
00438 
00440                 virtual void inPlaceFilter(DataPoints& cloud) = 0;
00441         };
00442         
00444         struct DataPointsFilters: public std::vector<std::shared_ptr<DataPointsFilter> >
00445         {
00446                 DataPointsFilters();
00447                 DataPointsFilters(std::istream& in);
00448                 void init();
00449                 void apply(DataPoints& cloud);
00450         };
00451         typedef typename DataPointsFilters::iterator DataPointsFiltersIt; 
00452         typedef typename DataPointsFilters::const_iterator DataPointsFiltersConstIt; 
00453         
00454         DEF_REGISTRAR(DataPointsFilter)
00455         
00456         // ---------------------------------
00457         
00458         
00459 
00462         struct Matcher: public Parametrizable
00463         {
00464                 unsigned long visitCounter; 
00465                 
00466                 Matcher();
00467                 Matcher(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00468                 virtual ~Matcher();
00469                 
00470                 void resetVisitCount();
00471                 unsigned long getVisitCount() const;
00472                 
00474                 virtual void init(const DataPoints& filteredReference) = 0;
00476                 virtual Matches findClosests(const DataPoints& filteredReading) = 0;
00477         };
00478         
00479         DEF_REGISTRAR(Matcher)
00480         
00481         // ---------------------------------
00482         
00483         
00484 
00488         struct OutlierFilter: public Parametrizable
00489         {
00490                 OutlierFilter();
00491                 OutlierFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00492                 
00493                 virtual ~OutlierFilter();
00494                 
00496                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input) = 0;
00497         };
00498         
00499         
00501         struct OutlierFilters: public std::vector<std::shared_ptr<OutlierFilter> >
00502         {
00503                 
00504                 OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00505                 
00506         };
00507         
00508         typedef typename OutlierFilters::const_iterator OutlierFiltersConstIt; 
00509         typedef typename OutlierFilters::iterator OutlierFiltersIt; 
00510         
00511         DEF_REGISTRAR(OutlierFilter)
00512 
00513         // ---------------------------------
00514         
00515         
00516 
00519         struct ErrorMinimizer: public Parametrizable
00520         {
00522                 struct ErrorElements
00523                 {
00524                         DataPoints reading; 
00525                         DataPoints reference; 
00526                         OutlierWeights weights; 
00527                         Matches matches; 
00528                         int nbRejectedMatches; 
00529                         int nbRejectedPoints; 
00530                         T pointUsedRatio;  
00531                         T weightedPointUsedRatio;
00532 
00533                         ErrorElements();
00534                         ErrorElements(const DataPoints& requestedPts, const DataPoints& sourcePts, const OutlierWeights& outlierWeights, const Matches& matches);
00535                 };
00536                 
00537                 ErrorMinimizer();
00538                 ErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00539                 virtual ~ErrorMinimizer();
00540                 
00541                 T getPointUsedRatio() const;
00542                 T getWeightedPointUsedRatio() const;
00543                 ErrorElements getErrorElements() const; //TODO: ensure that is return a usable value
00544                 virtual T getOverlap() const;
00545                 virtual Matrix getCovariance() const;
00546                 virtual T getResidualError(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches) const;
00547                 
00549                 virtual TransformationParameters compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches);
00551                 virtual TransformationParameters compute(const ErrorElements& matchedPoints) = 0;
00552                 
00553                 // helper functions
00554                 static Matrix crossProduct(const Matrix& A, const Matrix& B);//TODO: this might go in pointmatcher_support namespace
00555                 
00556         protected:
00557                 //T pointUsedRatio; //!< the ratio of how many points were used for error minimization
00558                 //T weightedPointUsedRatio; //!< the ratio of how many points were used (with weight) for error minimization
00559                 //TODO: standardize the use of this variable
00560                 ErrorElements lastErrorElements; 
00561         };
00562         
00563         DEF_REGISTRAR(ErrorMinimizer)
00564         
00565         // ---------------------------------
00566         
00567         
00568 
00572         struct TransformationChecker: public Parametrizable
00573         {
00574         protected:
00575                 typedef std::vector<std::string> StringVector; 
00576                 Vector limits; 
00577                 Vector conditionVariables; 
00578                 StringVector limitNames; 
00579                 StringVector conditionVariableNames; 
00580 
00581         public:
00582                 TransformationChecker();
00583                 TransformationChecker(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00584                 virtual ~TransformationChecker();
00586                 virtual void init(const TransformationParameters& parameters, bool& iterate) = 0;
00588                 virtual void check(const TransformationParameters& parameters, bool& iterate) = 0;
00589                 
00590                 const Vector& getLimits() const;
00591                 const Vector& getConditionVariables() const;
00592                 const StringVector& getLimitNames() const;
00593                 const StringVector& getConditionVariableNames() const;
00594                 
00595         protected:
00596                 static Vector matrixToAngles(const TransformationParameters& parameters);
00597         };
00598         
00600         struct TransformationCheckers: public std::vector<std::shared_ptr<TransformationChecker> >
00601         {
00602                 void init(const TransformationParameters& parameters, bool& iterate);
00603                 void check(const TransformationParameters& parameters, bool& iterate);
00604         };
00605         typedef typename TransformationCheckers::iterator TransformationCheckersIt; 
00606         typedef typename TransformationCheckers::const_iterator TransformationCheckersConstIt; 
00607         
00608         DEF_REGISTRAR(TransformationChecker)
00609 
00610         // ---------------------------------
00611         
00612         
00613         struct Inspector: public Parametrizable
00614         {
00615                 
00616                 Inspector();
00617                 Inspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00618                 
00619                 // 
00620                 virtual ~Inspector();
00621                 virtual void init();
00622                 
00623                 // performance statistics
00624                 virtual void addStat(const std::string& name, double data);
00625                 virtual void dumpStats(std::ostream& stream);
00626                 virtual void dumpStatsHeader(std::ostream& stream);
00627                 
00628                 // data statistics 
00629                 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);
00630                 virtual void finish(const size_t iterationCount);
00631         };
00632         
00633         DEF_REGISTRAR(Inspector) 
00634         
00635         // ---------------------------------
00636         
00637         DEF_REGISTRAR_IFACE(Logger, PointMatcherSupport::Logger)
00638 
00639         // ---------------------------------
00640         
00641         // algorithms
00642         
00644         struct ICPChainBase
00645         {
00646         public:
00647                 DataPointsFilters readingDataPointsFilters; 
00648                 DataPointsFilters readingStepDataPointsFilters; 
00649                 DataPointsFilters referenceDataPointsFilters; 
00650                 Transformations transformations; 
00651                 std::shared_ptr<Matcher> matcher; 
00652                 OutlierFilters outlierFilters; 
00653                 std::shared_ptr<ErrorMinimizer> errorMinimizer; 
00654                 TransformationCheckers transformationCheckers; 
00655                 std::shared_ptr<Inspector> inspector; 
00656                 
00657                 virtual ~ICPChainBase();
00658 
00659                 virtual void setDefault();
00660                 
00661                 void loadFromYaml(std::istream& in);
00662                 unsigned getPrefilteredReadingPtsCount() const;
00663                 unsigned getPrefilteredReferencePtsCount() const;
00664 
00665                 bool getMaxNumIterationsReached() const;
00666                 
00667         protected:
00668                 unsigned prefilteredReadingPtsCount; 
00669                 unsigned prefilteredReferencePtsCount; 
00670                 bool maxNumIterationsReached; 
00671 
00672                 ICPChainBase();
00673                 
00674                 void cleanup();
00675                 
00676         virtual void loadAdditionalYAMLContent(PointMatcherSupport::YAML::Node& doc);
00677                 
00679                 template<typename R>
00680         const std::string& createModulesFromRegistrar(const std::string& regName, const PointMatcherSupport::YAML::Node& doc, const R& registrar, std::vector<std::shared_ptr<typename R::TargetType> >& modules);
00681                 
00683                 template<typename R>
00684         const std::string& createModuleFromRegistrar(const std::string& regName, const PointMatcherSupport::YAML::Node& doc, const R& registrar, std::shared_ptr<typename R::TargetType>& module);
00685                 
00687         std::string nodeVal(const std::string& regName, const PointMatcherSupport::YAML::Node& doc);
00688         };
00689         
00691         struct ICP: ICPChainBase
00692         {
00693                 TransformationParameters operator()(
00694                         const DataPoints& readingIn,
00695                         const DataPoints& referenceIn);
00696 
00697                 TransformationParameters operator()(
00698                         const DataPoints& readingIn,
00699                         const DataPoints& referenceIn,
00700                         const TransformationParameters& initialTransformationParameters);
00701                 
00702                 TransformationParameters compute(
00703                         const DataPoints& readingIn,
00704                         const DataPoints& referenceIn,
00705                         const TransformationParameters& initialTransformationParameters);
00706 
00708                 const DataPoints& getReadingFiltered() const { return readingFiltered; }
00709 
00710         protected:
00711                 TransformationParameters computeWithTransformedReference(
00712                         const DataPoints& readingIn, 
00713                         const DataPoints& reference, 
00714                         const TransformationParameters& T_refIn_refMean,
00715                         const TransformationParameters& initialTransformationParameters);
00716 
00717                 DataPoints readingFiltered; 
00718         };
00719         
00722         struct ICPSequence: public ICP
00723         {
00724                 TransformationParameters operator()(
00725                         const DataPoints& cloudIn);
00726                 TransformationParameters operator()(
00727                         const DataPoints& cloudIn,
00728                         const TransformationParameters& initialTransformationParameters);
00729                 TransformationParameters compute(
00730                         const DataPoints& cloudIn,
00731                         const TransformationParameters& initialTransformationParameters);
00732                 
00733                 bool hasMap() const;
00734                 bool setMap(const DataPoints& map);
00735                 void clearMap();
00736                 PM_DEPRECATED("Use getPrefilteredInternalMap instead. "
00737                                     "Function now always returns map with filter chain applied. "
00738                                     "This may have altered your program behavior."
00739                               "Reasons for this stated here and in associated PR: "
00740                               "https://github.com/ethz-asl/libpointmatcher/issues/209.")
00741                 const DataPoints& getInternalMap() const;
00742                 const DataPoints& getPrefilteredInternalMap() const;
00743                 PM_DEPRECATED("Use getPrefilteredMap instead. "
00744                                                                         "Function now always returns map with filter chain applied. "
00745                                     "This may have altered your program behavior."
00746                                     "Reasons for this stated here and in associated PR: "
00747                                     "https://github.com/ethz-asl/libpointmatcher/issues/209")
00748                 const DataPoints getMap() const;
00749                 const DataPoints getPrefilteredMap() const;
00750                 
00751         protected:
00752                 DataPoints mapPointCloud; 
00753                 TransformationParameters T_refIn_refMean; 
00754         };
00755         
00756         // ---------------------------------
00757         // Instance-related functions
00758         // ---------------------------------
00759         
00760         PointMatcher();
00761         
00762         static const PointMatcher& get();
00763 
00764         
00765 }; // PointMatcher<T>
00766 
00767 #endif // __POINTMATCHER_CORE_H
00768 


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:32