Elipsoids.cpp
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 #include "Elipsoids.h"
36 
38 
39 // Eigenvalues
40 #include "Eigen/QR"
41 #include "Eigen/Eigenvalues"
42 
43 #include "PointMatcherPrivate.h"
44 
45 // ElipsoidsDataPointsFilter
46 
47 // Constructor
48 template<typename T>
50  PointMatcher<T>::DataPointsFilter("ElipsoidsDataPointsFilter",
51  ElipsoidsDataPointsFilter::availableParameters(), params),
52  ratio(Parametrizable::get<T>("ratio")),
53  knn(Parametrizable::get<int>("knn")),
54  samplingMethod(Parametrizable::get<int>("samplingMethod")),
55  maxBoxDim(Parametrizable::get<T>("maxBoxDim")),
56  maxTimeWindow(Parametrizable::get<T>("maxTimeWindow")),
57  minPlanarity(Parametrizable::get<T>("minPlanarity")),
58  averageExistingDescriptors(Parametrizable::get<bool>("averageExistingDescriptors")),
59  keepNormals(Parametrizable::get<bool>("keepNormals")),
60  keepDensities(Parametrizable::get<bool>("keepDensities")),
61  keepEigenValues(Parametrizable::get<bool>("keepEigenValues")),
62  keepEigenVectors(Parametrizable::get<bool>("keepEigenVectors")),
63  keepCovariances(Parametrizable::get<bool>("keepCovariances")),
64  keepWeights(Parametrizable::get<bool>("keepWeights")),
65  keepMeans(Parametrizable::get<bool>("keepMeans")),
66  keepShapes(Parametrizable::get<bool>("keepShapes")),
67  keepIndices(Parametrizable::get<bool>("keepIndices"))
68 {
69 }
70 
71 // Compute
72 template<typename T>
75 {
76  DataPoints output(input);
77  inPlaceFilter(output);
78  return output;
79 }
80 
81 // In-place filter
82 template<typename T>
84 {
85  typedef typename DataPoints::View View;
86  typedef typename DataPoints::Label Label;
87  typedef typename DataPoints::Labels Labels;
88  typedef typename DataPoints::TimeView TimeView;
89 
90  const int pointsCount(cloud.features.cols());
91  const int featDim(cloud.features.rows());
92  const int descDim(cloud.descriptors.rows());
93  const unsigned int labelDim(cloud.descriptorLabels.size());
94 
95  int insertDim(0);
97  {
98  // TODO: this should be in the form of an assert
99  // Validate descriptors and labels
100  for(unsigned int i = 0; i < labelDim; ++i)
101  insertDim += cloud.descriptorLabels[i].span;
102  if (insertDim != descDim)
103  throw InvalidField("ElipsoidsDataPointsFilter: Error, descriptor labels do not match descriptor data");
104  }
105 
106  // Compute space requirement for new descriptors
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);
116 
117  // Allocate space for new descriptors
118  Labels cloudLabels, timeLabels;
119  if (keepIndices)
120  {
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));
126  }
127  if (keepNormals)
128  cloudLabels.push_back(Label("normals", dimNormals));
129  if (keepDensities)
130  cloudLabels.push_back(Label("densities", dimDensities));
131  if (keepEigenValues)
132  cloudLabels.push_back(Label("eigValues", dimEigValues));
133  if (keepEigenVectors)
134  cloudLabels.push_back(Label("eigVectors", dimEigVectors));
135  if (keepCovariances)
136  cloudLabels.push_back(Label("covariance", dimCovariances));
137  if (keepWeights)
138  cloudLabels.push_back(Label("weights", dimWeights));
139  if (keepMeans)
140  cloudLabels.push_back(Label("means", dimMeans));
141  if (keepShapes)
142  {
143  assert(featDim == 3);
144  cloudLabels.push_back(Label("shapes", dimShapes)); // Planarity, Cylindricality, Sphericality
145  }
146  timeLabels.push_back(Label("time", 2));
147 
148  cloud.allocateDescriptors(cloudLabels);
149  cloud.allocateTimes(timeLabels);
150 
151  // we keep build data on stack for reentrant behaviour
152  View cloudExistingDescriptors(cloud.descriptors.block(0,0,cloud.descriptors.rows(),cloud.descriptors.cols()));
153  TimeView cloudExistingTimes(cloud.times.block(0,0,cloud.times.rows(),cloud.times.cols()));
154  BuildData buildData(cloud.features, cloud.descriptors, cloud.times);
155 
156  // get views
157  if (keepIndices)
158  {
159  buildData.pointIds = cloud.getDescriptorViewByName("pointIds");
160  buildData.pointX = cloud.getDescriptorViewByName("pointX");
161  buildData.pointY = cloud.getDescriptorViewByName("pointY");
162  buildData.pointZ = cloud.getDescriptorViewByName("pointZ");
163  buildData.numOfNN = cloud.getDescriptorViewByName("numOfNN");
164  }
165  if (keepNormals)
166  buildData.normals = cloud.getDescriptorViewByName("normals");
167  if (keepDensities)
168  buildData.densities = cloud.getDescriptorViewByName("densities");
169  if (keepEigenValues)
170  buildData.eigenValues = cloud.getDescriptorViewByName("eigValues");
171  if (keepEigenVectors)
172  buildData.eigenVectors = cloud.getDescriptorViewByName("eigVectors");
173  if (keepCovariances)
174  buildData.covariance = cloud.getDescriptorViewByName("covariance");
175  if (keepWeights)
176  buildData.weights = cloud.getDescriptorViewByName("weights");
177  if (keepMeans)
178  buildData.means = cloud.getDescriptorViewByName("means");
179  if (keepShapes)
180  buildData.shapes = cloud.getDescriptorViewByName("shapes");
181 
182  // build the new point cloud
183  buildNew(
184  buildData,
185  0,
186  pointsCount,
187  cloud.features.rowwise().minCoeff(),
188  cloud.features.rowwise().maxCoeff()
189  );
190 
191  // Bring the data we keep to the front of the arrays then
192  // wipe the leftover unused space.
193  std::sort(buildData.indicesToKeep.begin(), buildData.indicesToKeep.end());
194  const int ptsOut = buildData.indicesToKeep.size();
195  for (int i = 0; i < ptsOut; ++i)
196  {
197  const int k = buildData.indicesToKeep[i];
198  assert(i <= k);
199  cloud.features.col(i) = cloud.features.col(k);
200  cloud.times.col(i) = cloud.times.col(k);
201  if (cloud.descriptors.rows() != 0)
202  cloud.descriptors.col(i) = cloud.descriptors.col(k);
203  if(keepIndices)
204  {
205  buildData.pointIds->col(i) = buildData.pointIds->col(k);
206  buildData.pointX->col(i) = buildData.pointX->col(k);
207  buildData.pointY->col(i) = buildData.pointY->col(k);
208  buildData.pointZ->col(i) = buildData.pointZ->col(k);
209  buildData.numOfNN->col(i) = buildData.numOfNN->col(k);
210  }
211  if(keepNormals)
212  buildData.normals->col(i) = buildData.normals->col(k);
213  if(keepDensities)
214  (*buildData.densities)(0,i) = (*buildData.densities)(0,k);
215  if(keepEigenValues)
216  buildData.eigenValues->col(i) = buildData.eigenValues->col(k);
217  if(keepEigenVectors)
218  buildData.eigenVectors->col(i) = buildData.eigenVectors->col(k);
219  if(keepWeights)
220  buildData.weights->col(i) = buildData.weights->col(k);
221  if(keepCovariances)
222  buildData.covariance->col(i) = buildData.covariance->col(k);
223  if(keepMeans)
224  buildData.means->col(i) = buildData.means->col(k);
225  if(keepShapes)
226  buildData.shapes->col(i) = buildData.shapes->col(k);
227  }
228  cloud.features.conservativeResize(Eigen::NoChange, ptsOut);
229  cloud.descriptors.conservativeResize(Eigen::NoChange, ptsOut);
230  cloud.times.conservativeResize(Eigen::NoChange, ptsOut);
231 
232  // warning if some points were dropped
233  if(buildData.unfitPointsCount != 0)
234  LOG_INFO_STREAM(" ElipsoidsDataPointsFilter - Could not compute normal for " << buildData.unfitPointsCount << " pts.");
235 }
236 
237 template<typename T>
239  BuildData& data, const int first, const int last,
240  Vector&& minValues, Vector&& maxValues) const
241 {
242  using namespace PointMatcherSupport;
243 
244  const int count(last - first);
245  if (count <= int(knn))
246  {
247  // compute for this range
248  fuseRange(data, first, last);
249  // typically by stopping recursion after the median of the bounding cuboid
250  // is below a threshold, or that the number of points falls under a threshold
251  return;
252  }
253  // find the largest dimension of the box
254  const int cutDim = argMax<T>(maxValues - minValues);
255 
256  // compute number of elements
257  const int rightCount(count/2);
258  const int leftCount(count - rightCount);
259  assert(last - rightCount == first + leftCount);
260 
261  // sort, hack std::nth_element
262  std::nth_element(
263  data.indices.begin() + first,
264  data.indices.begin() + first + leftCount,
265  data.indices.begin() + last,
266  CompareDim(cutDim, data)
267  );
268 
269  // get value
270  const int cutIndex(data.indices[first+leftCount]);
271  const T cutVal(data.features(cutDim, cutIndex));
272 
273  // update bounds for left
274  Vector leftMaxValues(maxValues);
275  leftMaxValues[cutDim] = cutVal;
276  // update bounds for right
277  Vector rightMinValues(minValues);
278  rightMinValues[cutDim] = cutVal;
279 
280  // recurse
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));
283 }
284 
285 template<typename T>
287  BuildData& data, const int first, const int last) const
288 {
289  using namespace PointMatcherSupport;
290 
291  typedef typename Eigen::Matrix<std::int64_t, Eigen::Dynamic, Eigen::Dynamic> Int64Matrix;
292 
293  const int colCount(last-first);
294  const int featDim(data.features.rows());
295 
296  // build nearest neighbors list
297  Matrix d(featDim-1, colCount);
298  Int64Matrix t(1, colCount);
299  for (int i = 0; i < colCount; ++i)
300  {
301  d.col(i) = data.features.block(0,data.indices[first+i],featDim-1, 1);
302  t.col(i) = data.times.col(data.indices[first + i]); //, 0);
303  }
304  const Vector box = d.rowwise().maxCoeff() - d.rowwise().minCoeff();
305  const std::int64_t timeBox = t.maxCoeff() - t.minCoeff();
306 
307  const T boxDim(box.maxCoeff());
308  // drop box if it is too large or max timeframe is exceeded
309  if (boxDim > maxBoxDim || timeBox > maxTimeWindow)
310  {
311  data.unfitPointsCount += colCount;
312  return;
313  }
314  const Vector mean = d.rowwise().sum() / T(colCount);
315  const Matrix NN = (d.colwise() - mean);
316 
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);
320 
321  // compute covariance
322  const Matrix C(NN * NN.transpose());
323  Vector eigenVa = Vector::Identity(featDim-1, 1);
324  Matrix eigenVe = Matrix::Identity(featDim-1, featDim-1);
325  // Ensure that the matrix is suited for eigenvalues calculation
327  {
328  if(C.fullPivHouseholderQr().rank()+1 >= featDim-1)
329  {
330  const Eigen::EigenSolver<Matrix> solver(C);
331  eigenVa = solver.eigenvalues().real();
332  eigenVe = solver.eigenvectors().real();
333  }
334  else
335  {
336  data.unfitPointsCount += colCount;
337  return;
338  }
339  if(minPlanarity > 0)
340  {
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);
345  // throw out surfel if it does not meet planarity criteria
346  if (planarity < minPlanarity)
347  {
348  data.unfitPointsCount += colCount;
349  return;
350  }
351  }
352  }
353 
354  // keep the indices of each ellipsoid
355  Vector pointIds(1,colCount);
356  Matrix points(3,colCount);
357 
358  if(keepIndices)
359  {
360  for (int i = 0; i < colCount; ++i)
361  {
362  pointIds(i) = data.indices[first+i];
363  points.col(i) = data.features.block(0,data.indices[first+i],2, 1);
364  }
365  }
366 
367  Vector normal;
368  if(keepNormals)
369  normal = computeNormal<T>(eigenVa, eigenVe);
370 
371  T density = 0;
372  if(keepDensities)
373  density = computeDensity<T>(NN);
374  Vector serialEigVector;
375  if(keepEigenVectors)
376  serialEigVector = serializeEigVec<T>(eigenVe);
377  Vector serialCovVector;
378  if(keepCovariances)
379  serialCovVector = serializeEigVec<T>(C);
380 
381  // some safety check
382  if(data.descriptors.rows() != 0)
383  assert(data.descriptors.cols() != 0);
384 
385  // Filter points randomly
386  if(samplingMethod == 0)
387  {
388  for(int i=0; i<colCount; ++i)
389  {
390  const float r = (float)std::rand()/(float)RAND_MAX;
391  if(r < ratio)
392  {
393  // Keep points with their descriptors
394  const int k = data.indices[first+i];
395  // Mark the indices which will be part of the final data
396  data.indicesToKeep.push_back(k);
397 
398  // write the updated times: min, max, mean
399  data.times(0, k) = minTime;
400  data.times(1, k) = maxTime;
401  data.times(2, k) = meanTime;
402 
403  // Build new descriptors
404  if(keepIndices)
405  {
406  data.pointIds->col(k) = pointIds;
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();
411  }
412  if(keepNormals)
413  data.normals->col(k) = normal;
414  if(keepDensities)
415  (*data.densities)(0,k) = density;
416  if(keepEigenValues)
417  data.eigenValues->col(k) = eigenVa;
418  if(keepEigenVectors)
419  data.eigenVectors->col(k) = serialEigVector;
420  if(keepCovariances)
421  data.covariance->col(k) = serialCovVector;
422  if(keepMeans)
423  data.means->col(k) = mean;
424  // a 3d vecetor of shape parameters: planarity (P), cylindricality (C), sphericality (S)
425  if(keepShapes)
426  {
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;
433 
434  }
435  if(keepWeights)
436  {
437  (*data.weights)(0,k) = colCount;
438  }
439  }
440  }
441  }
442  else
443  {
444  const int k = data.indices[first];
445  // Mark the indices which will be part of the final data
446  data.indicesToKeep.push_back(k);
447  data.features.col(k).topRows(featDim-1) = mean;
448  // write the updated times: min, max, mean
449  data.times(0, k) = minTime;
450  data.times(1, k) = maxTime;
451  data.times(2, k) = meanTime;
452 
453  data.features(featDim-1, k) = 1;
454 
455  if(data.descriptors.rows() != 0)
456  {
457  // average the existing descriptors
459  {
460  Vector mergedDesc(Vector::Zero(data.descriptors.rows()));
461  for (int i = 0; i < colCount; ++i)
462  mergedDesc += data.descriptors.col(data.indices[first+i]);
463  mergedDesc /= T(colCount);
464  data.descriptors.col(k) = mergedDesc;
465  }
466  // else just keep the first one
467  }
468 
469  // Build new descriptors
470  if(keepIndices)
471  {
472  data.pointIds->col(k) = pointIds;
473  data.pointX->col(k) = points.row(0);
474  data.pointY->col(k) = points.row(1);
475  data.pointZ->col(k) = points.row(2);
476  }
477  if(keepNormals)
478  data.normals->col(k) = normal;
479  if(keepDensities)
480  (*data.densities)(0,k) = density;
481  if(keepEigenValues)
482  data.eigenValues->col(k) = eigenVa;
483  if(keepEigenVectors)
484  data.eigenVectors->col(k) = serialEigVector;
485  if(keepCovariances)
486  data.covariance->col(k) = serialCovVector;
487  if(keepMeans)
488  data.means->col(k) = mean;
489  if(keepShapes)
490  {
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; //eigenVa;
497  }
498  if(keepWeights)
499  (*data.weights)(0,k) = colCount;
500  }
501 
502 }
503 
504 template struct ElipsoidsDataPointsFilter<float>;
505 template struct ElipsoidsDataPointsFilter<double>;
506 
#define LOG_INFO_STREAM(args)
boost::optional< View > shapes
Definition: Elipsoids.h:126
void allocateTimes(const Labels &newLabels)
Make sure a vector of time of given names exist.
const bool keepCovariances
Definition: Elipsoids.h:93
PointMatcher< T >::DataPoints::InvalidField InvalidField
Definition: Elipsoids.h:53
DataPoints::Label Label
Matrix descriptors
descriptors of points in the cloud, might be empty
Definition: PointMatcher.h:333
Eigen::Block< Int64Matrix > TimeView
A view on a time.
Definition: PointMatcher.h:212
boost::optional< View > pointIds
Definition: Elipsoids.h:127
boost::optional< View > numOfNN
Definition: Elipsoids.h:131
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
Definition: Elipsoids.h:130
data
Definition: icp.py:50
const bool averageExistingDescriptors
Definition: Elipsoids.h:88
virtual void inPlaceFilter(DataPoints &cloud)
Definition: Elipsoids.cpp:83
void fuseRange(BuildData &data, const int first, const int last) const
Definition: Elipsoids.cpp:286
PointMatcher< T >::Vector Vector
Definition: Elipsoids.h:50
boost::optional< View > means
Definition: Elipsoids.h:125
The name for a certain number of dim.
Definition: PointMatcher.h:221
PointMatcher< T >::Matrix Matrix
Definition: Elipsoids.h:51
boost::optional< View > eigenVectors
Definition: Elipsoids.h:122
Functions and classes that are not dependant on scalar type are defined in this namespace.
const unsigned samplingMethod
Definition: Elipsoids.h:84
void buildNew(BuildData &data, const int first, const int last, Vector &&minValues, Vector &&maxValues) const
Definition: Elipsoids.cpp:238
DataPoints::Labels Labels
Functions and classes that are dependant on scalar type are defined in this templatized class...
Definition: PointMatcher.h:130
PM::Int64Matrix Int64Matrix
boost::optional< View > pointY
Definition: Elipsoids.h:129
const unsigned knn
Definition: Elipsoids.h:83
boost::optional< View > covariance
Definition: Elipsoids.h:124
boost::optional< View > densities
Definition: Elipsoids.h:120
ElipsoidsDataPointsFilter(const Parameters &params=Parameters())
Definition: Elipsoids.cpp:49
const M::mapped_type & get(const M &m, const typename M::key_type &k)
boost::optional< View > eigenValues
Definition: Elipsoids.h:121
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.
Definition: PointMatcher.h:210
const bool keepDensities
Definition: Elipsoids.h:90
boost::optional< View > normals
Definition: Elipsoids.h:119
Int64Matrix times
time associated to each points, might be empty
Definition: PointMatcher.h:335
Parametrizable::Parameters Parameters
Definition: Elipsoids.h:45
boost::optional< View > weights
Definition: Elipsoids.h:123
const bool keepEigenValues
Definition: Elipsoids.h:91
Matrix features
features of points in the cloud
Definition: PointMatcher.h:331
PM::DataPointsFilter DataPointsFilter
boost::optional< View > pointX
Definition: Elipsoids.h:128
virtual DataPoints filter(const DataPoints &input)
Definition: Elipsoids.cpp:74
void allocateDescriptors(const Labels &newLabels)
Make sure a vector of descriptors of given names exist.
const bool keepEigenVectors
Definition: Elipsoids.h:92
Labels descriptorLabels
labels of descriptors
Definition: PointMatcher.h:334
Subsampling Surfels (Elipsoids) filter. First decimate the space until there is at most knn points...
Definition: Elipsoids.h:41


libpointmatcher
Author(s):
autogenerated on Sat May 27 2023 02:36:30