38#ifndef PCL_VOXEL_GRID_COVARIANCE_IMPL_H_
39#define PCL_VOXEL_GRID_COVARIANCE_IMPL_H_
42#include <pcl/common/point_tests.h>
43#include <pcl/filters/voxel_grid_covariance.h>
44#include <Eigen/Cholesky>
45#include <Eigen/Eigenvalues>
46#include <boost/mpl/size.hpp>
47#include <boost/random/mersenne_twister.hpp>
48#include <boost/random/normal_distribution.hpp>
49#include <boost/random/variate_generator.hpp>
52template<
typename Po
intT>
void
60 PCL_WARN (
"[pcl::%s::applyFilter] No input dataset given!\n",
getClassName ().c_str ());
61 output.width = output.height = 0;
68 output.is_dense =
true;
71 Eigen::Vector4f min_p, max_p;
79 std::int64_t dx =
static_cast<std::int64_t
>((max_p[0] - min_p[0]) *
inverse_leaf_size_[0])+1;
80 std::int64_t dy =
static_cast<std::int64_t
>((max_p[1] - min_p[1]) *
inverse_leaf_size_[1])+1;
81 std::int64_t dz =
static_cast<std::int64_t
>((max_p[2] - min_p[2]) *
inverse_leaf_size_[2])+1;
83 if((dx*dy*dz) > std::numeric_limits<std::int32_t>::max())
85 PCL_WARN(
"[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.\n",
getClassName().c_str());
108 int centroid_size = 4;
111 centroid_size = boost::mpl::size<FieldList>::value;
114 std::vector<pcl::PCLPointField>
fields;
117 if (rgba_index == -1)
121 rgba_index =
fields[rgba_index].offset;
129 std::vector<pcl::PCLPointField>
fields;
131 if (distance_idx == -1)
132 PCL_WARN (
"[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n",
getClassName ().c_str (), distance_idx);
135 for (
const auto& point: *
input_)
143 const auto* pt_data =
reinterpret_cast<const std::uint8_t*
> (&point);
144 float distance_value = 0;
145 memcpy (&distance_value, pt_data +
fields[distance_idx].offset,
sizeof (
float));
161 const Eigen::Vector4i ijk =
163 .template cast<int>();
170 leaf.
centroid.resize (centroid_size);
174 Eigen::Vector3d pt3d = point.getVector3fMap().template cast<double>();
178 leaf.
cov_.noalias() += pt3d * pt3d.transpose ();
183 leaf.
centroid.template head<3> () += point.getVector3fMap();
188 Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
194 const pcl::RGB& rgb = *
reinterpret_cast<const RGB*
> (
reinterpret_cast<const char*
> (&point) + rgba_index);
195 centroid[centroid_size - 4] = rgb.a;
196 centroid[centroid_size - 3] = rgb.r;
197 centroid[centroid_size - 2] = rgb.g;
198 centroid[centroid_size - 1] = rgb.b;
209 for (
const auto& point: *
input_)
217 const Eigen::Vector4i ijk =
219 .template cast<int>();
226 leaf.
centroid.resize (centroid_size);
230 Eigen::Vector3d pt3d = point.getVector3fMap().template cast<double>();
234 leaf.
cov_.noalias() += pt3d * pt3d.transpose ();
239 leaf.
centroid.template head<3> () += point.getVector3fMap();
244 Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
250 const pcl::RGB& rgb = *
reinterpret_cast<const RGB*
> (
reinterpret_cast<const char*
> (&point) + rgba_index);
251 centroid[centroid_size - 4] = rgb.a;
252 centroid[centroid_size - 3] = rgb.r;
253 centroid[centroid_size - 2] = rgb.g;
254 centroid[centroid_size - 1] = rgb.b;
263 output.reserve (
leaves_.size ());
271 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigensolver;
272 Eigen::Matrix3d eigen_val;
273 Eigen::Vector3d pt_sum;
276 double min_covar_eigvalue;
282 Leaf& leaf = it->second;
298 output.push_back (PointT ());
303 output.back ().x = leaf.
centroid[0];
304 output.back ().y = leaf.
centroid[1];
305 output.back ().z = leaf.
centroid[2];
313 pcl::RGB& rgb = *
reinterpret_cast<RGB*
> (
reinterpret_cast<char*
> (&output.back ()) + rgba_index);
314 rgb.a = leaf.
centroid[centroid_size - 4];
315 rgb.r = leaf.
centroid[centroid_size - 3];
316 rgb.g = leaf.
centroid[centroid_size - 2];
317 rgb.b = leaf.
centroid[centroid_size - 1];
329 eigensolver.compute (leaf.
cov_);
330 eigen_val = eigensolver.eigenvalues ().asDiagonal ();
331 leaf.
evecs_ = eigensolver.eigenvectors ();
333 if (eigen_val (0, 0) < -Eigen::NumTraits<double>::dummy_precision () || eigen_val (1, 1) < -Eigen::NumTraits<double>::dummy_precision () || eigen_val (2, 2) <= 0)
335 PCL_WARN (
"[VoxelGridCovariance::applyFilter] Invalid eigen value! (%g, %g, %g)\n", eigen_val (0, 0), eigen_val (1, 1), eigen_val (2, 2));
343 if (eigen_val (0, 0) < min_covar_eigvalue)
345 eigen_val (0, 0) = min_covar_eigvalue;
347 if (eigen_val (1, 1) < min_covar_eigvalue)
349 eigen_val (1, 1) = min_covar_eigvalue;
354 leaf.
evals_ = eigen_val.diagonal ();
357 if (leaf.
icov_.maxCoeff () == std::numeric_limits<float>::infinity ( )
358 || leaf.
icov_.minCoeff () == -std::numeric_limits<float>::infinity ( ) )
366 output.width = output.size ();
370template<
typename Po
intT>
int
376 Eigen::Vector4i ijk = Eigen::floor(reference_point.getArray4fMap() *
inverse_leaf_size_).template cast<int>();
378 const Eigen::Array4i diff2min =
min_b_ - ijk;
379 const Eigen::Array4i diff2max =
max_b_ - ijk;
380 neighbors.reserve (relative_coordinates.cols ());
383 for (Eigen::Index ni = 0; ni < relative_coordinates.cols (); ni++)
385 const Eigen::Vector4i displacement = (Eigen::Vector4i () << relative_coordinates.col (ni), 0).finished ();
387 if ((diff2min <= displacement.array ()).all () && (diff2max >= displacement.array ()).all ())
393 neighbors.push_back (leaf);
398 return static_cast<int> (neighbors.size());
402template<
typename Po
intT>
int
410template<
typename Po
intT>
int
413 return getNeighborhoodAtPoint(Eigen::Matrix<int, 3, Eigen::Dynamic>::Zero(3,1), reference_point, neighbors);
417template<
typename Po
intT>
int
420 Eigen::Matrix<int, 3, Eigen::Dynamic> relative_coordinates(3, 7);
421 relative_coordinates.setZero();
422 relative_coordinates(0, 1) = 1;
423 relative_coordinates(0, 2) = -1;
424 relative_coordinates(1, 3) = 1;
425 relative_coordinates(1, 4) = -1;
426 relative_coordinates(2, 5) = 1;
427 relative_coordinates(2, 6) = -1;
433template<
typename Po
intT>
int
436 Eigen::Matrix<int, 3, Eigen::Dynamic> relative_coordinates(3, 27);
437 relative_coordinates.col(0).setZero();
444template<
typename Po
intT>
void
451 boost::normal_distribution<> nd (0.0, 1.0);
452 boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
454 Eigen::LLT<Eigen::Matrix3d> llt_of_cov;
455 Eigen::Matrix3d cholesky_decomp;
456 Eigen::Vector3d cell_mean;
457 Eigen::Vector3d rand_point;
458 Eigen::Vector3d dist_point;
461 [
this] (
auto& l) { return (l.second.nr_points >= min_points_per_voxel_); }));
466 const Leaf& leaf = it->second;
470 cell_mean = leaf.
mean_;
471 llt_of_cov.compute (leaf.
cov_);
472 cholesky_decomp = llt_of_cov.matrixL ();
475 for (
int i = 0; i < pnt_per_cell; i++)
477 rand_point = Eigen::Vector3d (var_nor (), var_nor (), var_nor ());
478 dist_point.noalias() = cell_mean + cholesky_decomp * rand_point;
479 cell_cloud.
push_back (
PointXYZ (
static_cast<float> (dist_point (0)),
static_cast<float> (dist_point (1)),
static_cast<float> (dist_point (2))));
485#define PCL_INSTANTIATE_VoxelGridCovariance(T) template class PCL_EXPORTS pcl::VoxelGridCovariance<T>;
const std::string & getClassName() const
Get a string representation of the name of this class.
PointCloudConstPtr input_
The input point cloud dataset.
PointCloud represents the base class in PCL for storing collections of 3D points.
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
void clear()
Removes all points in a cloud and sets the width and height to 0.
void reserve(std::size_t n)
void applyFilter(PointCloud &output) override
Filter cloud and initializes voxel structure.
int min_points_per_voxel_
Minimum points contained with in a voxel to allow it to be usable.
typename Filter< PointT >::PointCloud PointCloud
void getDisplayCloud(pcl::PointCloud< PointXYZ > &cell_cloud, int pnt_per_cell=1000) const
Get a cloud to visualize each voxels normal distribution.
int getAllNeighborsAtPoint(const PointT &reference_point, std::vector< LeafConstPtr > &neighbors) const
Get all 3x3x3 neighbor voxels of p (up to 27 voxels).
int getVoxelAtPoint(const PointT &reference_point, std::vector< LeafConstPtr > &neighbors) const
Get the voxel at p.
bool searchable_
Flag to determine if voxel structure is searchable.
double min_covar_eigvalue_mult_
Minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
const Leaf * LeafConstPtr
Const pointer to VoxelGridCovariance leaf structure.
int getNeighborhoodAtPoint(const Eigen::Matrix< int, 3, Eigen::Dynamic > &relative_coordinates, const PointT &reference_point, std::vector< LeafConstPtr > &neighbors) const
Get the voxels surrounding point p designated by relative_coordinates.
std::vector< int > voxel_centroids_leaf_indices_
Indices of leaf structures associated with each point in voxel_centroids_ (used for searching).
std::map< std::size_t, Leaf > leaves_
Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of poin...
int getFaceNeighborsAtPoint(const PointT &reference_point, std::vector< LeafConstPtr > &neighbors) const
Get the voxel at p and its facing voxels (up to 7 voxels).
bool downsample_all_data_
Set to true if all fields need to be downsampled, or false if just XYZ.
std::vector< int > leaf_layout_
The leaf layout information for fast access to cells relative to current position.
Eigen::Vector4i divb_mul_
bool save_leaf_layout_
Set to true if leaf layout information needs to be saved in leaf_layout_.
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_).
Eigen::Vector4i min_b_
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
std::string filter_field_name_
The desired user filter field name.
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Eigen::Array4f inverse_leaf_size_
Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
Define standard C methods and C++ classes that are common to all methods.
void getMinMax3D(const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
Eigen::MatrixXi getAllNeighborCellIndices()
Get the relative cell indices of all the 26 neighbors.
int getFieldIndex(const pcl::PointCloud< PointT > &, const std::string &field_name, std::vector< pcl::PCLPointField > &fields)
constexpr bool isXYZFinite(const PointT &) noexcept
Helper functor structure for copying data between an Eigen type and a PointT.
Helper functor structure for copying data between an Eigen type and a PointT.
A point structure representing Euclidean xyz coordinates.
A structure representing RGB color information.
Simple structure to hold a centroid, covarince and the number of points in a leaf.
int nr_points
Number of points contained by voxel.
Eigen::Vector3d mean_
3D voxel centroid
Eigen::Matrix3d icov_
Inverse of voxel covariance matrix.
Eigen::VectorXf centroid
Nd voxel centroid.
Eigen::Vector3d evals_
Eigen values of voxel covariance matrix.
Eigen::Matrix3d cov_
Voxel covariance matrix.
Eigen::Matrix3d evecs_
Eigen vectors of voxel covariance matrix.