VoxelGrid to estimate occluded space in the scene. The ray traversal algorithm is implemented by the work of 'John Amanatides and Andrew Woo, A Fast Voxel Traversal Algorithm for Ray Tracing'. More...
#include <voxel_grid_occlusion_estimation.h>

Public Member Functions | |
| Eigen::Vector4f | getCentroidCoordinate (const Eigen::Vector3i &ijk) |
| Returns the corresponding centroid (x,y,z) coordinates in the grid of voxel (i,j,k). | |
| PointCloud | getFilteredPointCloud () |
| Returns the voxel grid filtered point cloud. | |
| Eigen::Vector3f | getMaxBoundCoordinates () |
| Returns the maximum bounding of coordinates of the voxel grid (x,y,z). | |
| Eigen::Vector3f | getMinBoundCoordinates () |
| Returns the minimum bounding of coordinates of the voxel grid (x,y,z). | |
| void | initializeVoxelGrid () |
| Initialize the voxel grid, needs to be called first Builts the voxel grid and computes additional values for the ray traversal algorithm. | |
| int | occlusionEstimation (int &out_state, const Eigen::Vector3i &in_target_voxel) |
| Returns the state (free = 0, occluded = 1) of the voxel after utilizing a ray traversal algorithm to a target voxel in (i, j, k) coordinates. | |
| int | occlusionEstimation (int &out_state, std::vector< Eigen::Vector3i > &out_ray, const Eigen::Vector3i &in_target_voxel) |
| Returns the state (free = 0, occluded = 1) of the voxel after utilizing a ray traversal algorithm to a target voxel in (i, j, k) coordinates. Additionally, this function returns the voxels penetrated of the ray-traversal algorithm till reaching the target voxel. | |
| int | occlusionEstimationAll (std::vector< Eigen::Vector3i > &occluded_voxels) |
| Returns the voxel coordinates (i, j, k) of all occluded voxels in the voxel gird. | |
| VoxelGridOcclusionEstimation () | |
| Empty constructor. | |
| virtual | ~VoxelGridOcclusionEstimation () |
| Destructor. | |
Protected Types | |
| typedef Filter< PointT > ::PointCloud | PointCloud |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
| typedef PointCloud::Ptr | PointCloudPtr |
Protected Member Functions | |
| 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. (p_entry = origin + tmin * orientation) | |
| 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. | |
| int | rayTraversal (std::vector< Eigen::Vector3i > &out_ray, 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) and the voxels penetrated by the ray unsing a ray traversal algorithm. | |
| float | round (float d) |
| Returns a rounded value. | |
Protected Attributes | |
| Eigen::Vector4f | b_max_ |
| Eigen::Vector4f | b_min_ |
| PointCloud | filtered_cloud_ |
| bool | initialized_ |
| Eigen::Quaternionf | sensor_orientation_ |
| Eigen::Vector4f | sensor_origin_ |
VoxelGrid to estimate occluded space in the scene. The ray traversal algorithm is implemented by the work of 'John Amanatides and Andrew Woo, A Fast Voxel Traversal Algorithm for Ray Tracing'.
Definition at line 56 of file voxel_grid_occlusion_estimation.h.
typedef Filter<PointT>::PointCloud pcl::VoxelGridOcclusionEstimation< PointT >::PointCloud [protected] |
Reimplemented from pcl::VoxelGrid< PointT >.
Definition at line 65 of file voxel_grid_occlusion_estimation.h.
typedef PointCloud::ConstPtr pcl::VoxelGridOcclusionEstimation< PointT >::PointCloudConstPtr [protected] |
Reimplemented from pcl::VoxelGrid< PointT >.
Definition at line 67 of file voxel_grid_occlusion_estimation.h.
typedef PointCloud::Ptr pcl::VoxelGridOcclusionEstimation< PointT >::PointCloudPtr [protected] |
Reimplemented from pcl::VoxelGrid< PointT >.
Definition at line 66 of file voxel_grid_occlusion_estimation.h.
| pcl::VoxelGridOcclusionEstimation< PointT >::VoxelGridOcclusionEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 71 of file voxel_grid_occlusion_estimation.h.
| virtual pcl::VoxelGridOcclusionEstimation< PointT >::~VoxelGridOcclusionEstimation | ( | ) | [inline, virtual] |
Destructor.
Definition at line 78 of file voxel_grid_occlusion_estimation.h.
| Eigen::Vector4f pcl::VoxelGridOcclusionEstimation< PointT >::getCentroidCoordinate | ( | const Eigen::Vector3i & | ijk | ) | [inline] |
Returns the corresponding centroid (x,y,z) coordinates in the grid of voxel (i,j,k).
| [in] | the | coordinate (i, j, k) of the voxel |
Definition at line 145 of file voxel_grid_occlusion_estimation.h.
| PointCloud pcl::VoxelGridOcclusionEstimation< PointT >::getFilteredPointCloud | ( | ) | [inline] |
Returns the voxel grid filtered point cloud.
| [out] | The | voxel grid filtered point cloud |
Definition at line 124 of file voxel_grid_occlusion_estimation.h.
| Eigen::Vector3i pcl::VoxelGridOcclusionEstimation< PointT >::getGridCoordinatesRound | ( | float | x, |
| float | y, | ||
| float | z | ||
| ) | [inline, protected] |
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
| [in] | x | the X point coordinate to get the (i, j, k) index at |
| [in] | y | the Y point coordinate to get the (i, j, k) index at |
| [in] | z | the Z point coordinate to get the (i, j, k) index at |
Definition at line 225 of file voxel_grid_occlusion_estimation.h.
| Eigen::Vector3f pcl::VoxelGridOcclusionEstimation< PointT >::getMaxBoundCoordinates | ( | ) | [inline] |
Returns the maximum bounding of coordinates of the voxel grid (x,y,z).
Definition at line 137 of file voxel_grid_occlusion_estimation.h.
| Eigen::Vector3f pcl::VoxelGridOcclusionEstimation< PointT >::getMinBoundCoordinates | ( | ) | [inline] |
Returns the minimum bounding of coordinates of the voxel grid (x,y,z).
Definition at line 131 of file voxel_grid_occlusion_estimation.h.
| void pcl::VoxelGridOcclusionEstimation< PointT >::initializeVoxelGrid | ( | ) |
Initialize the voxel grid, needs to be called first Builts the voxel grid and computes additional values for the ray traversal algorithm.
Definition at line 47 of file voxel_grid_occlusion_estimation.hpp.
| int pcl::VoxelGridOcclusionEstimation< PointT >::occlusionEstimation | ( | int & | out_state, |
| const Eigen::Vector3i & | in_target_voxel | ||
| ) |
Returns the state (free = 0, occluded = 1) of the voxel after utilizing a ray traversal algorithm to a target voxel in (i, j, k) coordinates.
| [out] | The | state of the voxel. |
| [in] | The | target voxel coordinate (i, j, k) of the voxel. |
Definition at line 70 of file voxel_grid_occlusion_estimation.hpp.
| int pcl::VoxelGridOcclusionEstimation< PointT >::occlusionEstimation | ( | int & | out_state, |
| std::vector< Eigen::Vector3i > & | out_ray, | ||
| const Eigen::Vector3i & | in_target_voxel | ||
| ) |
Returns the state (free = 0, occluded = 1) of the voxel after utilizing a ray traversal algorithm to a target voxel in (i, j, k) coordinates. Additionally, this function returns the voxels penetrated of the ray-traversal algorithm till reaching the target voxel.
| [out] | The | state of the voxel. |
| [out] | The | voxels penetrated of the ray-traversal algorithm. |
| [in] | The | target voxel coordinate (i, j, k) of the voxel. |
Definition at line 101 of file voxel_grid_occlusion_estimation.hpp.
| int pcl::VoxelGridOcclusionEstimation< PointT >::occlusionEstimationAll | ( | std::vector< Eigen::Vector3i > & | occluded_voxels | ) |
Returns the voxel coordinates (i, j, k) of all occluded voxels in the voxel gird.
| [out] | the | coordinates (i, j, k) of all occluded voxels |
Definition at line 133 of file voxel_grid_occlusion_estimation.hpp.
| float pcl::VoxelGridOcclusionEstimation< PointT >::rayBoxIntersection | ( | const Eigen::Vector4f & | origin, |
| const Eigen::Vector4f & | direction | ||
| ) | [protected] |
Returns the scaling value (tmin) were the ray intersects with the voxel grid bounding box. (p_entry = origin + tmin * orientation)
| [in] | The | sensor origin |
| [in] | The | sensor orientation |
Definition at line 176 of file voxel_grid_occlusion_estimation.hpp.
| int pcl::VoxelGridOcclusionEstimation< PointT >::rayTraversal | ( | const Eigen::Vector3i & | target_voxel, |
| const Eigen::Vector4f & | origin, | ||
| const Eigen::Vector4f & | direction, | ||
| const float | t_min | ||
| ) | [protected] |
Returns the state of the target voxel (0 = visible, 1 = occupied) unsing a ray traversal algorithm.
| [in] | The | target voxel in the voxel grid with coordinate (i, j, k). |
| [in] | The | sensor origin. |
| [in] | The | sensor orientation |
| [in] | The | scaling value (tmin). |
Definition at line 243 of file voxel_grid_occlusion_estimation.hpp.
| int pcl::VoxelGridOcclusionEstimation< PointT >::rayTraversal | ( | std::vector< Eigen::Vector3i > & | out_ray, |
| const Eigen::Vector3i & | target_voxel, | ||
| const Eigen::Vector4f & | origin, | ||
| const Eigen::Vector4f & | direction, | ||
| const float | t_min | ||
| ) | [protected] |
Returns the state of the target voxel (0 = visible, 1 = occupied) and the voxels penetrated by the ray unsing a ray traversal algorithm.
| [out] | The | voxels penetrated by the ray in (i, j, k) coordinates |
| [in] | The | target voxel in the voxel grid with coordinate (i, j, k). |
| [in] | The | sensor origin. |
| [in] | The | sensor orientation |
| [in] | The | scaling value (tmin). |
Definition at line 337 of file voxel_grid_occlusion_estimation.hpp.
| float pcl::VoxelGridOcclusionEstimation< PointT >::round | ( | float | d | ) | [inline, protected] |
Returns a rounded value.
| [in] | value |
Definition at line 213 of file voxel_grid_occlusion_estimation.h.
Eigen::Vector4f pcl::VoxelGridOcclusionEstimation< PointT >::b_max_ [protected] |
Definition at line 239 of file voxel_grid_occlusion_estimation.h.
Eigen::Vector4f pcl::VoxelGridOcclusionEstimation< PointT >::b_min_ [protected] |
Definition at line 239 of file voxel_grid_occlusion_estimation.h.
PointCloud pcl::VoxelGridOcclusionEstimation< PointT >::filtered_cloud_ [protected] |
Definition at line 242 of file voxel_grid_occlusion_estimation.h.
bool pcl::VoxelGridOcclusionEstimation< PointT >::initialized_ [protected] |
Definition at line 233 of file voxel_grid_occlusion_estimation.h.
Eigen::Quaternionf pcl::VoxelGridOcclusionEstimation< PointT >::sensor_orientation_ [protected] |
Definition at line 236 of file voxel_grid_occlusion_estimation.h.
Eigen::Vector4f pcl::VoxelGridOcclusionEstimation< PointT >::sensor_origin_ [protected] |
Definition at line 235 of file voxel_grid_occlusion_estimation.h.