41 #include "Eigen/Eigenvalues" 58 averageExistingDescriptors(
Parametrizable::
get<bool>(
"averageExistingDescriptors")),
90 const int pointsCount(cloud.
features.cols());
91 const int featDim(cloud.
features.rows());
100 for(
unsigned int i = 0; i < labelDim; ++i)
102 if (insertDim != descDim)
103 throw InvalidField(
"ElipsoidsDataPointsFilter: Error, descriptor labels do not match descriptor data");
107 const int dimNormals(featDim-1);
108 const int dimDensities(1);
109 const int dimEigValues(featDim-1);
110 const int dimEigVectors((featDim-1)*(featDim-1));
111 const int dimWeights(1);
112 const int dimMeans(featDim-1);
113 const int dimCovariances((featDim-1)*(featDim-1));
114 const int dimShapes(featDim-1);
115 const int dimPointIds(
knn);
118 Labels cloudLabels, timeLabels;
121 cloudLabels.push_back(
Label(
"pointIds", dimPointIds));
122 cloudLabels.push_back(
Label(
"pointX", dimPointIds));
123 cloudLabels.push_back(
Label(
"pointY", dimPointIds));
124 cloudLabels.push_back(
Label(
"pointZ", dimPointIds));
125 cloudLabels.push_back(
Label(
"numOfNN", 1));
128 cloudLabels.push_back(
Label(
"normals", dimNormals));
130 cloudLabels.push_back(
Label(
"densities", dimDensities));
132 cloudLabels.push_back(
Label(
"eigValues", dimEigValues));
134 cloudLabels.push_back(
Label(
"eigVectors", dimEigVectors));
136 cloudLabels.push_back(
Label(
"covariance", dimCovariances));
138 cloudLabels.push_back(
Label(
"weights", dimWeights));
140 cloudLabels.push_back(
Label(
"means", dimMeans));
143 assert(featDim == 3);
144 cloudLabels.push_back(
Label(
"shapes", dimShapes));
146 timeLabels.push_back(
Label(
"time", 2));
153 TimeView cloudExistingTimes(cloud.
times.block(0,0,cloud.
times.rows(),cloud.
times.cols()));
187 cloud.
features.rowwise().minCoeff(),
195 for (
int i = 0; i < ptsOut; ++i)
224 buildData.
means->col(i) = buildData.
means->col(k);
228 cloud.
features.conservativeResize(Eigen::NoChange, ptsOut);
229 cloud.
descriptors.conservativeResize(Eigen::NoChange, ptsOut);
230 cloud.
times.conservativeResize(Eigen::NoChange, ptsOut);
244 const int count(last - first);
245 if (count <=
int(
knn))
254 const int cutDim = argMax<T>(maxValues - minValues);
257 const int rightCount(count/2);
258 const int leftCount(count - rightCount);
259 assert(last - rightCount == first + leftCount);
264 data.
indices.begin() + first + leftCount,
270 const int cutIndex(data.
indices[first+leftCount]);
271 const T cutVal(data.
features(cutDim, cutIndex));
274 Vector leftMaxValues(maxValues);
275 leftMaxValues[cutDim] = cutVal;
277 Vector rightMinValues(minValues);
278 rightMinValues[cutDim] = cutVal;
281 buildNew(data, first, first + leftCount, std::forward<Vector>(minValues), std::move(leftMaxValues));
282 buildNew(data, first + leftCount, last, std::move(rightMinValues), std::forward<Vector>(maxValues));
291 typedef typename Eigen::Matrix<std::int64_t, Eigen::Dynamic, Eigen::Dynamic>
Int64Matrix;
293 const int colCount(last-first);
294 const int featDim(data.
features.rows());
297 Matrix d(featDim-1, colCount);
298 Int64Matrix t(1, colCount);
299 for (
int i = 0; i < colCount; ++i)
304 const Vector box = d.rowwise().maxCoeff() - d.rowwise().minCoeff();
305 const std::int64_t timeBox = t.maxCoeff() - t.minCoeff();
307 const T boxDim(box.maxCoeff());
314 const Vector mean = d.rowwise().sum() /
T(colCount);
315 const Matrix NN = (d.colwise() - mean);
317 const std::int64_t minTime = t.minCoeff();
318 const std::int64_t maxTime = t.maxCoeff();
319 const std::int64_t meanTime = t.sum() /
T(colCount);
322 const Matrix C(NN * NN.transpose());
323 Vector eigenVa = Vector::Identity(featDim-1, 1);
324 Matrix eigenVe = Matrix::Identity(featDim-1, featDim-1);
328 if(C.fullPivHouseholderQr().rank()+1 >= featDim-1)
330 const Eigen::EigenSolver<Matrix> solver(C);
331 eigenVa = solver.eigenvalues().real();
332 eigenVe = solver.eigenvectors().real();
341 Eigen::Matrix<T, 3, 1> vals;
342 (vals << eigenVa(0),eigenVa(1),eigenVa(2));
343 vals = vals/eigenVa.sum();
344 const T planarity = 2 * vals(1)-2*vals(2);
355 Vector pointIds(1,colCount);
356 Matrix points(3,colCount);
360 for (
int i = 0; i < colCount; ++i)
362 pointIds(i) = data.
indices[first+i];
369 normal = computeNormal<T>(eigenVa, eigenVe);
373 density = computeDensity<T>(NN);
376 serialEigVector = serializeEigVec<T>(eigenVe);
379 serialCovVector = serializeEigVec<T>(C);
388 for(
int i=0; i<colCount; ++i)
390 const float r = (float)std::rand()/(float)RAND_MAX;
394 const int k = data.
indices[first+i];
399 data.
times(0, k) = minTime;
400 data.
times(1, k) = maxTime;
401 data.
times(2, k) = meanTime;
407 data.
pointX->col(k) = points.row(0);
408 data.
pointY->col(k) = points.row(1);
409 data.
pointZ->col(k) = points.row(2);
410 (*data.
numOfNN)(0,k) = NN.cols();
423 data.
means->col(k) = mean;
427 Eigen::Matrix<T, 3, 3> shapeMat;
428 (shapeMat << 0, 2, -2, 1, -1, 0, 0, 0, 3);
429 Eigen::Matrix<T, 3, 1> vals;
430 (vals << eigenVa(0),eigenVa(1),eigenVa(2));
431 vals = vals/eigenVa.sum();
432 data.
shapes->col(k) = shapeMat * vals;
437 (*data.
weights)(0,k) = colCount;
444 const int k = data.
indices[first];
447 data.
features.col(k).topRows(featDim-1) = mean;
449 data.
times(0, k) = minTime;
450 data.
times(1, k) = maxTime;
451 data.
times(2, k) = meanTime;
461 for (
int i = 0; i < colCount; ++i)
463 mergedDesc /=
T(colCount);
473 data.
pointX->col(k) = points.row(0);
474 data.
pointY->col(k) = points.row(1);
475 data.
pointZ->col(k) = points.row(2);
488 data.
means->col(k) = mean;
491 Eigen::Matrix<T, 3, 3> shapeMat;
492 (shapeMat << 0, 2, -2, 1, -1, 0, 0, 0, 3);
493 Eigen::Matrix<T, 3, 1> vals;
494 (vals << eigenVa(0),eigenVa(1),eigenVa(2));
495 vals = vals/eigenVa.sum();
496 data.
shapes->col(k) = shapeMat * vals;
499 (*data.
weights)(0,k) = colCount;
#define LOG_INFO_STREAM(args)
boost::optional< View > shapes
void allocateTimes(const Labels &newLabels)
Make sure a vector of time of given names exist.
const bool keepCovariances
PointMatcher< T >::DataPoints::InvalidField InvalidField
Matrix descriptors
descriptors of points in the cloud, might be empty
Eigen::Block< Int64Matrix > TimeView
A view on a time.
boost::optional< View > pointIds
boost::optional< View > numOfNN
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
boost::optional< View > pointZ
const bool averageExistingDescriptors
virtual void inPlaceFilter(DataPoints &cloud)
void fuseRange(BuildData &data, const int first, const int last) const
PointMatcher< T >::Vector Vector
boost::optional< View > means
The name for a certain number of dim.
PointMatcher< T >::Matrix Matrix
boost::optional< View > eigenVectors
Functions and classes that are not dependant on scalar type are defined in this namespace.
const unsigned samplingMethod
void buildNew(BuildData &data, const int first, const int last, Vector &&minValues, Vector &&maxValues) const
DataPoints::Labels Labels
Functions and classes that are dependant on scalar type are defined in this templatized class...
PM::Int64Matrix Int64Matrix
boost::optional< View > pointY
boost::optional< View > covariance
boost::optional< View > densities
ElipsoidsDataPointsFilter(const Parameters ¶ms=Parameters())
const M::mapped_type & get(const M &m, const typename M::key_type &k)
boost::optional< View > eigenValues
The superclass of classes that are constructed using generic parameters. This class provides the para...
Eigen::Block< Matrix > View
A view on a feature or descriptor.
boost::optional< View > normals
Int64Matrix times
time associated to each points, might be empty
Parametrizable::Parameters Parameters
boost::optional< View > weights
const bool keepEigenValues
Matrix features
features of points in the cloud
PM::DataPointsFilter DataPointsFilter
boost::optional< View > pointX
virtual DataPoints filter(const DataPoints &input)
void allocateDescriptors(const Labels &newLabels)
Make sure a vector of descriptors of given names exist.
const bool keepEigenVectors
Labels descriptorLabels
labels of descriptors
Subsampling Surfels (Elipsoids) filter. First decimate the space until there is at most knn points...