Elipsoids.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--2018,
6 François 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 #pragma once
36 
37 #include "PointMatcher.h"
38 
40 template<typename T>
42 {
49 
50  typedef typename PointMatcher<T>::Vector Vector;
51  typedef typename PointMatcher<T>::Matrix Matrix;
54 
55  inline static const std::string description()
56  {
57  return "Subsampling, Surfels (Elipsoids). This filter decomposes the point-cloud space in boxes, by recursively splitting the cloud through axis-aligned hyperplanes such as to maximize the evenness of the aspect ratio of the box. When the number of points in a box reaches a value knn or lower, the filter computes the center of mass of these points and its normal by taking the eigenvector corresponding to the smallest eigenvalue of all points in the box.";
58  }
59  inline static const ParametersDoc availableParameters()
60  {
61  return {
62  {"ratio", "ratio of points to keep with random subsampling. Matrix (normal, density, etc.) will be associated to all points in the same bin.", "0.5", "0.0000001", "0.9999999", &P::Comp<T> },
63  {"knn", "determined how many points are used to compute the normals. Direct link with the rapidity of the computation (large = fast). Technically, limit over which a box is splitted in two", "7", "3", "2147483647", &P::Comp<unsigned> },
64  {"samplingMethod", "if set to 0, random subsampling using the parameter ratio. If set to 1, bin subsampling with the resulting number of points being 1/knn.", "0", "0", "1", &P::Comp<unsigned> },
65  {"maxBoxDim", "maximum length of a box above which the box is discarded", "inf" },
66  {"averageExistingDescriptors", "whether the filter keep the existing point descriptors and average them or should it drop them", "1" },
67  {"maxTimeWindow", "maximum spread of times in a surfel", "inf" },
68  {"minPlanarity", "to what extend planarity of surfels needs to be enforced", "0"},
69  {"keepNormals", "whether the normals should be added as descriptors to the resulting cloud", "1" },
70  {"keepDensities", "whether the point densities should be added as descriptors to the resulting cloud", "0" },
71  {"keepEigenValues", "whether the eigen values should be added as descriptors to the resulting cloud", "0" },
72  {"keepEigenVectors", "whether the eigen vectors should be added as descriptors to the resulting cloud", "0" },
73  {"keepMeans", "whether the means should be added as descriptors to the resulting cloud", "0" },
74  {"keepCovariances", "whether the covariances should be added as descriptors to the resulting cloud", "0" },
75  {"keepWeights", "whether the original number of points should be added as descriptors to the resulting cloud", "0" },
76  {"keepShapes", "whether the shape parameters of cylindricity (C), sphericality (S) and planarity (P) shall be calculated", "0" },
77  {"keepIndices", "whether the indices of points an ellipsoid is constructed of shall be kept", "0" }
78  }
79  ;
80  }
81 
82  const T ratio;
83  const unsigned knn;
84  const unsigned samplingMethod;
85  const T maxBoxDim;
87  const T minPlanarity;
89  const bool keepNormals;
90  const bool keepDensities;
91  const bool keepEigenValues;
92  const bool keepEigenVectors;
93  const bool keepCovariances;
94  const bool keepWeights;
95  const bool keepMeans;
96  const bool keepShapes;
97  const bool keepIndices;
98 
99 
100  public:
103  virtual DataPoints filter(const DataPoints& input);
104  virtual void inPlaceFilter(DataPoints& cloud);
105 
106  protected:
107  struct BuildData
108  {
109  typedef std::vector<int> Indices;
110  typedef typename DataPoints::View View;
111  typedef typename Eigen::Matrix<std::int64_t, Eigen::Dynamic, Eigen::Dynamic> Int64Matrix;
112  typedef typename Eigen::Matrix<std::int64_t, 1, Eigen::Dynamic> Int64Vector;
113 
119  boost::optional<View> normals;
120  boost::optional<View> densities;
121  boost::optional<View> eigenValues;
122  boost::optional<View> eigenVectors;
123  boost::optional<View> weights;
124  boost::optional<View> covariance;
125  boost::optional<View> means;
126  boost::optional<View> shapes;
127  boost::optional<View> pointIds;
128  boost::optional<View> pointX;
129  boost::optional<View> pointY;
130  boost::optional<View> pointZ;
131  boost::optional<View> numOfNN;
134 
138  times(times),
140  {
141  const int pointsCount(features.cols());
142  indices.reserve(pointsCount);
143  for (int i = 0; i < pointsCount; ++i)
144  indices.push_back(i);
145  }
146  };
147 
148  struct CompareDim
149  {
150  const int dim;
153  bool operator() (const int& p0, const int& p1)
154  {
155  return buildData.features(dim, p0) <
156  buildData.features(dim, p1);
157  }
158  };
159 
160  protected:
161  void buildNew(BuildData& data, const int first, const int last, Vector&& minValues, Vector&& maxValues) const;
162  void fuseRange(BuildData& data, const int first, const int last) const;
163 };
ElipsoidsDataPointsFilter::BuildData::descriptors
Matrix & descriptors
Definition: Elipsoids.h:117
ElipsoidsDataPointsFilter::BuildData
Definition: Elipsoids.h:107
ElipsoidsDataPointsFilter::CompareDim
Definition: Elipsoids.h:148
ElipsoidsDataPointsFilter::BuildData::features
Matrix & features
Definition: Elipsoids.h:116
ElipsoidsDataPointsFilter::keepEigenValues
const bool keepEigenValues
Definition: Elipsoids.h:91
Vector
PM::Vector Vector
Definition: pypoint_matcher_helper.h:55
ElipsoidsDataPointsFilter::keepNormals
const bool keepNormals
Definition: Elipsoids.h:89
DataPointsFilter
PM::DataPointsFilter DataPointsFilter
Definition: pypoint_matcher_helper.h:22
ElipsoidsDataPointsFilter::ElipsoidsDataPointsFilter
ElipsoidsDataPointsFilter(const Parameters &params=Parameters())
Definition: Elipsoids.cpp:49
ElipsoidsDataPointsFilter::Parametrizable
PointMatcherSupport::Parametrizable Parametrizable
Definition: Elipsoids.h:43
ElipsoidsDataPointsFilter::CompareDim::dim
const int dim
Definition: Elipsoids.h:150
ElipsoidsDataPointsFilter::Vector
PointMatcher< T >::Vector Vector
Definition: Elipsoids.h:50
ElipsoidsDataPointsFilter::BuildData::pointIds
boost::optional< View > pointIds
Definition: Elipsoids.h:127
ElipsoidsDataPointsFilter::averageExistingDescriptors
const bool averageExistingDescriptors
Definition: Elipsoids.h:88
build_map.T
T
Definition: build_map.py:34
ElipsoidsDataPointsFilter::keepDensities
const bool keepDensities
Definition: Elipsoids.h:90
ElipsoidsDataPointsFilter::buildNew
void buildNew(BuildData &data, const int first, const int last, Vector &&minValues, Vector &&maxValues) const
Definition: Elipsoids.cpp:238
ElipsoidsDataPointsFilter::keepWeights
const bool keepWeights
Definition: Elipsoids.h:94
ElipsoidsDataPointsFilter::BuildData::pointX
boost::optional< View > pointX
Definition: Elipsoids.h:128
ElipsoidsDataPointsFilter::~ElipsoidsDataPointsFilter
virtual ~ElipsoidsDataPointsFilter()
Definition: Elipsoids.h:102
ElipsoidsDataPointsFilter::BuildData::Int64Matrix
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
Definition: Elipsoids.h:111
ElipsoidsDataPointsFilter::keepMeans
const bool keepMeans
Definition: Elipsoids.h:95
PointMatcher
Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: PointMatcher.h:130
ElipsoidsDataPointsFilter::BuildData::indices
Indices indices
Definition: Elipsoids.h:114
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
ElipsoidsDataPointsFilter::BuildData::shapes
boost::optional< View > shapes
Definition: Elipsoids.h:126
ElipsoidsDataPointsFilter::BuildData::unfitPointsCount
int unfitPointsCount
Definition: Elipsoids.h:133
ElipsoidsDataPointsFilter::BuildData::pointY
boost::optional< View > pointY
Definition: Elipsoids.h:129
ElipsoidsDataPointsFilter::description
static const std::string description()
Definition: Elipsoids.h:55
ElipsoidsDataPointsFilter::BuildData::View
DataPoints::View View
Definition: Elipsoids.h:110
ElipsoidsDataPointsFilter::InvalidParameter
Parametrizable::InvalidParameter InvalidParameter
Definition: Elipsoids.h:48
ElipsoidsDataPointsFilter::keepEigenVectors
const bool keepEigenVectors
Definition: Elipsoids.h:92
testing::internal::string
::std::string string
Definition: gtest.h:1979
ElipsoidsDataPointsFilter::DataPoints
PointMatcher< T >::DataPoints DataPoints
Definition: Elipsoids.h:52
ElipsoidsDataPointsFilter::ParameterDoc
Parametrizable::ParameterDoc ParameterDoc
Definition: Elipsoids.h:46
ElipsoidsDataPointsFilter::keepShapes
const bool keepShapes
Definition: Elipsoids.h:96
ElipsoidsDataPointsFilter::BuildData::BuildData
BuildData(Matrix &features, Matrix &descriptors, Int64Matrix &times)
Definition: Elipsoids.h:135
ElipsoidsDataPointsFilter::BuildData::outputInsertionPoint
int outputInsertionPoint
Definition: Elipsoids.h:132
PointMatcher::DataPoints::InvalidField
An exception thrown when one tries to access features or descriptors unexisting or of wrong dimension...
Definition: PointMatcher.h:250
ElipsoidsDataPointsFilter::filter
virtual DataPoints filter(const DataPoints &input)
Definition: Elipsoids.cpp:74
ElipsoidsDataPointsFilter::keepCovariances
const bool keepCovariances
Definition: Elipsoids.h:93
PointMatcherSupport::Parametrizable::ParametersDoc
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
Definition: Parametrizable.h:187
align_sequence.params
params
Definition: align_sequence.py:13
ElipsoidsDataPointsFilter::minPlanarity
const T minPlanarity
Definition: Elipsoids.h:87
ElipsoidsDataPointsFilter
Subsampling Surfels (Elipsoids) filter. First decimate the space until there is at most knn points,...
Definition: Elipsoids.h:41
ElipsoidsDataPointsFilter::ratio
const T ratio
Definition: Elipsoids.h:82
icp.data
data
Definition: icp.py:50
PointMatcher::Matrix
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
ElipsoidsDataPointsFilter::BuildData::means
boost::optional< View > means
Definition: Elipsoids.h:125
ElipsoidsDataPointsFilter::CompareDim::operator()
bool operator()(const int &p0, const int &p1)
Definition: Elipsoids.h:153
ElipsoidsDataPointsFilter::BuildData::times
Int64Matrix & times
Definition: Elipsoids.h:118
PointMatcherSupport::Parametrizable::InvalidParameter
An exception thrown when one tries to fetch the value of an unexisting parameter.
Definition: Parametrizable.h:144
PointMatcher::Vector
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Definition: PointMatcher.h:161
ElipsoidsDataPointsFilter::BuildData::indicesToKeep
Indices indicesToKeep
Definition: Elipsoids.h:115
ElipsoidsDataPointsFilter::maxBoxDim
const T maxBoxDim
Definition: Elipsoids.h:85
ElipsoidsDataPointsFilter::samplingMethod
const unsigned samplingMethod
Definition: Elipsoids.h:84
ElipsoidsDataPointsFilter::P
PointMatcherSupport::Parametrizable P
Definition: Elipsoids.h:44
ElipsoidsDataPointsFilter::BuildData::eigenVectors
boost::optional< View > eigenVectors
Definition: Elipsoids.h:122
ElipsoidsDataPointsFilter::inPlaceFilter
virtual void inPlaceFilter(DataPoints &cloud)
Definition: Elipsoids.cpp:83
ElipsoidsDataPointsFilter::ParametersDoc
Parametrizable::ParametersDoc ParametersDoc
Definition: Elipsoids.h:47
ElipsoidsDataPointsFilter::knn
const unsigned knn
Definition: Elipsoids.h:83
ElipsoidsDataPointsFilter::BuildData::covariance
boost::optional< View > covariance
Definition: Elipsoids.h:124
PointMatcherSupport::Parametrizable
The superclass of classes that are constructed using generic parameters. This class provides the para...
Definition: Parametrizable.h:141
ElipsoidsDataPointsFilter::Matrix
PointMatcher< T >::Matrix Matrix
Definition: Elipsoids.h:51
ElipsoidsDataPointsFilter::availableParameters
static const ParametersDoc availableParameters()
Definition: Elipsoids.h:59
ElipsoidsDataPointsFilter::BuildData::eigenValues
boost::optional< View > eigenValues
Definition: Elipsoids.h:121
ElipsoidsDataPointsFilter::BuildData::Int64Vector
Eigen::Matrix< std::int64_t, 1, Eigen::Dynamic > Int64Vector
Definition: Elipsoids.h:112
ElipsoidsDataPointsFilter::Parameters
Parametrizable::Parameters Parameters
Definition: Elipsoids.h:45
PointMatcherSupport::Parametrizable::ParameterDoc
The documentation of a parameter.
Definition: Parametrizable.h:160
PointMatcher::DataPoints::View
Eigen::Block< Matrix > View
A view on a feature or descriptor.
Definition: PointMatcher.h:210
ElipsoidsDataPointsFilter::BuildData::densities
boost::optional< View > densities
Definition: Elipsoids.h:120
ElipsoidsDataPointsFilter::BuildData::numOfNN
boost::optional< View > numOfNN
Definition: Elipsoids.h:131
ElipsoidsDataPointsFilter::CompareDim::buildData
const BuildData & buildData
Definition: Elipsoids.h:151
ElipsoidsDataPointsFilter::BuildData::weights
boost::optional< View > weights
Definition: Elipsoids.h:123
ElipsoidsDataPointsFilter::BuildData::normals
boost::optional< View > normals
Definition: Elipsoids.h:119
PointMatcher.h
public interface
ElipsoidsDataPointsFilter::InvalidField
PointMatcher< T >::DataPoints::InvalidField InvalidField
Definition: Elipsoids.h:53
ElipsoidsDataPointsFilter::fuseRange
void fuseRange(BuildData &data, const int first, const int last) const
Definition: Elipsoids.cpp:286
ElipsoidsDataPointsFilter::BuildData::pointZ
boost::optional< View > pointZ
Definition: Elipsoids.h:130
ElipsoidsDataPointsFilter::CompareDim::CompareDim
CompareDim(const int dim, const BuildData &buildData)
Definition: Elipsoids.h:152
PointMatcherSupport::Parametrizable::Parameters
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Definition: Parametrizable.h:199
ElipsoidsDataPointsFilter::maxTimeWindow
const T maxTimeWindow
Definition: Elipsoids.h:86
ElipsoidsDataPointsFilter::BuildData::Indices
std::vector< int > Indices
Definition: Elipsoids.h:109
ElipsoidsDataPointsFilter::keepIndices
const bool keepIndices
Definition: Elipsoids.h:97


libpointmatcher
Author(s):
autogenerated on Mon Jan 1 2024 03:24:42