44 k{Parametrizable::get<std::size_t>(
"k")},
45 sigma{Parametrizable::get<T>(
"sigma")},
46 radius{Parametrizable::get<T>(
"radius")},
47 itMax{Parametrizable::get<std::size_t>(
"itMax")},
48 keepNormals{Parametrizable::get<bool>(
"keepNormals")},
49 keepLabels{Parametrizable::get<bool>(
"keepLabels")},
50 keepLambdas{Parametrizable::get<bool>(
"keepLambdas")},
51 keepTensors{Parametrizable::get<bool>(
"keepTensors")}
75 tv.cfvote(cloud,
true);
82 const std::size_t itMax_ =
itMax;
83 const std::size_t k_ =
k;
84 std::size_t oldnbPts = nbPts;
86 auto checkConvergence = [&oldnbPts, &it, &itMax_, &k_](
const DataPoints& pts,
const std::size_t threshold)
mutable ->
bool{
87 const std::size_t nbPts = pts.getNbPoints();
88 bool ret = (oldnbPts - nbPts) < threshold;
92 return ret or ++it >= itMax_ or k_ >= nbPts;
110 tv.cfvote(cloud,
true);
116 while(not checkConvergence(cloud, 5 ));
133 template <
typename T>
138 Matrix labels = Matrix::Zero(1, nbPts);
139 Matrix l1 = PM::Matrix::Zero(1, nbPts);
140 Matrix l2 = PM::Matrix::Zero(1, nbPts);
141 Matrix l3 = PM::Matrix::Zero(1, nbPts);
143 if(keepLabels_ or keepLambdas_)
145 #pragma omp parallel for 146 for(std::size_t i = 0; i < nbPts; ++i)
153 Vector coeff = (
Vector(3) << lambda3, (lambda2 - lambda3), (lambda1 - lambda2)).finished();
154 coeff.maxCoeff(&index);
156 labels(i) = index + 1 ;
193 std::cerr <<
"SpectralDecomposition<T>::inPlaceFilter::addDescriptor: Cannot add descriptors to pointcloud" << std::endl;
202 template <
typename T>
205 static constexpr
int POINT = 0;
206 static constexpr
int CURVE = 1;
207 static constexpr
int SURFACE = 2;
209 static constexpr
T th = 0.1;
219 for (std::size_t i = 0; i < nbPts; ++i)
226 (
Vector(3) << pointness, curveness, surfaceness).finished().maxCoeff(&label);
228 bool keepPt = ((label == POINT) and (pointness >= th_p))
229 or ((label == CURVE) and (curveness >= th_c))
230 or ((label == SURFACE) and (surfaceness >= th_s));
244 template <
typename T>
247 constexpr std::size_t seed = 1;
248 std::mt19937 gen(seed);
249 std::uniform_real_distribution<> uni01(0., 1.);
256 throw InvalidField(
"SpectralDecomposition<T>::filter: Error, lambdas field not found in descriptors.");
264 for (std::size_t i = 0; i < nbPts; ++i)
266 const T randv = uni01(gen);
268 const T nl1 = lambda1(0,i) /
k;
269 const T nl2 = lambda2(0,i) /
k;
270 const T nl3 = lambda3(0,i) /
k;
272 if (nl1 < xi or nl2 < 0.75 * xi or nl3 < 0.75 * xi or randv < 0.5)
281 template <
typename T>
284 constexpr std::size_t seed = 1;
285 std::mt19937 gen(seed);
286 std::uniform_real_distribution<> uni01(0., 1.);
293 throw InvalidField(
"SpectralDecomposition<T>::filter: Error, lambdas field not found in descriptors.");
301 for (std::size_t i = 0; i < nbPts; ++i)
303 const T randv = uni01(gen);
305 const T nl1 = lambda1(0,i) /
k;
306 const T nl2 = lambda2(0,i) /
k;
307 const T nl3 = lambda3(0,i) /
k;
309 if (nl1 < xi or nl2 < xi or nl3 < 0.5 * xi or randv < 0.5)
318 template <
typename T>
321 constexpr std::size_t seed = 1;
322 std::mt19937 gen(seed);
323 std::uniform_real_distribution<> uni01(0., 1.);
330 throw InvalidField(
"SpectralDecomposition<T>::filter: Error, lambdas field not found in descriptors.");
338 for (std::size_t i = 0; i < nbPts; ++i)
340 const T randv = uni01(gen);
342 const T nl1 = lambda1(0,i) /
k;
343 const T nl2 = lambda2(0,i) /
k;
344 const T nl3 = lambda3(0,i) /
k;
346 if (nl1 < (5./6.) * xi or nl2 < (5./6.) * xi or nl3 < (5./6.) * xi or randv < 0.2)
Parametrizable::Parameters Parameters
void setColFrom(Index thisCol, const DataPoints &that, Index thatCol)
Set column thisCol equal to column thatCol of that, copy features and descriptors if any...
void filterPointness(DataPoints &pts, T xi, std::size_t k) const
void addDescriptor(DataPoints &pts, const TensorVoting< T > &tv, bool keepNormals_, bool keepLabels_, bool keepLambdas_, bool keepTensors_) const
SpectralDecompositionDataPointsFilter(const Parameters ¶ms=Parameters())
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
void filterSurfaceness(DataPoints &pts, T xi, std::size_t k) const
void removeOutlier(DataPoints &pts, const TensorVoting< T > &tv) const
unsigned getNbPoints() const
Return the number of points contained in the point cloud.
virtual DataPoints filter(const DataPoints &input)
Apply filters to input point cloud. This is the non-destructive version and returns a copy...
virtual void inPlaceFilter(DataPoints &cloud)
Apply these filters to a point cloud without copying.
PointMatcher< T >::DataPoints::InvalidField InvalidField
void filterCurveness(DataPoints &pts, T xi, std::size_t k) const
static T xi_expectation(const std::size_t D, const T sigma_, const T radius_)
Functions and classes that are dependant on scalar type are defined in this templatized class...
bool descriptorExists(const std::string &name) const
Look if a descriptor with a given name exist.
A data filter takes a point cloud as input, transforms it, and produces another point cloud as output...
void conservativeResize(Index pointCount)
Resize the cloud to pointCount points, conserving existing ones.
void addDescriptor(const std::string &name, const Matrix &newDescriptor)
Add a descriptor by name, remove first if already exists.