Go to the documentation of this file.
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.";
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" }
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;
141 const int pointsCount(
features.cols());
143 for (
int i = 0; i < pointsCount; ++i)
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;
const bool keepEigenValues
ElipsoidsDataPointsFilter(const Parameters ¶ms=Parameters())
PointMatcherSupport::Parametrizable Parametrizable
PointMatcher< T >::Vector Vector
boost::optional< View > pointIds
const bool averageExistingDescriptors
void buildNew(BuildData &data, const int first, const int last, Vector &&minValues, Vector &&maxValues) const
boost::optional< View > pointX
virtual ~ElipsoidsDataPointsFilter()
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
Functions and classes that are dependant on scalar type are defined in this templatized class.
boost::optional< View > shapes
boost::optional< View > pointY
static const std::string description()
Parametrizable::InvalidParameter InvalidParameter
const bool keepEigenVectors
PointMatcher< T >::DataPoints DataPoints
Parametrizable::ParameterDoc ParameterDoc
BuildData(Matrix &features, Matrix &descriptors, Int64Matrix ×)
An exception thrown when one tries to access features or descriptors unexisting or of wrong dimension...
virtual DataPoints filter(const DataPoints &input)
const bool keepCovariances
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
DataPointsFilter()
Construct without parameter.
Subsampling Surfels (Elipsoids) filter. First decimate the space until there is at most knn points,...
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
boost::optional< View > means
bool operator()(const int &p0, const int &p1)
An exception thrown when one tries to fetch the value of an unexisting parameter.
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
const unsigned samplingMethod
PointMatcherSupport::Parametrizable P
boost::optional< View > eigenVectors
virtual void inPlaceFilter(DataPoints &cloud)
Parametrizable::ParametersDoc ParametersDoc
boost::optional< View > covariance
The superclass of classes that are constructed using generic parameters. This class provides the para...
PointMatcher< T >::Matrix Matrix
static const ParametersDoc availableParameters()
boost::optional< View > eigenValues
Eigen::Matrix< std::int64_t, 1, Eigen::Dynamic > Int64Vector
Parametrizable::Parameters Parameters
The documentation of a parameter.
Eigen::Block< Matrix > View
A view on a feature or descriptor.
boost::optional< View > densities
boost::optional< View > numOfNN
const BuildData & buildData
boost::optional< View > weights
boost::optional< View > normals
PointMatcher< T >::DataPoints::InvalidField InvalidField
void fuseRange(BuildData &data, const int first, const int last) const
boost::optional< View > pointZ
CompareDim(const int dim, const BuildData &buildData)
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
std::vector< int > Indices
mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:39