PointMatcher.h
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2012,
6 Francois Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
7 You can contact the authors at <f dot pomerleau at gmail dot com> and
8 <stephane at magnenat dot net>
9 
10 All rights reserved.
11 
12 Redistribution and use in source and binary forms, with or without
13 modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of the <organization> nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
27 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 
34 */
35 
36 #ifndef __POINTMATCHER_CORE_H
37 #define __POINTMATCHER_CORE_H
38 
39 #ifndef EIGEN_USE_NEW_STDVECTOR
40 #define EIGEN_USE_NEW_STDVECTOR
41 #endif // EIGEN_USE_NEW_STDVECTOR
42 //#define EIGEN2_SUPPORT
43 
44 //TODO: investigate if that causes more problems down the road
45 #define EIGEN_NO_DEBUG
46 
47 #include "Eigen/StdVector"
48 #include "Eigen/Core"
49 #include "Eigen/Geometry"
50 
51 
52 #include <boost/thread/mutex.hpp>
53 
54 #include <stdexcept>
55 #include <limits>
56 #include <iostream>
57 #include <ostream>
58 #include <memory>
59 //#include <cstdint>
60 #include <boost/cstdint.hpp>
61 
62 #include "DeprecationWarnings.h"
63 #include "Parametrizable.h"
64 #include "Registrar.h"
65 
72 #define POINTMATCHER_VERSION "1.3.1"
74 #define POINTMATCHER_VERSION_INT 10301
76 
78 namespace PointMatcherSupport
79 {
80  // TODO: gather all exceptions
81 
83  struct InvalidModuleType: std::runtime_error
84  {
85  InvalidModuleType(const std::string& reason);
86  };
87 
89  struct TransformationError: std::runtime_error
90  {
92  TransformationError(const std::string& reason);
93  };
94 
96  struct ConfigurationError: std::runtime_error
97  {
99  ConfigurationError(const std::string& reason);
100  };
101 
102 
104  struct Logger: public Parametrizable
105  {
106  Logger();
107  Logger(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
108 
109  virtual ~Logger();
110  virtual bool hasInfoChannel() const;
111  virtual void beginInfoEntry(const char *file, unsigned line, const char *func);
112  virtual std::ostream* infoStream();
113  virtual void finishInfoEntry(const char *file, unsigned line, const char *func);
114  virtual bool hasWarningChannel() const;
115  virtual void beginWarningEntry(const char *file, unsigned line, const char *func);
116  virtual std::ostream* warningStream();
117  virtual void finishWarningEntry(const char *file, unsigned line, const char *func);
118  };
119 
120  void setLogger(std::shared_ptr<Logger> newLogger);
121 
122  void validateFile(const std::string& fileName);
123 
125  typedef std::map<std::string, std::vector<std::string> > CsvElements;
126 }
127 
129 template<typename T>
131 {
132  // ---------------------------------
133  // macros for constants
134  // ---------------------------------
135 
137  #define ZERO_PLUS_EPS (0. + std::numeric_limits<double>::epsilon())
138  #define ONE_MINUS_EPS (1. - std::numeric_limits<double>::epsilon())
140 
141  // ---------------------------------
142  // exceptions
143  // ---------------------------------
144 
145  //TODO: gather exceptions here and in Exceptions.cpp
146 
148  struct ConvergenceError: std::runtime_error
149  {
150  ConvergenceError(const std::string& reason);
151  };
152 
153 
154  // ---------------------------------
155  // eigen and nabo-based types
156  // ---------------------------------
157 
159  typedef T ScalarType;
161  typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
163  typedef std::vector<Vector, Eigen::aligned_allocator<Vector> > VectorVector;
165  typedef typename Eigen::Quaternion<T> Quaternion;
167  typedef std::vector<Quaternion, Eigen::aligned_allocator<Quaternion> > QuaternionVector;
169  typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
171  typedef typename Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic> IntMatrix;
173  typedef typename Eigen::Matrix<std::int64_t, Eigen::Dynamic, Eigen::Dynamic> Int64Matrix;
175  typedef typename Eigen::Array<T, Eigen::Dynamic, Eigen::Dynamic> Array;
176 
177 
179 
183 
184  // alias for scope reasons
190 
191  // ---------------------------------
192  // input types
193  // ---------------------------------
194 
196 
207  struct DataPoints
208  {
210  typedef Eigen::Block<Matrix> View;
212  typedef Eigen::Block<Int64Matrix> TimeView;
214  typedef const Eigen::Block<const Matrix> ConstView;
216  typedef const Eigen::Block<const Int64Matrix> TimeConstView;
218  typedef typename Matrix::Index Index;
219 
221  struct Label
222  {
224  size_t span;
225  Label(const std::string& text = "", const size_t span = 0);
226  bool operator ==(const Label& that) const;
227  };
229  struct Labels: std::vector<Label>
230  {
231  typedef typename std::vector<Label>::const_iterator const_iterator;
232  Labels();
233  Labels(const Label& label);
234  bool contains(const std::string& text) const;
235  size_t totalDim() const;
236  friend std::ostream& operator<< (std::ostream& stream, const Labels& labels)
237  {
238  for(size_t i=0; i<labels.size(); i++)
239  {
240  stream << labels[i].text;
241  if(i != (labels.size() -1))
242  stream << ", ";
243  }
244 
245  return stream;
246  };
247  };
248 
250  struct InvalidField: std::runtime_error
251  {
252  InvalidField(const std::string& reason);
253  };
254 
255  // Constructors from descriptions (reserve memory)
256  DataPoints();
257  DataPoints(const Labels& featureLabels, const Labels& descriptorLabels, const size_t pointCount);
258  DataPoints(const Labels& featureLabels, const Labels& descriptorLabels, const Labels& timeLabels, const size_t pointCount);
259 
260  // Copy constructors from partial data
264 
265  bool operator ==(const DataPoints& that) const;
266 
267  unsigned getNbPoints() const;
268  unsigned getEuclideanDim() const;
269  unsigned getHomogeneousDim() const;
270  unsigned getNbGroupedDescriptors() const;
271  unsigned getDescriptorDim() const;
272  unsigned getTimeDim() const;
273 
274  void save(const std::string& fileName, bool binary = false) const;
275  static DataPoints load(const std::string& fileName);
276 
277  void concatenate(const DataPoints& dp);
278  void conservativeResize(Index pointCount);
280  DataPoints createSimilarEmpty(Index pointCount) const;
281  void setColFrom(Index thisCol, const DataPoints& that, Index thatCol);
282  void swapCols(Index iCol,Index jCol);
283 
284  // methods related to features
285  void allocateFeature(const std::string& name, const unsigned dim);
286  void allocateFeatures(const Labels& newLabels);
287  void addFeature(const std::string& name, const Matrix& newFeature);
288  void removeFeature(const std::string& name);
289  Matrix getFeatureCopyByName(const std::string& name) const;
290  ConstView getFeatureViewByName(const std::string& name) const;
292  ConstView getFeatureRowViewByName(const std::string& name, const unsigned row) const;
293  View getFeatureRowViewByName(const std::string& name, const unsigned row);
294  bool featureExists(const std::string& name) const;
295  bool featureExists(const std::string& name, const unsigned dim) const;
296  unsigned getFeatureDimension(const std::string& name) const;
297  unsigned getFeatureStartingRow(const std::string& name) const;
298 
299  // methods related to descriptors
300  void allocateDescriptor(const std::string& name, const unsigned dim);
301  void allocateDescriptors(const Labels& newLabels);
302  void addDescriptor(const std::string& name, const Matrix& newDescriptor);
303  void removeDescriptor(const std::string& name);
304  Matrix getDescriptorCopyByName(const std::string& name) const;
305  ConstView getDescriptorViewByName(const std::string& name) const;
307  ConstView getDescriptorRowViewByName(const std::string& name, const unsigned row) const;
308  View getDescriptorRowViewByName(const std::string& name, const unsigned row);
309  bool descriptorExists(const std::string& name) const;
310  bool descriptorExists(const std::string& name, const unsigned dim) const;
311  unsigned getDescriptorDimension(const std::string& name) const;
312  unsigned getDescriptorStartingRow(const std::string& name) const;
313  void assertDescriptorConsistency() const;
314 
315  // methods related to times
316  void allocateTime(const std::string& name, const unsigned dim);
317  void allocateTimes(const Labels& newLabels);
318  void addTime(const std::string& name, const Int64Matrix& newTime);
319  void removeTime(const std::string& name);
320  Int64Matrix getTimeCopyByName(const std::string& name) const;
321  TimeConstView getTimeViewByName(const std::string& name) const;
323  TimeConstView getTimeRowViewByName(const std::string& name, const unsigned row) const;
324  TimeView getTimeRowViewByName(const std::string& name, const unsigned row);
325  bool timeExists(const std::string& name) const;
326  bool timeExists(const std::string& name, const unsigned dim) const;
327  unsigned getTimeDimension(const std::string& name) const;
328  unsigned getTimeStartingRow(const std::string& name) const;
329  void assertTimesConsistency() const;
330 
337 
338  private:
339  void assertConsistency(const std::string& dataName, const int dataRows, const int dataCols, const Labels& labels) const;
340  template<typename MatrixType>
341  void allocateFields(const Labels& newLabels, Labels& labels, MatrixType& data) const;
342  template<typename MatrixType>
343  void allocateField(const std::string& name, const unsigned dim, Labels& labels, MatrixType& data) const;
344  template<typename MatrixType>
345  void addField(const std::string& name, const MatrixType& newField, Labels& labels, MatrixType& data) const;
346  template<typename MatrixType>
347  void removeField(const std::string& name, Labels& labels, MatrixType& data) const;
348  template<typename MatrixType>
349  const Eigen::Block<const MatrixType> getConstViewByName(const std::string& name, const Labels& labels, const MatrixType& data, const int viewRow = -1) const;
350  template<typename MatrixType>
351  Eigen::Block<MatrixType> getViewByName(const std::string& name, const Labels& labels, MatrixType& data, const int viewRow = -1) const;
352  bool fieldExists(const std::string& name, const unsigned dim, const Labels& labels) const;
353  unsigned getFieldDimension(const std::string& name, const Labels& labels) const;
354  unsigned getFieldStartingRow(const std::string& name, const Labels& labels) const;
355 
356  template<typename MatrixType>
357  void concatenateLabelledMatrix(Labels* labels, MatrixType* data, const Labels extraLabels, const MatrixType extraData);
358  };
359 
360  static void swapDataPoints(DataPoints& a, DataPoints& b);
361 
362  // ---------------------------------
363  // intermediate types
364  // ---------------------------------
365 
367 
371  struct Matches
372  {
373  typedef Matrix Dists;
374  typedef IntMatrix Ids;
375 
376 
377  static constexpr int InvalidId = -1;
378  static constexpr T InvalidDist = std::numeric_limits<T>::infinity();
379 
380  Matches();
381  Matches(const Dists& dists, const Ids ids);
382  Matches(const int knn, const int pointsCount);
383 
386 
387  T getDistsQuantile(const T quantile) const;
388  T getMedianAbsDeviation() const;
389  T getStandardDeviation() const;
390 
391  };
392 
394 
398 
399  // ---------------------------------
400  // types of processing bricks
401  // ---------------------------------
402 
405  {
406  Transformation();
407  Transformation(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
408  virtual ~Transformation();
409 
411  virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const = 0;
412 
414  virtual bool checkParameters(const TransformationParameters& parameters) const = 0;
415 
418 
419  };
420 
422  struct Transformations: public std::vector<std::shared_ptr<Transformation> >
423  {
424  void apply(DataPoints& cloud, const TransformationParameters& parameters) const;
425  };
426  typedef typename Transformations::iterator TransformationsIt;
427  typedef typename Transformations::const_iterator TransformationsConstIt;
428 
429  DEF_REGISTRAR(Transformation)
430 
431  // ---------------------------------
432 
433 
434 
438  {
440  DataPointsFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
441  virtual ~DataPointsFilter();
442  virtual void init();
443 
445  virtual DataPoints filter(const DataPoints& input) = 0;
446 
448  virtual void inPlaceFilter(DataPoints& cloud) = 0;
449  };
450 
452  struct DataPointsFilters: public std::vector<std::shared_ptr<DataPointsFilter> >
453  {
455  DataPointsFilters(std::istream& in);
456  void init();
457  void apply(DataPoints& cloud);
458  };
459  typedef typename DataPointsFilters::iterator DataPointsFiltersIt;
460  typedef typename DataPointsFilters::const_iterator DataPointsFiltersConstIt;
461 
462  DEF_REGISTRAR(DataPointsFilter)
463 
464  // ---------------------------------
465 
466 
467 
470  struct Matcher: public Parametrizable
471  {
472  unsigned long visitCounter;
473 
474  Matcher();
475  Matcher(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
476  virtual ~Matcher();
477 
478  void resetVisitCount();
479  unsigned long getVisitCount() const;
480 
482  virtual void init(const DataPoints& filteredReference) = 0;
484  virtual Matches findClosests(const DataPoints& filteredReading) = 0;
485  };
486 
488 
489  // ---------------------------------
490 
491 
492 
497  {
498  OutlierFilter();
499  OutlierFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
500 
501  virtual ~OutlierFilter();
502 
504  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input) = 0;
505  };
506 
507 
509  struct OutlierFilters: public std::vector<std::shared_ptr<OutlierFilter> >
510  {
511 
512  OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
513 
514  };
515 
516  typedef typename OutlierFilters::const_iterator OutlierFiltersConstIt;
517  typedef typename OutlierFilters::iterator OutlierFiltersIt;
518 
519  DEF_REGISTRAR(OutlierFilter)
520 
521  // ---------------------------------
522 
523 
524 
528  {
531  {
540 
541  ErrorElements();
542  ErrorElements(const DataPoints& requestedPts, const DataPoints& sourcePts, const OutlierWeights& outlierWeights, const Matches& matches);
543  };
544 
545  ErrorMinimizer();
546  ErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
547  virtual ~ErrorMinimizer();
548 
549  T getPointUsedRatio() const;
550  T getWeightedPointUsedRatio() const;
551  ErrorElements getErrorElements() const; //TODO: ensure that is return a usable value
552  virtual T getOverlap() const;
553  virtual Matrix getCovariance() const;
554  virtual T getResidualError(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches) const;
555 
557  virtual TransformationParameters compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches);
559  virtual TransformationParameters compute(const ErrorElements& matchedPoints) = 0;
560 
561  // helper functions
562  static Matrix crossProduct(const Matrix& A, const Matrix& B);//TODO: this might go in pointmatcher_support namespace
563 
564  protected:
565  //T pointUsedRatio; //!< the ratio of how many points were used for error minimization
566  //T weightedPointUsedRatio; //!< the ratio of how many points were used (with weight) for error minimization
567  //TODO: standardize the use of this variable
569  };
570 
572 
573  // ---------------------------------
574 
575 
576 
581  {
582  protected:
583  typedef std::vector<std::string> StringVector;
588 
589  public:
591  TransformationChecker(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
592  virtual ~TransformationChecker();
594  virtual void init(const TransformationParameters& parameters, bool& iterate) = 0;
596  virtual void check(const TransformationParameters& parameters, bool& iterate) = 0;
597 
598  const Vector& getLimits() const;
599  const Vector& getConditionVariables() const;
600  const StringVector& getLimitNames() const;
601  const StringVector& getConditionVariableNames() const;
602 
603  protected:
604  static Vector matrixToAngles(const TransformationParameters& parameters);
605  };
606 
608  struct TransformationCheckers: public std::vector<std::shared_ptr<TransformationChecker> >
609  {
610  void init(const TransformationParameters& parameters, bool& iterate);
611  void check(const TransformationParameters& parameters, bool& iterate);
612  };
613  typedef typename TransformationCheckers::iterator TransformationCheckersIt;
614  typedef typename TransformationCheckers::const_iterator TransformationCheckersConstIt;
615 
616  DEF_REGISTRAR(TransformationChecker)
617 
618  // ---------------------------------
619 
620 
621  struct Inspector: public Parametrizable
622  {
623 
624  Inspector();
625  Inspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
626 
627  //
628  virtual ~Inspector();
629  virtual void init();
630 
631  // performance statistics
632  virtual void addStat(const std::string& name, double data);
633  virtual void dumpStats(std::ostream& stream);
634  virtual void dumpStatsHeader(std::ostream& stream);
635 
636  // data statistics
637  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);
638  virtual void finish(const size_t iterationCount);
639  };
640 
642 
643  // ---------------------------------
644 
646 
647  // ---------------------------------
648 
649  // algorithms
650 
651 
653  {
654  public:
659  std::shared_ptr<Matcher> matcher;
661  std::shared_ptr<ErrorMinimizer> errorMinimizer;
663  std::shared_ptr<Inspector> inspector;
664 
665  virtual ~ICPChainBase();
666 
667  virtual void setDefault();
668 
669  virtual void loadFromYaml(std::istream& in);
670  unsigned getPrefilteredReadingPtsCount() const;
671  unsigned getPrefilteredReferencePtsCount() const;
672 
673  bool getMaxNumIterationsReached() const;
674 
675  protected:
679 
680  ICPChainBase();
681 
682  void cleanup();
683 
684  virtual void loadAdditionalYAMLContent(PointMatcherSupport::YAML::Node& doc);
685 
687  template<typename R>
688  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);
689 
691  template<typename R>
692  const std::string& createModuleFromRegistrar(const std::string& regName, const PointMatcherSupport::YAML::Node& doc, const R& registrar, std::shared_ptr<typename R::TargetType>& module);
693 
695  std::string nodeVal(const std::string& regName, const PointMatcherSupport::YAML::Node& doc);
696  };
697 
700  {
702  const DataPoints& readingIn,
703  const DataPoints& referenceIn);
704 
706  const DataPoints& readingIn,
707  const DataPoints& referenceIn,
708  const TransformationParameters& initialTransformationParameters);
709 
711  const DataPoints& readingIn,
712  const DataPoints& referenceIn,
713  const TransformationParameters& initialTransformationParameters);
714 
716  const DataPoints& getReadingFiltered() const { return readingFiltered; }
717 
718  protected:
720  const DataPoints& readingIn,
721  const DataPoints& reference,
722  const TransformationParameters& T_refIn_refMean,
723  const TransformationParameters& initialTransformationParameters);
724 
726  };
727 
730  struct ICPSequence: public ICP
731  {
733  const DataPoints& cloudIn);
735  const DataPoints& cloudIn,
736  const TransformationParameters& initialTransformationParameters);
738  const DataPoints& cloudIn,
739  const TransformationParameters& initialTransformationParameters);
740 
741  bool hasMap() const;
742  bool setMap(const DataPoints& map);
743  void clearMap();
744  virtual void setDefault();
745  virtual void loadFromYaml(std::istream& in);
746  PM_DEPRECATED("Use getPrefilteredInternalMap instead. "
747  "Function now always returns map with filter chain applied. "
748  "This may have altered your program behavior."
749  "Reasons for this stated here and in associated PR: "
750  "https://github.com/ethz-asl/libpointmatcher/issues/209.")
751  const DataPoints& getInternalMap() const;
752  const DataPoints& getPrefilteredInternalMap() const;
753  PM_DEPRECATED("Use getPrefilteredMap instead. "
754  "Function now always returns map with filter chain applied. "
755  "This may have altered your program behavior."
756  "Reasons for this stated here and in associated PR: "
757  "https://github.com/ethz-asl/libpointmatcher/issues/209")
758  const DataPoints getMap() const;
759  const DataPoints getPrefilteredMap() const;
760 
761  protected:
764  };
765 
766  // ---------------------------------
767  // Instance-related functions
768  // ---------------------------------
769 
770  PointMatcher();
771 
772  static const PointMatcher& get();
773 
774 
775 }; // PointMatcher<T>
776 
777 #endif // __POINTMATCHER_CORE_H
778 
PointMatcher::ICPSequence
Definition: PointMatcher.h:730
PointMatcher::ICPSequence::setDefault
virtual void setDefault()
Construct an ICP algorithm that works in most of the cases.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:520
check
ROSCPP_DECL bool check()
PointMatcher::ICPSequence::clearMap
void clearMap()
Clear the map (reset to same state as after the object is created)
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:512
PointMatcher::ICPSequence::hasMap
bool hasMap() const
Return whether the object currently holds a valid map.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:457
PointMatcher::DataPoints::timeExists
bool timeExists(const std::string &name) const
Look if a time with a given name exist.
Definition: pointmatcher/DataPoints.cpp:687
PointMatcher::ErrorMinimizer::ErrorElements::nbRejectedPoints
int nbRejectedPoints
number of points with all matches set to zero weights
Definition: PointMatcher.h:537
PointMatcher::DataPointsFilters::DataPointsFilters
DataPointsFilters()
Construct an empty chain.
Definition: DataPointsFilter.cpp:73
PointMatcher::DataPoints::getNbGroupedDescriptors
unsigned getNbGroupedDescriptors() const
Return the number of grouped descriptors (e.g., normals can have 3 components but would count as only...
Definition: pointmatcher/DataPoints.cpp:179
PointMatcher::OutlierFilters
A chain of OutlierFilter.
Definition: PointMatcher.h:509
PointMatcher::Parameters
Parametrizable::Parameters Parameters
alias
Definition: PointMatcher.h:186
PointMatcher::DataPointsFiltersIt
DataPointsFilters::iterator DataPointsFiltersIt
alias
Definition: PointMatcher.h:459
PointMatcher::Matches::Dists
Matrix Dists
Squared distances to closest points, dense matrix of ScalarType.
Definition: PointMatcher.h:373
PointMatcher::DataPoints::Label::operator==
bool operator==(const Label &that) const
Return whether two labels are equals.
Definition: pointmatcher/DataPoints.cpp:57
PointMatcher::Matches::dists
Dists dists
squared distances to closest points
Definition: PointMatcher.h:384
PointMatcher::DataPoints::descriptorLabels
Labels descriptorLabels
labels of descriptors
Definition: PointMatcher.h:334
PointMatcher::ICPSequence::compute
TransformationParameters compute(const DataPoints &cloudIn, const TransformationParameters &initialTransformationParameters)
Apply ICP to cloud cloudIn, with initial guess.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:595
PointMatcher::DataPoints::swapCols
void swapCols(Index iCol, Index jCol)
Swap column i and j in the point cloud, swap also features and descriptors if any....
Definition: pointmatcher/DataPoints.cpp:405
PointMatcherSupport::Logger::finishInfoEntry
virtual void finishInfoEntry(const char *file, unsigned line, const char *func)
Finish the entry into the info channel.
Definition: Logger.cpp:74
PointMatcher::DataPoints::Label::text
std::string text
name of the label
Definition: PointMatcher.h:223
PointMatcherSupport::validateFile
void validateFile(const std::string &fileName)
Throw a runtime_error exception if fileName cannot be opened.
Definition: pointmatcher/IO.cpp:355
PointMatcher::OutlierFiltersConstIt
OutlierFilters::const_iterator OutlierFiltersConstIt
alias
Definition: PointMatcher.h:516
PointMatcher::VectorVector
std::vector< Vector, Eigen::aligned_allocator< Vector > > VectorVector
A vector of vector over ScalarType, not a matrix.
Definition: PointMatcher.h:163
PointMatcher::DataPoints::getEuclideanDim
unsigned getEuclideanDim() const
Return the dimension of the point cloud.
Definition: pointmatcher/DataPoints.cpp:165
PointMatcher::Matches::getMedianAbsDeviation
T getMedianAbsDeviation() const
Calculate the Median of Absolute Deviation(MAD), which is median(|x-median(x)|), a kind of robust sta...
Definition: Matches.cpp:91
PointMatcher::DataPointsFilters::init
void init()
Init the chain.
Definition: DataPointsFilter.cpp:97
PointMatcher::Matches::ids
Ids ids
identifiers of closest points
Definition: PointMatcher.h:385
PointMatcher::OutlierWeights
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
Definition: PointMatcher.h:397
PointMatcherSupport::Logger::beginInfoEntry
virtual void beginInfoEntry(const char *file, unsigned line, const char *func)
Start a new entry into the info channel.
Definition: Logger.cpp:64
PointMatcher::DataPoints::addTime
void addTime(const std::string &name, const Int64Matrix &newTime)
Add a time by name, remove first if already exists.
Definition: pointmatcher/DataPoints.cpp:636
PointMatcher::Transformations
A chain of Transformation.
Definition: PointMatcher.h:422
PointMatcher::DataPoints::assertDescriptorConsistency
void assertDescriptorConsistency() const
Assert if descriptors are not consistent with features.
Definition: pointmatcher/DataPoints.cpp:610
PointMatcher::ICPChainBase::transformationCheckers
TransformationCheckers transformationCheckers
transformation checkers
Definition: PointMatcher.h:662
PointMatcher::ErrorMinimizer::ErrorElements::pointUsedRatio
T pointUsedRatio
the ratio of how many points were used for error minimization
Definition: PointMatcher.h:538
PointMatcher::DataPoints::Labels
A vector of Label.
Definition: PointMatcher.h:229
PointMatcher::ICP::compute
TransformationParameters compute(const DataPoints &readingIn, const DataPoints &referenceIn, const TransformationParameters &initialTransformationParameters)
Perform ICP from initial guess and return optimised transformation matrix.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:265
PointMatcher::DataPoints::removeFeature
void removeFeature(const std::string &name)
Remove a feature by name, the whole matrix will be copied.
Definition: pointmatcher/DataPoints.cpp:444
PointMatcher::DataPoints::concatenate
void concatenate(const DataPoints &dp)
Add another point cloud after the current one. Faster merge will be achieved if all descriptor and ti...
Definition: pointmatcher/DataPoints.cpp:225
PointMatcher::DataPoints::addFeature
void addFeature(const std::string &name, const Matrix &newFeature)
Add a feature by name, remove first if already exists. The 'pad' field will stay at the end for homog...
Definition: pointmatcher/DataPoints.cpp:435
PointMatcherSupport::CsvElements
std::map< std::string, std::vector< std::string > > CsvElements
Data from a CSV file.
Definition: PointMatcher.h:125
PointMatcherSupport::Logger::infoStream
virtual std::ostream * infoStream()
Return the info stream, 0 if hasInfoChannel() returns false.
Definition: Logger.cpp:68
PointMatcher::DataPoints::allocateDescriptor
void allocateDescriptor(const std::string &name, const unsigned dim)
Makes sure a descriptor of a given name exists, if present, check its dimensions.
Definition: pointmatcher/DataPoints.cpp:518
Index
NNSNabo::Index Index
Definition: python/nabo.cpp:11
PointMatcher::DataPoints::descriptorExists
bool descriptorExists(const std::string &name) const
Look if a descriptor with a given name exist.
Definition: pointmatcher/DataPoints.cpp:582
PointMatcher::Parametrizable
PointMatcherSupport::Parametrizable Parametrizable
alias
Definition: PointMatcher.h:185
PointMatcher::TransformationCheckersIt
TransformationCheckers::iterator TransformationCheckersIt
alias
Definition: PointMatcher.h:613
PointMatcher::DataPoints::getViewByName
Eigen::Block< MatrixType > getViewByName(const std::string &name, const Labels &labels, MatrixType &data, const int viewRow=-1) const
Definition: pointmatcher/DataPoints.cpp:948
PointMatcher::ScalarType
T ScalarType
The scalar type.
Definition: PointMatcher.h:159
PointMatcher::DataPoints::addDescriptor
void addDescriptor(const std::string &name, const Matrix &newDescriptor)
Add a descriptor by name, remove first if already exists.
Definition: pointmatcher/DataPoints.cpp:532
PointMatcher::DataPoints::getConstViewByName
const Eigen::Block< const MatrixType > getConstViewByName(const std::string &name, const Labels &labels, const MatrixType &data, const int viewRow=-1) const
Definition: pointmatcher/DataPoints.cpp:921
PointMatcherSupport::ConfigurationError
An expception thrown when the yaml config file contains invalid configuration (e.g....
Definition: PointMatcher.h:96
PointMatcher::DataPoints::allocateFields
void allocateFields(const Labels &newLabels, Labels &labels, MatrixType &data) const
Make sure a vector of fields of given names exist.
Definition: pointmatcher/DataPoints.cpp:785
PointMatcher::ICPSequence::setMap
bool setMap(const DataPoints &map)
Set the map using inputCloud.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:464
PointMatcher::OutlierFilter
An outlier filter removes or weights links between points in reading and their matched points in refe...
Definition: PointMatcher.h:496
PointMatcher::Array
Eigen::Array< T, Eigen::Dynamic, Eigen::Dynamic > Array
A dense array over ScalarType.
Definition: PointMatcher.h:175
PointMatcher
Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: PointMatcher.h:130
PointMatcher::ICPChainBase::referenceDataPointsFilters
DataPointsFilters referenceDataPointsFilters
filters for reference
Definition: PointMatcher.h:657
PointMatcher::ConvergenceError
Point matcher did not converge.
Definition: PointMatcher.h:148
PointMatcherSupport::setLogger
void setLogger(std::shared_ptr< Logger > newLogger)
Set a new logger, protected by a mutex.
Definition: Logger.cpp:98
PointMatcher::DataPointsFilters
A chain of DataPointsFilter.
Definition: PointMatcher.h:452
PointMatcher::TransformationCheckersConstIt
TransformationCheckers::const_iterator TransformationCheckersConstIt
alias
Definition: PointMatcher.h:614
PointMatcherSupport::TransformationError::TransformationError
TransformationError(const std::string &reason)
return an exception when a transformation has invalid parameters
Definition: TransformationsImpl.cpp:44
PointMatcherSupport::Logger
The logger interface, used to output warnings and informations.
Definition: PointMatcher.h:104
PointMatcherSupport::Logger::hasWarningChannel
virtual bool hasWarningChannel() const
Return whether this logger provides the warning channel.
Definition: Logger.cpp:78
PointMatcher::ICPChainBase::maxNumIterationsReached
bool maxNumIterationsReached
store if we reached the maximum number of iterations last time compute was called
Definition: PointMatcher.h:678
PointMatcher::ICPChainBase
Stuff common to all ICP algorithms.
Definition: PointMatcher.h:652
PointMatcher::DataPoints::getDescriptorCopyByName
Matrix getDescriptorCopyByName(const std::string &name) const
Get descriptor by name, return a matrix containing a copy of the requested descriptor.
Definition: pointmatcher/DataPoints.cpp:547
PointMatcher::DataPoints::getTimeDim
unsigned getTimeDim() const
Return the total number of times.
Definition: pointmatcher/DataPoints.cpp:193
PointMatcher::DataPoints::getTimeCopyByName
Int64Matrix getTimeCopyByName(const std::string &name) const
Get time by name, return a matrix containing a copy of the requested time.
Definition: pointmatcher/DataPoints.cpp:650
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
PointMatcher::DataPoints::allocateFeatures
void allocateFeatures(const Labels &newLabels)
Make sure a vector of features of given names exist.
Definition: pointmatcher/DataPoints.cpp:428
Parametrizable.h
PointMatcher::ICPSequence::mapPointCloud
DataPoints mapPointCloud
point cloud of the map, always in global frame (frame of first point cloud)
Definition: PointMatcher.h:762
PointMatcher::DataPoints::getDescriptorStartingRow
unsigned getDescriptorStartingRow(const std::string &name) const
Return the starting row of a descriptor with a given name. Return 0 if the name is not found.
Definition: pointmatcher/DataPoints.cpp:603
PointMatcher::QuaternionVector
std::vector< Quaternion, Eigen::aligned_allocator< Quaternion > > QuaternionVector
A vector of quaternions over ScalarType.
Definition: PointMatcher.h:167
PointMatcher::DataPoints::getHomogeneousDim
unsigned getHomogeneousDim() const
Return the dimension of the point cloud in homogeneous coordinates (one more than Euclidean dimension...
Definition: pointmatcher/DataPoints.cpp:172
PointMatcher::Matcher
A matcher links points in the reading to points in the reference.
Definition: PointMatcher.h:470
testing::internal::string
::std::string string
Definition: gtest.h:1979
PointMatcher::DataPoints::timeLabels
Labels timeLabels
labels of times.
Definition: PointMatcher.h:336
PointMatcher::ICPSequence::PM_DEPRECATED
PM_DEPRECATED("Use getPrefilteredInternalMap instead. " "Function now always returns map with filter chain applied. " "This may have altered your program behavior." "Reasons for this stated here and in associated PR: " "https://github.com/ethz-asl/libpointmatcher/issues/209.") const DataPoints &getInternalMap() const
PointMatcher::ICPSequence::operator()
TransformationParameters operator()(const DataPoints &cloudIn)
Apply ICP to cloud cloudIn, with identity as initial guess.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:577
PointMatcher::DataPoints::Labels::operator<<
friend std::ostream & operator<<(std::ostream &stream, const Labels &labels)
Definition: PointMatcher.h:236
PointMatcher::Transformation::checkParameters
virtual bool checkParameters(const TransformationParameters &parameters) const =0
Return whether the given parameters respect the expected constraints.
PointMatcher::ParametersDoc
Parametrizable::ParametersDoc ParametersDoc
alias
Definition: PointMatcher.h:188
PointMatcher::DataPoints::operator==
bool operator==(const DataPoints &that) const
Return whether two point-clouds are identical (same data and same labels)
Definition: pointmatcher/DataPoints.cpp:200
PointMatcherSupport::InvalidModuleType
An exception thrown when one tries to use a module type that does not exist.
Definition: PointMatcher.h:83
PointMatcher::TransformationChecker::limits
Vector limits
values of limits involved in conditions to stop ICP loop
Definition: PointMatcher.h:584
PointMatcher::DataPoints::getTimeDimension
unsigned getTimeDimension(const std::string &name) const
Return the dimension of a time with a given name. Return 0 if the name is not found.
Definition: pointmatcher/DataPoints.cpp:701
PointMatcher::DataPoints::getFeatureDimension
unsigned getFeatureDimension(const std::string &name) const
Return the dimension of a feature with a given name. Return 0 if the name is not found.
Definition: pointmatcher/DataPoints.cpp:500
DEF_REGISTRAR_IFACE
#define DEF_REGISTRAR_IFACE(name, ifaceName)
Definition: Registrar.h:222
DEF_REGISTRAR
#define DEF_REGISTRAR(name)
Definition: Registrar.h:221
PointMatcher::DataPoints::TimeConstView
const typedef Eigen::Block< const Int64Matrix > TimeConstView
a view on a const time
Definition: PointMatcher.h:216
PointMatcher::Transformation
A function that transforms points and their descriptors given a transformation matrix.
Definition: PointMatcher.h:404
PointMatcher::DataPoints::InvalidField
An exception thrown when one tries to access features or descriptors unexisting or of wrong dimension...
Definition: PointMatcher.h:250
PointMatcher::DataPoints::getFeatureViewByName
ConstView getFeatureViewByName(const std::string &name) const
Get a const view on a feature by name, throw an exception if it does not exist.
Definition: pointmatcher/DataPoints.cpp:458
PointMatcher::OutlierFilters::compute
OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Apply outlier-detection chain.
Definition: OutlierFilter.cpp:64
PointMatcher::ICPSequence::getPrefilteredInternalMap
const DataPoints & getPrefilteredInternalMap() const
Return the map, in internal coordinates (fast)
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:564
PointMatcher::Int64Matrix
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
A dense signed 64-bits matrix.
Definition: PointMatcher.h:173
PointMatcher::ICPChainBase::readingDataPointsFilters
DataPointsFilters readingDataPointsFilters
filters for reading, applied once
Definition: PointMatcher.h:655
PointMatcher::DataPointsFiltersConstIt
DataPointsFilters::const_iterator DataPointsFiltersConstIt
alias
Definition: PointMatcher.h:460
PointMatcher::TransformationCheckers::init
void init(const TransformationParameters &parameters, bool &iterate)
Init all transformation checkers, set iterate to false if iteration should stop.
Definition: TransformationChecker.cpp:112
PointMatcher::DataPoints::featureExists
bool featureExists(const std::string &name) const
Look if a feature with a given name exist.
Definition: pointmatcher/DataPoints.cpp:486
PointMatcher::ICP::getReadingFiltered
const DataPoints & getReadingFiltered() const
Return the filtered point cloud reading used in the ICP chain.
Definition: PointMatcher.h:716
PointMatcher::OutlierFiltersIt
OutlierFilters::iterator OutlierFiltersIt
alias
Definition: PointMatcher.h:517
PointMatcher::ErrorMinimizer::ErrorElements
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
Definition: PointMatcher.h:530
PointMatcher::DataPoints::removeField
void removeField(const std::string &name, Labels &labels, MatrixType &data) const
Remove a descriptor or feature by name, no copy is done.
Definition: pointmatcher/DataPoints.cpp:884
PointMatcher::DataPoints::allocateTime
void allocateTime(const std::string &name, const unsigned dim)
Makes sure a time of a given name exists, if present, check its dimensions.
Definition: pointmatcher/DataPoints.cpp:621
PointMatcher::DataPoints::allocateFeature
void allocateFeature(const std::string &name, const unsigned dim)
Makes sure a feature of a given name exists, if present, check its dimensions.
Definition: pointmatcher/DataPoints.cpp:421
PointMatcher::Matches::Matches
Matches()
In case of too few matches the dists are filled with InvalidDist.
Definition: Matches.cpp:43
PointMatcherSupport::Logger::warningStream
virtual std::ostream * warningStream()
Return the warning stream, 0 if hasWarningChannel() returns false.
Definition: Logger.cpp:88
PointMatcherSupport::Parametrizable::ParametersDoc
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
Definition: Parametrizable.h:144
PointMatcher::PointMatcher
PointMatcher()
Constructor, populates the registrars.
Definition: Registry.cpp:61
PointMatcher::DataPoints::getFieldStartingRow
unsigned getFieldStartingRow(const std::string &name, const Labels &labels) const
Return the starting row of a feature or a descriptor with a given name. Return 0 if the name is not f...
Definition: pointmatcher/DataPoints.cpp:1004
PointMatcher::DataPoints::featureLabels
Labels featureLabels
labels of features
Definition: PointMatcher.h:332
PointMatcher::Transformation::correctParameters
virtual TransformationParameters correctParameters(const TransformationParameters &parameters) const =0
Return a valid version of the given transformation.
PointMatcher::ICPChainBase::outlierFilters
OutlierFilters outlierFilters
outlier filters
Definition: PointMatcher.h:660
PointMatcher::ICPSequence::loadFromYaml
virtual void loadFromYaml(std::istream &in)
Construct an ICP algorithm from a YAML file.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:531
PointMatcher::ErrorMinimizer::ErrorElements::matches
Matches matches
associations
Definition: PointMatcher.h:535
PointMatcher::DataPoints::setColFrom
void setColFrom(Index thisCol, const DataPoints &that, Index thatCol)
Set column thisCol equal to column thatCol of that, copy features and descriptors if any....
Definition: pointmatcher/DataPoints.cpp:392
PointMatcher::DataPoints::createSimilarEmpty
DataPoints createSimilarEmpty() const
Create an empty DataPoints of similar dimensions and labels for features, descriptors and times.
Definition: pointmatcher/DataPoints.cpp:339
PointMatcher::ICPChainBase::errorMinimizer
std::shared_ptr< ErrorMinimizer > errorMinimizer
error minimizer
Definition: PointMatcher.h:661
PointMatcher::DataPoints::concatenateLabelledMatrix
void concatenateLabelledMatrix(Labels *labels, MatrixType *data, const Labels extraLabels, const MatrixType extraData)
Add another matrix after the current one. Faster merge will be achieved if all labels are the same....
Definition: pointmatcher/DataPoints.cpp:257
PointMatcher::ErrorMinimizer::ErrorElements::weightedPointUsedRatio
T weightedPointUsedRatio
the ratio of how many points were used (with weight) for error minimization
Definition: PointMatcher.h:539
PointMatcher::DataPoints::descriptors
Matrix descriptors
descriptors of points in the cloud, might be empty
Definition: PointMatcher.h:333
PointMatcherSupport::Parametrizable::parameters
Parameters parameters
parameters with their values encoded in string
Definition: Parametrizable.h:161
PointMatcher::DataPoints::TimeView
Eigen::Block< Int64Matrix > TimeView
A view on a time.
Definition: PointMatcher.h:212
Registrar.h
PointMatcher::Matrix
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
PointMatcher::TransformationChecker
A transformation checker can stop the iteration depending on some conditions.
Definition: PointMatcher.h:580
PointMatcherSupport::Logger::Logger
Logger()
Construct without parameter.
Definition: Logger.cpp:45
PointMatcher::ErrorMinimizer::ErrorElements::reading
DataPoints reading
reading point cloud
Definition: PointMatcher.h:532
PointMatcher::DataPointsFilter
A data filter takes a point cloud as input, transforms it, and produces another point cloud as output...
Definition: PointMatcher.h:437
PointMatcher::DataPoints::getFeatureRowViewByName
ConstView getFeatureRowViewByName(const std::string &name, const unsigned row) const
Get a const view on a feature row by name and number, throw an exception if it does not exist.
Definition: pointmatcher/DataPoints.cpp:472
PointMatcher::DataPoints::getTimeViewByName
TimeConstView getTimeViewByName(const std::string &name) const
Get a const view on a time by name, throw an exception if it does not exist.
Definition: pointmatcher/DataPoints.cpp:658
PointMatcher::Matches::Ids
IntMatrix Ids
Identifiers of closest points, dense matrix of integers.
Definition: PointMatcher.h:374
PointMatcher::DataPoints::assertTimesConsistency
void assertTimesConsistency() const
Assert if times are not consistent with features.
Definition: pointmatcher/DataPoints.cpp:715
PointMatcher::IntMatrix
Eigen::Matrix< int, Eigen::Dynamic, Eigen::Dynamic > IntMatrix
A dense integer matrix.
Definition: PointMatcher.h:171
PointMatcherSupport::Parametrizable::InvalidParameter
An exception thrown when one tries to fetch the value of an unexisting parameter.
Definition: Parametrizable.h:101
PointMatcherSupport::Logger::hasInfoChannel
virtual bool hasInfoChannel() const
Return whether this logger provides the info channel.
Definition: Logger.cpp:58
PointMatcher::DataPoints::getNbPoints
unsigned getNbPoints() const
Return the number of points contained in the point cloud.
Definition: pointmatcher/DataPoints.cpp:158
PointMatcher::DataPoints::allocateField
void allocateField(const std::string &name, const unsigned dim, Labels &labels, MatrixType &data) const
Make sure a field of a given name exists, if present, check its dimensions.
Definition: pointmatcher/DataPoints.cpp:760
PointMatcher::TransformationChecker::conditionVariables
Vector conditionVariables
values of variables involved in conditions to stop ICP loop
Definition: PointMatcher.h:585
PointMatcher::ICP::operator()
TransformationParameters operator()(const DataPoints &readingIn, const DataPoints &referenceIn)
Perform ICP and return optimised transformation matrix.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:244
PointMatcher::DataPoints::Label::Label
Label(const std::string &text="", const size_t span=0)
Construct a label from a given name and number of data dimensions it spans.
Definition: pointmatcher/DataPoints.cpp:44
PointMatcher::swapDataPoints
static void swapDataPoints(DataPoints &a, DataPoints &b)
Exchange in place point clouds a and b, with no data copy.
Definition: pointmatcher/DataPoints.cpp:1022
PointMatcher::DataPoints::features
Matrix features
features of points in the cloud
Definition: PointMatcher.h:331
PointMatcher::ErrorMinimizer::ErrorElements::reference
DataPoints reference
reference point cloud
Definition: PointMatcher.h:533
PointMatcher::Vector
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Definition: PointMatcher.h:161
PointMatcher::DataPoints::ConstView
const typedef Eigen::Block< const Matrix > ConstView
A view on a const feature or const descriptor.
Definition: PointMatcher.h:214
PointMatcher::TransformationsIt
Transformations::iterator TransformationsIt
alias
Definition: PointMatcher.h:426
PointMatcher::DataPoints::Index
Matrix::Index Index
An index to a row or a column.
Definition: PointMatcher.h:218
PointMatcher::ICPChainBase::matcher
std::shared_ptr< Matcher > matcher
matcher
Definition: PointMatcher.h:659
PointMatcher::TransformationCheckers::check
void check(const TransformationParameters &parameters, bool &iterate)
Check using all transformation checkers, set iterate to false if iteration should stop.
Definition: TransformationChecker.cpp:120
DeprecationWarnings.h
PointMatcher::ICP::computeWithTransformedReference
TransformationParameters computeWithTransformedReference(const DataPoints &readingIn, const DataPoints &reference, const TransformationParameters &T_refIn_refMean, const TransformationParameters &initialTransformationParameters)
Perferm ICP using an already-transformed reference and with an already-initialized matcher.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:317
PointMatcherSupport::Logger::beginWarningEntry
virtual void beginWarningEntry(const char *file, unsigned line, const char *func)
Start a new entry into the warning channel.
Definition: Logger.cpp:84
PointMatcher::DataPoints::Labels::contains
bool contains(const std::string &text) const
Return whether there is a label named text.
Definition: pointmatcher/DataPoints.cpp:75
PointMatcher::InvalidParameter
Parametrizable::InvalidParameter InvalidParameter
alias
Definition: PointMatcher.h:189
PointMatcher::Matches
Result of the data-association step (Matcher::findClosests), before outlier rejection.
Definition: PointMatcher.h:371
PointMatcher::ICPChainBase::inspector
std::shared_ptr< Inspector > inspector
inspector
Definition: PointMatcher.h:663
PointMatcher::TransformationChecker::conditionVariableNames
StringVector conditionVariableNames
names of variables involved in conditions to stop ICP loop
Definition: PointMatcher.h:587
PointMatcher::DataPoints::times
Int64Matrix times
time associated to each points, might be empty
Definition: PointMatcher.h:335
PointMatcher::DataPoints::allocateTimes
void allocateTimes(const Labels &newLabels)
Make sure a vector of time of given names exist.
Definition: pointmatcher/DataPoints.cpp:628
PointMatcherSupport::Parametrizable
The superclass of classes that are constructed using generic parameters. This class provides the para...
Definition: Parametrizable.h:98
PointMatcher::DataPoints::removeTime
void removeTime(const std::string &name)
Remove a descriptor by name, the whole matrix will be copied.
Definition: pointmatcher/DataPoints.cpp:643
PointMatcher::DataPoints::assertConsistency
void assertConsistency(const std::string &dataName, const int dataRows, const int dataCols, const Labels &labels) const
Assert if a matrix is not consistent with features.
Definition: pointmatcher/DataPoints.cpp:722
PointMatcher::DataPoints::removeDescriptor
void removeDescriptor(const std::string &name)
Remove a descriptor by name, the whole matrix will be copied.
Definition: pointmatcher/DataPoints.cpp:539
PointMatcher::Matches::InvalidId
static constexpr int InvalidId
Definition: PointMatcher.h:377
PointMatcher::ICPChainBase::prefilteredReadingPtsCount
unsigned prefilteredReadingPtsCount
remaining number of points after prefiltering but before the iterative process
Definition: PointMatcher.h:676
PointMatcher::DataPoints::getTimeStartingRow
unsigned getTimeStartingRow(const std::string &name) const
Return the starting row of a time with a given name. Return 0 if the name is not found.
Definition: pointmatcher/DataPoints.cpp:708
PointMatcher::ErrorMinimizer::ErrorElements::weights
OutlierWeights weights
weights for every association
Definition: PointMatcher.h:534
PointMatcher::DataPoints::Label::span
size_t span
number of data dimensions the label spans
Definition: PointMatcher.h:224
PointMatcher::DataPoints::Labels::Labels
Labels()
Construct empty Labels.
Definition: pointmatcher/DataPoints.cpp:64
PointMatcher::Matcher::visitCounter
unsigned long visitCounter
number of points visited
Definition: PointMatcher.h:472
PointMatcherSupport::Parametrizable::ParameterDoc
The documentation of a parameter.
Definition: Parametrizable.h:117
PointMatcherSupport::Logger::~Logger
virtual ~Logger()
Virtual destructor, do nothing.
Definition: Logger.cpp:54
PointMatcher::DataPoints::getDescriptorDimension
unsigned getDescriptorDimension(const std::string &name) const
Return the dimension of a descriptor with a given name. Return 0 if the name is not found.
Definition: pointmatcher/DataPoints.cpp:596
PointMatcher::TransformationCheckers
A chain of TransformationChecker.
Definition: PointMatcher.h:608
PointMatcher::DataPoints::getDescriptorDim
unsigned getDescriptorDim() const
Return the total number of descriptors.
Definition: pointmatcher/DataPoints.cpp:186
PointMatcher::DataPoints::View
Eigen::Block< Matrix > View
A view on a feature or descriptor.
Definition: PointMatcher.h:210
PointMatcher::Inspector
An inspector allows to log data at the different steps, for analysis.
Definition: PointMatcher.h:621
PointMatcher::DataPoints::conservativeResize
void conservativeResize(Index pointCount)
Resize the cloud to pointCount points, conserving existing ones.
Definition: pointmatcher/DataPoints.cpp:327
init
void init(const M_string &remappings)
PointMatcher::TransformationChecker::StringVector
std::vector< std::string > StringVector
a vector of strings
Definition: PointMatcher.h:583
PointMatcher::DataPoints::getDescriptorRowViewByName
ConstView getDescriptorRowViewByName(const std::string &name, const unsigned row) const
Get a const view on a descriptor row by name and number, throw an exception if it does not exist.
Definition: pointmatcher/DataPoints.cpp:568
PointMatcher::Transformations::apply
void apply(DataPoints &cloud, const TransformationParameters &parameters) const
Apply this chain to cloud, using parameters, mutates cloud.
Definition: Transformation.cpp:61
PointMatcher::get
static const PointMatcher & get()
Return instances.
Definition: Registry.cpp:141
PointMatcher::ErrorMinimizer::ErrorElements::nbRejectedMatches
int nbRejectedMatches
number of matches with zero weights
Definition: PointMatcher.h:536
PointMatcher::DataPoints::Labels::totalDim
size_t totalDim() const
Return the sum of the spans of each label.
Definition: pointmatcher/DataPoints.cpp:87
PointMatcher::Matches::getStandardDeviation
T getStandardDeviation() const
Definition: Matches.cpp:125
PointMatcher::ICPChainBase::transformations
Transformations transformations
transformations
Definition: PointMatcher.h:658
PointMatcherSupport::Logger::finishWarningEntry
virtual void finishWarningEntry(const char *file, unsigned line, const char *func)
Finish the entry into the warning channel.
Definition: Logger.cpp:94
PointMatcher::DataPoints::DataPoints
DataPoints()
Construct an empty point cloud.
Definition: pointmatcher/DataPoints.cpp:97
PointMatcher::ParameterDoc
Parametrizable::ParameterDoc ParameterDoc
alias
Definition: PointMatcher.h:187
PointMatcher::ErrorMinimizer
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
Definition: PointMatcher.h:527
PointMatcherSupport
Functions and classes that are not dependant on scalar type are defined in this namespace.
Definition: Bibliography.cpp:45
PointMatcher::Transformation::~Transformation
virtual ~Transformation()
virtual destructor
Definition: Transformation.cpp:52
PointMatcher::DataPoints::getFieldDimension
unsigned getFieldDimension(const std::string &name, const Labels &labels) const
Return the dimension of a feature or a descriptor with a given name. Return 0 if the name is not foun...
Definition: pointmatcher/DataPoints.cpp:991
PointMatcher::DataPoints::getTimeRowViewByName
TimeConstView getTimeRowViewByName(const std::string &name, const unsigned row) const
Get a const view on a time row by name and number, throw an exception if it does not exist.
Definition: pointmatcher/DataPoints.cpp:672
PointMatcher::DataPoints::fieldExists
bool fieldExists(const std::string &name, const unsigned dim, const Labels &labels) const
Look if a descriptor or a feature with a given name and dimension exist.
Definition: pointmatcher/DataPoints.cpp:973
PointMatcher::Transformation::Transformation
Transformation()
Construct without parameter.
Definition: Transformation.cpp:41
PointMatcherSupport::ConfigurationError::ConfigurationError
ConfigurationError(const std::string &reason)
return an exception when a transformation has invalid parameters
Definition: Exceptions.cpp:46
PointMatcher::Matches::getDistsQuantile
T getDistsQuantile(const T quantile) const
Get the distance at the T-ratio closest point.
Definition: Matches.cpp:61
PointMatcher::ICPSequence::getPrefilteredMap
const DataPoints getPrefilteredMap() const
Return the map, in global coordinates (slow)
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:543
PointMatcherSupport::TransformationError
An expection thrown when a transformation has invalid parameters.
Definition: PointMatcher.h:89
PointMatcher::Transformation::compute
virtual DataPoints compute(const DataPoints &input, const TransformationParameters &parameters) const =0
Transform input using the transformation matrix.
PointMatcher::ICPSequence::T_refIn_refMean
TransformationParameters T_refIn_refMean
offset for centered map
Definition: PointMatcher.h:763
PointMatcher::DataPoints::load
static DataPoints load(const std::string &fileName)
Load a point cloud from a file, determine format from extension.
Definition: pointmatcher/IO.cpp:375
PointMatcher::TransformationChecker::limitNames
StringVector limitNames
names of limits involved in conditions to stop ICP loop
Definition: PointMatcher.h:586
PointMatcher::DataPointsFilters::apply
void apply(DataPoints &cloud)
Apply this chain to cloud, mutates cloud.
Definition: DataPointsFilter.cpp:107
PointMatcher::DataPoints::addField
void addField(const std::string &name, const MatrixType &newField, Labels &labels, MatrixType &data) const
Add a descriptor or feature by name, remove first if already exists.
Definition: pointmatcher/DataPoints.cpp:827
PointMatcher::DataPoints::getDescriptorViewByName
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
Definition: pointmatcher/DataPoints.cpp:554
PointMatcher::DataPoints::save
void save(const std::string &fileName, bool binary=false) const
Save a point cloud to a file, determine format from extension.
Definition: pointmatcher/IO.cpp:809
PointMatcher::DataPoints::InvalidField::InvalidField
InvalidField(const std::string &reason)
Construct the exception with an error message.
Definition: pointmatcher/DataPoints.cpp:51
PointMatcher::ConvergenceError::ConvergenceError
ConvergenceError(const std::string &reason)
Construct the exception with an error message.
Definition: Exceptions.cpp:42
PointMatcherSupport::Parametrizable::className
const std::string className
name of the class
Definition: Parametrizable.h:159
PointMatcher::ErrorMinimizer::lastErrorElements
ErrorElements lastErrorElements
memory of the last computed error
Definition: PointMatcher.h:568
PointMatcher::DataPoints::getFeatureStartingRow
unsigned getFeatureStartingRow(const std::string &name) const
Return the starting row of a feature with a given name. Return 0 if the name is not found.
Definition: pointmatcher/DataPoints.cpp:507
PointMatcher::DataPoints::getFeatureCopyByName
Matrix getFeatureCopyByName(const std::string &name) const
Get feature by name, return a matrix containing a copy of the requested feature.
Definition: pointmatcher/DataPoints.cpp:451
PointMatcher::ICP::readingFiltered
DataPoints readingFiltered
reading point cloud after the filters were applied
Definition: PointMatcher.h:725
PointMatcher::ICPChainBase::prefilteredReferencePtsCount
unsigned prefilteredReferencePtsCount
remaining number of points after prefiltering but before the iterative process
Definition: PointMatcher.h:677
PointMatcher::DataPoints::allocateDescriptors
void allocateDescriptors(const Labels &newLabels)
Make sure a vector of descriptors of given names exist.
Definition: pointmatcher/DataPoints.cpp:525
PointMatcher::TransformationsConstIt
Transformations::const_iterator TransformationsConstIt
alias
Definition: PointMatcher.h:427
PointMatcher::ICP
ICP algorithm.
Definition: PointMatcher.h:699
PointMatcher::Quaternion
Eigen::Quaternion< T > Quaternion
A quaternion over ScalarType.
Definition: PointMatcher.h:165
PointMatcherSupport::Parametrizable::Parameters
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Definition: Parametrizable.h:156
PointMatcher::ICPChainBase::readingStepDataPointsFilters
DataPointsFilters readingStepDataPointsFilters
filters for reading, applied at each step
Definition: PointMatcher.h:656
PointMatcher::DataPoints::Labels::const_iterator
std::vector< Label >::const_iterator const_iterator
alias
Definition: PointMatcher.h:231
PointMatcher::TransformationParameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182
PointMatcherSupport::InvalidModuleType::InvalidModuleType
InvalidModuleType(const std::string &reason)
Construct an invalid–module-type exception.
Definition: 3rdparty/libpointmatcher/pointmatcher/ICP.cpp:59
PointMatcher::DataPoints::Label
The name for a certain number of dim.
Definition: PointMatcher.h:221
PointMatcher::Matches::InvalidDist
static constexpr T InvalidDist
In case of too few matches the ids are filled with InvalidId.
Definition: PointMatcher.h:378


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04