39#ifndef PCL_FILTERS_IMPL_VOXEL_GRID_OCCLUSION_ESTIMATION_H_
40#define PCL_FILTERS_IMPL_VOXEL_GRID_OCCLUSION_ESTIMATION_H_
42#include <pcl/filters/voxel_grid_occlusion_estimation.h>
45template <
typename Po
intT>
void
68template <
typename Po
intT>
int
70 const Eigen::Vector3i& in_target_voxel)
74 PCL_ERROR (
"Voxel grid not initialized; call initializeVoxelGrid () first! \n");
81 direction.normalize ();
88 PCL_ERROR (
"The ray does not intersect with the bounding box \n");
99template <
typename Po
intT>
int
101 std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> >& out_ray,
102 const Eigen::Vector3i& in_target_voxel)
106 PCL_ERROR (
"Voxel grid not initialized; call initializeVoxelGrid () first! \n");
113 direction.normalize ();
120 PCL_ERROR (
"The ray does not intersect with the bounding box \n");
131template <
typename Po
intT>
int
136 PCL_ERROR (
"Voxel grid not initialized; call initializeVoxelGrid () first! \n");
142 occluded_voxels.reserve (reserve_size);
149 Eigen::Vector3i ijk (ii, jj, kk);
157 direction.normalize ();
167 occluded_voxels.push_back (ijk);
174template <
typename Po
intT>
float
176 const Eigen::Vector4f& direction)
178 float tmin, tmax, tymin, tymax, tzmin, tzmax;
180 if (direction[0] >= 0)
182 tmin = (
b_min_[0] - origin[0]) / direction[0];
183 tmax = (
b_max_[0] - origin[0]) / direction[0];
187 tmin = (
b_max_[0] - origin[0]) / direction[0];
188 tmax = (
b_min_[0] - origin[0]) / direction[0];
191 if (direction[1] >= 0)
193 tymin = (
b_min_[1] - origin[1]) / direction[1];
194 tymax = (
b_max_[1] - origin[1]) / direction[1];
198 tymin = (
b_max_[1] - origin[1]) / direction[1];
199 tymax = (
b_min_[1] - origin[1]) / direction[1];
202 if ((tmin > tymax) || (tymin > tmax))
204 PCL_ERROR (
"no intersection with the bounding box \n");
214 if (direction[2] >= 0)
216 tzmin = (
b_min_[2] - origin[2]) / direction[2];
217 tzmax = (
b_max_[2] - origin[2]) / direction[2];
221 tzmin = (
b_max_[2] - origin[2]) / direction[2];
222 tzmax = (
b_min_[2] - origin[2]) / direction[2];
225 if ((tmin > tzmax) || (tzmin > tmax))
227 PCL_ERROR (
"no intersection with the bounding box \n");
241template <
typename Po
intT>
int
243 const Eigen::Vector4f& origin,
244 const Eigen::Vector4f& direction,
248 Eigen::Vector4f start = origin + t_min * direction;
254 int step_x, step_y, step_z;
259 if (direction[0] >= 0)
269 if (direction[1] >= 0)
279 if (direction[2] >= 0)
290 float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0];
291 float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1];
292 float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2];
294 float t_delta_x =
leaf_size_[0] /
static_cast<float> (std::abs (direction[0]));
295 float t_delta_y =
leaf_size_[1] /
static_cast<float> (std::abs (direction[1]));
296 float t_delta_z =
leaf_size_[2] /
static_cast<float> (std::abs (direction[2]));
298 while ( (ijk[0] <
max_b_[0]+1) && (ijk[0] >=
min_b_[0]) &&
303 if (ijk[0] == target_voxel[0] && ijk[1] == target_voxel[1] && ijk[2] == target_voxel[2])
313 if(t_max_x <= t_max_y && t_max_x <= t_max_z)
315 t_max_x += t_delta_x;
318 else if(t_max_y <= t_max_z && t_max_y <= t_max_x)
320 t_max_y += t_delta_y;
325 t_max_z += t_delta_z;
333template <
typename Po
intT>
int
335 const Eigen::Vector3i& target_voxel,
336 const Eigen::Vector4f& origin,
337 const Eigen::Vector4f& direction,
341 int reserve_size =
div_b_.maxCoeff () *
div_b_.maxCoeff ();
342 out_ray.reserve (reserve_size);
345 Eigen::Vector4f start = origin + t_min * direction;
352 int step_x, step_y, step_z;
357 if (direction[0] >= 0)
367 if (direction[1] >= 0)
377 if (direction[2] >= 0)
388 float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0];
389 float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1];
390 float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2];
392 float t_delta_x =
leaf_size_[0] /
static_cast<float> (std::abs (direction[0]));
393 float t_delta_y =
leaf_size_[1] /
static_cast<float> (std::abs (direction[1]));
394 float t_delta_z =
leaf_size_[2] /
static_cast<float> (std::abs (direction[2]));
399 while ( (ijk[0] <
max_b_[0]+1) && (ijk[0] >=
min_b_[0]) &&
404 out_ray.push_back (ijk);
407 if (ijk[0] == target_voxel[0] && ijk[1] == target_voxel[1] && ijk[2] == target_voxel[2])
416 if(t_max_x <= t_max_y && t_max_x <= t_max_z)
418 t_max_x += t_delta_x;
421 else if(t_max_y <= t_max_z && t_max_y <= t_max_x)
423 t_max_y += t_delta_y;
428 t_max_z += t_delta_z;
436#define PCL_INSTANTIATE_VoxelGridOcclusionEstimation(T) template class PCL_EXPORTS pcl::VoxelGridOcclusionEstimation<T>;
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
int getCentroidIndexAt(const Eigen::Vector3i &ijk) const
Returns the index in the downsampled cloud corresponding to a given set of coordinates.
Eigen::Vector4i min_b_
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
Eigen::Vector4f leaf_size_
The size of a leaf.
void initializeVoxelGrid()
Initialize the voxel grid, needs to be called first Builts the voxel grid and computes additional val...
int occlusionEstimationAll(std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > &occluded_voxels)
Computes the voxel coordinates (i, j, k) of all occluded voxels in the voxel grid.
Eigen::Quaternionf sensor_orientation_
Eigen::Vector3i getGridCoordinatesRound(float x, float y, float z)
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
float rayBoxIntersection(const Eigen::Vector4f &origin, const Eigen::Vector4f &direction)
Returns the scaling value (tmin) were the ray intersects with the voxel grid bounding box.
int rayTraversal(const Eigen::Vector3i &target_voxel, const Eigen::Vector4f &origin, const Eigen::Vector4f &direction, const float t_min)
Returns the state of the target voxel (0 = visible, 1 = occupied) unsing a ray traversal algorithm.
PointCloud filtered_cloud_
Eigen::Vector4f sensor_origin_
int occlusionEstimation(int &out_state, const Eigen::Vector3i &in_target_voxel)
Computes the state (free = 0, occluded = 1) of the voxel after utilizing a ray traversal algorithm to...
Eigen::Vector4f getCentroidCoordinate(const Eigen::Vector3i &ijk)
Returns the corresponding centroid (x,y,z) coordinates in the grid of voxel (i,j,k).