40 #ifndef PCL18_BACKPORTS_VOXEL_GRID_H 41 #define PCL18_BACKPORTS_VOXEL_GRID_H 43 #ifndef BACKPORT_PCL_VOXEL_GRID 45 #include <pcl/filters/voxel_grid.h> 49 template <
typename Po
intT>
64 #include <pcl/common/centroid.h> 65 #include <pcl/filters/boost.h> 66 #include <pcl/filters/filter.h> 82 template <
typename Po
intT>
101 : leaf_size_(Eigen::Vector4f::Zero())
102 , inverse_leaf_size_(Eigen::Array4f::Zero())
104 , min_b_(Eigen::Vector4i::Zero())
105 , max_b_(Eigen::Vector4i::Zero())
106 , div_b_(Eigen::Vector4i::Zero())
107 , divb_mul_(Eigen::Vector4i::Zero())
111 , min_points_per_voxel_(0)
113 filter_name_ =
"VoxelGrid";
125 setLeafSize(
const Eigen::Vector4f& leaf_size)
127 leaf_size_ = leaf_size;
129 if (leaf_size_[3] == 0)
132 inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
141 setLeafSize(
float lx,
float ly,
float lz)
147 if (leaf_size_[3] == 0)
150 inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
154 inline Eigen::Vector3f
157 return (leaf_size_.head<3>());
164 setMinimumPointsNumberPerVoxel(
unsigned int min_points_per_voxel)
166 min_points_per_voxel_ = min_points_per_voxel;
172 getMinimumPointsNumberPerVoxel()
const 174 return min_points_per_voxel_;
180 inline Eigen::Vector3i
181 getMinBoxCoordinates()
const 183 return (min_b_.head<3>());
189 inline Eigen::Vector3i
190 getMaxBoxCoordinates()
const 192 return (max_b_.head<3>());
198 inline Eigen::Vector3i
199 getNrDivisions()
const 201 return (div_b_.head<3>());
207 inline Eigen::Vector3i
208 getDivisionMultiplier()
const 210 return (divb_mul_.head<3>());
222 getCentroidIndex(
const PointT& p)
const 224 return (leaf_layout_.at((Eigen::Vector4i(static_cast<int>(floor(p.x * inverse_leaf_size_[0])),
225 static_cast<int>(floor(p.y * inverse_leaf_size_[1])),
226 static_cast<int>(floor(p.z * inverse_leaf_size_[2])), 0) -
237 inline std::vector<int>
238 getNeighborCentroidIndices(
const PointT& reference_point,
const Eigen::MatrixXi& relative_coordinates)
const 240 Eigen::Vector4i ijk(static_cast<int>(floor(reference_point.x * inverse_leaf_size_[0])),
241 static_cast<int>(floor(reference_point.y * inverse_leaf_size_[1])),
242 static_cast<int>(floor(reference_point.z * inverse_leaf_size_[2])), 0);
243 Eigen::Array4i diff2min = min_b_ - ijk;
244 Eigen::Array4i diff2max = max_b_ - ijk;
245 std::vector<int> neighbors(relative_coordinates.cols());
246 for (
int ni = 0; ni < relative_coordinates.cols(); ni++)
248 Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
250 if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
251 neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot(divb_mul_))];
261 inline std::vector<int>
262 getLeafLayout()
const 264 return (leaf_layout_);
272 inline Eigen::Vector3i
273 getGridCoordinates(
float x,
float y,
float z)
const 275 return (Eigen::Vector3i(static_cast<int>(floor(x * inverse_leaf_size_[0])),
276 static_cast<int>(floor(y * inverse_leaf_size_[1])),
277 static_cast<int>(floor(z * inverse_leaf_size_[2]))));
284 getCentroidIndexAt(
const Eigen::Vector3i& ijk)
const 286 int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).
dot(divb_mul_);
287 if (idx < 0 || idx >= static_cast<int>(leaf_layout_.size()))
292 return (leaf_layout_[idx]);
300 setFilterLimits(
const double& limit_min,
const double& limit_max)
311 getFilterLimits(
double& limit_min,
double& limit_max)
const 322 setFilterLimitsNegative(
const bool limit_negative)
331 getFilterLimitsNegative(
bool& limit_negative)
const 340 getFilterLimitsNegative()
const 347 Eigen::Vector4f leaf_size_;
350 Eigen::Array4f inverse_leaf_size_;
353 std::vector<int> leaf_layout_;
356 Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
369 unsigned int min_points_per_voxel_;
371 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
377 applyFilter(PointCloud& output)
382 PCL_WARN(
"[pcl::%s::applyFilter] No input dataset given!\n", getClassName().c_str());
383 output.width = output.height = 0;
384 output.points.clear();
390 output.is_dense =
true;
392 Eigen::Vector4f min_p, max_p;
393 getMinMax3D<PointT>(*input_, *indices_, min_p, max_p);
396 int64_t dx =
static_cast<int64_t
>((max_p[0] - min_p[0]) * inverse_leaf_size_[0]) + 1;
397 int64_t dy =
static_cast<int64_t
>((max_p[1] - min_p[1]) * inverse_leaf_size_[1]) + 1;
398 int64_t dz =
static_cast<int64_t
>((max_p[2] - min_p[2]) * inverse_leaf_size_[2]) + 1;
400 if ((dx * dy * dz) >
static_cast<int64_t
>(std::numeric_limits<int32_t>::max()))
402 PCL_WARN(
"[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.",
403 getClassName().c_str());
409 min_b_[0] =
static_cast<int>(floor(min_p[0] * inverse_leaf_size_[0]));
410 max_b_[0] =
static_cast<int>(floor(max_p[0] * inverse_leaf_size_[0]));
411 min_b_[1] =
static_cast<int>(floor(min_p[1] * inverse_leaf_size_[1]));
412 max_b_[1] =
static_cast<int>(floor(max_p[1] * inverse_leaf_size_[1]));
413 min_b_[2] =
static_cast<int>(floor(min_p[2] * inverse_leaf_size_[2]));
414 max_b_[2] =
static_cast<int>(floor(max_p[2] * inverse_leaf_size_[2]));
417 div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones();
421 divb_mul_ = Eigen::Vector4i(1, div_b_[0], div_b_[0] * div_b_[1], 0);
424 std::vector<cloud_point_index_idx> index_vector;
425 index_vector.reserve(indices_->size());
431 for (std::vector<int>::const_iterator it = indices_->begin(); it != indices_->end(); ++it)
433 if (!input_->is_dense)
435 if (!pcl_isfinite(input_->points[*it].x) ||
436 !pcl_isfinite(input_->points[*it].y) ||
437 !pcl_isfinite(input_->points[*it].z))
440 int ijk0 =
static_cast<int>(
441 floor(input_->points[*it].x * inverse_leaf_size_[0]) -
static_cast<float>(min_b_[0]));
442 int ijk1 =
static_cast<int>(
443 floor(input_->points[*it].y * inverse_leaf_size_[1]) -
static_cast<float>(min_b_[1]));
444 int ijk2 =
static_cast<int>(
445 floor(input_->points[*it].z * inverse_leaf_size_[2]) -
static_cast<float>(min_b_[2]));
448 int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
449 index_vector.push_back(cloud_point_index_idx(static_cast<unsigned int>(idx), *it));
454 std::sort(index_vector.begin(), index_vector.end(), std::less<cloud_point_index_idx>());
458 unsigned int total = 0;
459 unsigned int index = 0;
463 std::vector<std::pair<unsigned int, unsigned int>> first_and_last_indices_vector;
465 first_and_last_indices_vector.reserve(index_vector.size());
466 while (index < index_vector.size())
468 unsigned int i = index + 1;
469 while (i < index_vector.size() && index_vector[i].idx == index_vector[index].idx)
471 if (i - index >= min_points_per_voxel_)
474 first_and_last_indices_vector.push_back(std::pair<unsigned int, unsigned int>(index, i));
480 output.points.resize(total);
483 for (
unsigned int cp = 0; cp < first_and_last_indices_vector.size(); ++cp)
486 unsigned int first_index = first_and_last_indices_vector[cp].first;
487 unsigned int last_index = first_and_last_indices_vector[cp].second;
489 CentroidPoint<PointT> centroid;
492 for (
unsigned int li = first_index; li < last_index; ++li)
493 centroid.add(input_->points[index_vector[li].cloud_point_index]);
495 centroid.get(output.points[index]);
499 output.width =
static_cast<uint32_t
>(output.points.size());
504 #endif // BACKPORT_PCL_VOXEL_GRID 506 #endif // PCL18_BACKPORTS_VOXEL_GRID_H
TFSIMD_FORCE_INLINE const tfScalar & y() const
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
VoxelGrid< PointT > VoxelGrid18
TFSIMD_FORCE_INLINE const tfScalar & x() const
pcl::PointCloud< pcl::PointXYZ > PointCloud
TFSIMD_FORCE_INLINE const tfScalar & z() const
PointCloud::ConstPtr PointCloudConstPtr
bool filter_limit_negative_
PointCloud::Ptr PointCloudPtr