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>
65 #include <pcl/common/centroid.h> 66 #include <pcl/filters/boost.h> 67 #include <pcl/filters/filter.h> 83 template <
typename Po
intT>
102 : leaf_size_(Eigen::Vector4f::Zero())
103 , inverse_leaf_size_(Eigen::Array4f::Zero())
105 , min_b_(Eigen::Vector4i::Zero())
106 , max_b_(Eigen::Vector4i::Zero())
107 , div_b_(Eigen::Vector4i::Zero())
108 , divb_mul_(Eigen::Vector4i::Zero())
112 , min_points_per_voxel_(0)
114 filter_name_ =
"VoxelGrid";
126 setLeafSize(
const Eigen::Vector4f& leaf_size)
128 leaf_size_ = leaf_size;
130 if (leaf_size_[3] == 0)
133 inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
142 setLeafSize(
float lx,
float ly,
float lz)
148 if (leaf_size_[3] == 0)
151 inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
155 inline Eigen::Vector3f
158 return (leaf_size_.head<3>());
165 setMinimumPointsNumberPerVoxel(
unsigned int min_points_per_voxel)
167 min_points_per_voxel_ = min_points_per_voxel;
173 getMinimumPointsNumberPerVoxel()
const 175 return min_points_per_voxel_;
181 inline Eigen::Vector3i
182 getMinBoxCoordinates()
const 184 return (min_b_.head<3>());
190 inline Eigen::Vector3i
191 getMaxBoxCoordinates()
const 193 return (max_b_.head<3>());
199 inline Eigen::Vector3i
200 getNrDivisions()
const 202 return (div_b_.head<3>());
208 inline Eigen::Vector3i
209 getDivisionMultiplier()
const 211 return (divb_mul_.head<3>());
223 getCentroidIndex(
const PointT& p)
const 225 return (leaf_layout_.at((Eigen::Vector4i(static_cast<int>(std::floor(p.x * inverse_leaf_size_[0])),
226 static_cast<int>(std::floor(p.y * inverse_leaf_size_[1])),
227 static_cast<int>(std::floor(p.z * inverse_leaf_size_[2])), 0) -
238 inline std::vector<int>
239 getNeighborCentroidIndices(
const PointT& reference_point,
const Eigen::MatrixXi& relative_coordinates)
const 241 Eigen::Vector4i ijk(static_cast<int>(std::floor(reference_point.x * inverse_leaf_size_[0])),
242 static_cast<int>(std::floor(reference_point.y * inverse_leaf_size_[1])),
243 static_cast<int>(std::floor(reference_point.z * inverse_leaf_size_[2])), 0);
244 Eigen::Array4i diff2min = min_b_ - ijk;
245 Eigen::Array4i diff2max = max_b_ - ijk;
246 std::vector<int> neighbors(relative_coordinates.cols());
247 for (
int ni = 0; ni < relative_coordinates.cols(); ni++)
249 Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
251 if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
252 neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot(divb_mul_))];
262 inline std::vector<int>
263 getLeafLayout()
const 265 return (leaf_layout_);
273 inline Eigen::Vector3i
274 getGridCoordinates(
float x,
float y,
float z)
const 276 return (Eigen::Vector3i(static_cast<int>(std::floor(x * inverse_leaf_size_[0])),
277 static_cast<int>(std::floor(y * inverse_leaf_size_[1])),
278 static_cast<int>(std::floor(z * inverse_leaf_size_[2]))));
285 getCentroidIndexAt(
const Eigen::Vector3i& ijk)
const 287 int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).
dot(divb_mul_);
288 if (idx < 0 || idx >= static_cast<int>(leaf_layout_.size()))
293 return (leaf_layout_[idx]);
301 setFilterLimits(
const double& limit_min,
const double& limit_max)
312 getFilterLimits(
double& limit_min,
double& limit_max)
const 323 setFilterLimitsNegative(
const bool limit_negative)
332 getFilterLimitsNegative(
bool& limit_negative)
const 341 getFilterLimitsNegative()
const 348 Eigen::Vector4f leaf_size_;
351 Eigen::Array4f inverse_leaf_size_;
354 std::vector<int> leaf_layout_;
357 Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
370 unsigned int min_points_per_voxel_;
372 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
378 applyFilter(PointCloud& output)
383 PCL_WARN(
"[pcl::%s::applyFilter] No input dataset given!\n", getClassName().c_str());
384 output.width = output.height = 0;
385 output.points.clear();
391 output.is_dense =
true;
393 Eigen::Vector4f min_p, max_p;
394 getMinMax3D<PointT>(*input_, *indices_, min_p, max_p);
397 int64_t dx =
static_cast<int64_t
>((max_p[0] - min_p[0]) * inverse_leaf_size_[0]) + 1;
398 int64_t dy =
static_cast<int64_t
>((max_p[1] - min_p[1]) * inverse_leaf_size_[1]) + 1;
399 int64_t dz =
static_cast<int64_t
>((max_p[2] - min_p[2]) * inverse_leaf_size_[2]) + 1;
401 if ((dx * dy * dz) >
static_cast<int64_t
>(std::numeric_limits<int32_t>::max()))
403 PCL_WARN(
"[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.",
404 getClassName().c_str());
410 min_b_[0] =
static_cast<int>(std::floor(min_p[0] * inverse_leaf_size_[0]));
411 max_b_[0] =
static_cast<int>(std::floor(max_p[0] * inverse_leaf_size_[0]));
412 min_b_[1] =
static_cast<int>(std::floor(min_p[1] * inverse_leaf_size_[1]));
413 max_b_[1] =
static_cast<int>(std::floor(max_p[1] * inverse_leaf_size_[1]));
414 min_b_[2] =
static_cast<int>(std::floor(min_p[2] * inverse_leaf_size_[2]));
415 max_b_[2] =
static_cast<int>(std::floor(max_p[2] * inverse_leaf_size_[2]));
418 div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones();
422 divb_mul_ = Eigen::Vector4i(1, div_b_[0], div_b_[0] * div_b_[1], 0);
425 std::vector<cloud_point_index_idx> index_vector;
426 index_vector.reserve(indices_->size());
432 for (std::vector<int>::const_iterator it = indices_->begin(); it != indices_->end(); ++it)
434 if (!input_->is_dense)
436 if (!pcl_isfinite(input_->points[*it].x) ||
437 !pcl_isfinite(input_->points[*it].y) ||
438 !pcl_isfinite(input_->points[*it].z))
441 int ijk0 =
static_cast<int>(
442 std::floor(input_->points[*it].x * inverse_leaf_size_[0]) -
static_cast<float>(min_b_[0]));
443 int ijk1 =
static_cast<int>(
444 std::floor(input_->points[*it].y * inverse_leaf_size_[1]) -
static_cast<float>(min_b_[1]));
445 int ijk2 =
static_cast<int>(
446 std::floor(input_->points[*it].z * inverse_leaf_size_[2]) -
static_cast<float>(min_b_[2]));
449 int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
450 index_vector.push_back(cloud_point_index_idx(static_cast<unsigned int>(idx), *it));
455 std::sort(index_vector.begin(), index_vector.end(), std::less<cloud_point_index_idx>());
459 unsigned int total = 0;
460 unsigned int index = 0;
464 std::vector<std::pair<unsigned int, unsigned int>> first_and_last_indices_vector;
466 first_and_last_indices_vector.reserve(index_vector.size());
467 while (index < index_vector.size())
469 unsigned int i = index + 1;
470 while (i < index_vector.size() && index_vector[i].idx == index_vector[index].idx)
472 if (i - index >= min_points_per_voxel_)
475 first_and_last_indices_vector.push_back(std::pair<unsigned int, unsigned int>(index, i));
481 output.points.resize(total);
484 for (
unsigned int cp = 0; cp < first_and_last_indices_vector.size(); ++cp)
487 unsigned int first_index = first_and_last_indices_vector[cp].first;
488 unsigned int last_index = first_and_last_indices_vector[cp].second;
490 CentroidPoint<PointT> centroid;
493 for (
unsigned int li = first_index; li < last_index; ++li)
494 centroid.add(input_->points[index_vector[li].cloud_point_index]);
496 centroid.get(output.points[index]);
500 output.width =
static_cast<uint32_t
>(output.points.size());
505 #endif // BACKPORT_PCL_VOXEL_GRID 507 #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