38#ifndef PCL_FILTERS_IMPL_VOXEL_GRID_H_
39#define PCL_FILTERS_IMPL_VOXEL_GRID_H_
45#include <pcl/common/io.h>
46#include <pcl/filters/voxel_grid.h>
47#include <boost/sort/spreadsort/integer_sort.hpp>
50template <
typename Po
intT>
void
52 const std::string &distance_field_name,
float min_distance,
float max_distance,
53 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt,
bool limit_negative)
55 Eigen::Array4f min_p, max_p;
56 min_p.setConstant (std::numeric_limits<float>::max());
57 max_p.setConstant (std::numeric_limits<float>::lowest());
60 std::vector<pcl::PCLPointField>
fields;
62 if (distance_idx < 0 ||
fields.empty()) {
63 PCL_ERROR (
"[pcl::getMinMax3D] Could not find field with name '%s'!\n", distance_field_name.c_str());
66 const auto field_offset =
fields[distance_idx].offset;
72 for (
const auto& point: *cloud)
75 const auto* pt_data =
reinterpret_cast<const std::uint8_t*
> (&point);
76 memcpy (&distance_value, pt_data + field_offset,
sizeof (
float));
81 if ((distance_value < max_distance) && (distance_value > min_distance))
87 if ((distance_value > max_distance) || (distance_value < min_distance))
92 min_p = min_p.min (pt);
93 max_p = max_p.max (pt);
98 for (
const auto& point: *cloud)
101 const auto* pt_data =
reinterpret_cast<const std::uint8_t*
> (&point);
102 memcpy (&distance_value, pt_data + field_offset,
sizeof (
float));
107 if ((distance_value < max_distance) && (distance_value > min_distance))
113 if ((distance_value > max_distance) || (distance_value < min_distance))
122 min_p = min_p.min (pt);
123 max_p = max_p.max (pt);
131template <
typename Po
intT>
void
134 const std::string &distance_field_name,
float min_distance,
float max_distance,
135 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt,
bool limit_negative)
137 Eigen::Array4f min_p, max_p;
138 min_p.setConstant (std::numeric_limits<float>::max());
139 max_p.setConstant (std::numeric_limits<float>::lowest());
142 std::vector<pcl::PCLPointField>
fields;
144 if (distance_idx < 0 ||
fields.empty()) {
145 PCL_ERROR (
"[pcl::getMinMax3D] Could not find field with name '%s'!\n", distance_field_name.c_str());
148 const auto field_offset =
fields[distance_idx].offset;
150 float distance_value;
154 for (
const auto &index : indices)
157 const auto* pt_data =
reinterpret_cast<const std::uint8_t*
> (&(*cloud)[index]);
158 memcpy (&distance_value, pt_data + field_offset,
sizeof (
float));
163 if ((distance_value < max_distance) && (distance_value > min_distance))
169 if ((distance_value > max_distance) || (distance_value < min_distance))
174 min_p = min_p.min (pt);
175 max_p = max_p.max (pt);
180 for (
const auto &index : indices)
183 const auto* pt_data =
reinterpret_cast<const std::uint8_t*
> (&(*cloud)[index]);
184 memcpy (&distance_value, pt_data + field_offset,
sizeof (
float));
189 if ((distance_value < max_distance) && (distance_value > min_distance))
195 if ((distance_value > max_distance) || (distance_value < min_distance))
200 if (!std::isfinite ((*cloud)[index].x) ||
201 !std::isfinite ((*cloud)[index].y) ||
202 !std::isfinite ((*cloud)[index].z))
206 min_p = min_p.min (pt);
207 max_p = max_p.max (pt);
215template <
typename Po
intT>
void
221 PCL_WARN (
"[pcl::%s::applyFilter] No input dataset given!\n",
getClassName ().c_str ());
222 output.width = output.height = 0;
229 output.is_dense =
true;
231 Eigen::Vector4f min_p, max_p;
239 std::int64_t dx =
static_cast<std::int64_t
>((max_p[0] - min_p[0]) *
inverse_leaf_size_[0])+1;
240 std::int64_t dy =
static_cast<std::int64_t
>((max_p[1] - min_p[1]) *
inverse_leaf_size_[1])+1;
241 std::int64_t dz =
static_cast<std::int64_t
>((max_p[2] - min_p[2]) *
inverse_leaf_size_[2])+1;
243 if ((dx*dy*dz) >
static_cast<std::int64_t
>(std::numeric_limits<std::int32_t>::max()))
245 PCL_WARN(
"[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.\n",
getClassName().c_str());
266 std::vector<internal::cloud_point_index_idx> index_vector;
267 index_vector.reserve (
indices_->size ());
273 std::vector<pcl::PCLPointField>
fields;
275 if (distance_idx == -1) {
279 const auto field_offset =
fields[distance_idx].offset;
284 for (
const auto& index : (*
indices_))
292 const auto* pt_data =
reinterpret_cast<const std::uint8_t*
> (&(*input_)[index]);
293 float distance_value = 0;
294 memcpy (&distance_value, pt_data + field_offset,
sizeof (
float));
315 index_vector.emplace_back(
static_cast<unsigned int> (idx), index);
324 for (
const auto& index : (*
indices_))
337 index_vector.emplace_back(
static_cast<unsigned int> (idx), index);
344 boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func);
348 unsigned int total = 0;
349 unsigned int index = 0;
353 std::vector<std::pair<unsigned int, unsigned int> > first_and_last_indices_vector;
355 first_and_last_indices_vector.reserve (index_vector.size ());
356 while (index < index_vector.size ())
358 unsigned int i = index + 1;
359 while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx)
364 first_and_last_indices_vector.emplace_back(index, i);
370 output.resize (total);
378 std::uint32_t reinit_size = std::min (
static_cast<unsigned int> (new_layout_size),
static_cast<unsigned int> (
leaf_layout_.size()));
379 for (std::uint32_t i = 0; i < reinit_size; i++)
385 catch (std::bad_alloc&)
387 throw PCLException(
"VoxelGrid bin size is too low; impossible to allocate memory for layout",
388 "voxel_grid.hpp",
"applyFilter");
390 catch (std::length_error&)
392 throw PCLException(
"VoxelGrid bin size is too low; impossible to allocate memory for layout",
393 "voxel_grid.hpp",
"applyFilter");
398 for (
const auto &cp : first_and_last_indices_vector)
401 unsigned int first_index = cp.first;
402 unsigned int last_index = cp.second;
411 Eigen::Vector4f centroid (Eigen::Vector4f::Zero ());
413 for (
unsigned int li = first_index; li < last_index; ++li)
414 centroid += (*
input_)[index_vector[li].cloud_point_index].getVector4fMap ();
416 centroid /=
static_cast<float> (last_index - first_index);
417 output[index].getVector4fMap () = centroid;
424 for (
unsigned int li = first_index; li < last_index; ++li)
425 centroid.
add ((*
input_)[index_vector[li].cloud_point_index]);
427 centroid.
get (output[index]);
432 output.width = output.size ();
435#define PCL_INSTANTIATE_VoxelGrid(T) template class PCL_EXPORTS pcl::VoxelGrid<T>;
436#define PCL_INSTANTIATE_getMinMax3D(T) template PCL_EXPORTS void pcl::getMinMax3D<T> (const pcl::PointCloud<T>::ConstPtr &, const std::string &, float, float, Eigen::Vector4f &, Eigen::Vector4f &, bool);
Define methods for centroid estimation and covariance matrix calculus.
A generic class that computes the centroid of points fed to it.
void get(PointOutT &point) const
Retrieve the current centroid.
void add(const PointT &point)
Add a new point to the centroid computation.
const std::string & getClassName() const
Get a string representation of the name of this class.
PointCloudConstPtr input_
The input point cloud dataset.
IndicesPtr indices_
A pointer to the vector of point indices to use.
A base class for all pcl exceptions which inherits from std::runtime_error.
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
shared_ptr< const PointCloud< PointT > > ConstPtr
bool downsample_all_data_
Set to true if all fields need to be downsampled, or false if just XYZ.
unsigned int min_points_per_voxel_
Minimum number of points per voxel for the centroid to be computed.
void applyFilter(PointCloud &output) override
Downsample a Point Cloud using a voxelized grid approach.
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.
typename Filter< PointT >::PointCloud PointCloud
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.
int getFieldIndex(const pcl::PointCloud< PointT > &, const std::string &field_name, std::vector< pcl::PCLPointField > &fields)
const Eigen::Map< const Eigen::Array4f, Eigen::Aligned > Array4fMapConst
IndicesAllocator<> Indices
Type used for indices in PCL.
constexpr bool isXYZFinite(const PointT &) noexcept
Used internally in voxel grid classes.