|
Point Cloud Library (PCL) 1.15.0
|
VoxelGrid to estimate occluded space in the scene. More...
#include <pcl/filters/voxel_grid_occlusion_estimation.h>
Public Member Functions | |
| PCL_MAKE_ALIGNED_OPERATOR_NEW | VoxelGridOcclusionEstimation () |
| Empty constructor. | |
| ~VoxelGridOcclusionEstimation () override=default | |
| Destructor. | |
| 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) |
| Computes 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, Eigen::aligned_allocator< Eigen::Vector3i > > &out_ray, const Eigen::Vector3i &in_target_voxel) |
| Computes 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 | 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. | |
| PointCloud | getFilteredPointCloud () |
| Returns the voxel grid filtered point cloud. | |
| Eigen::Vector3f | getMinBoundCoordinates () |
| Returns the minimum bounding of coordinates of the voxel grid (x,y,z). | |
| Eigen::Vector3f | getMaxBoundCoordinates () |
| Returns the maximum bounding of coordinates of the voxel grid (x,y,z). | |
| Eigen::Vector4f | getCentroidCoordinate (const Eigen::Vector3i &ijk) |
| Returns the corresponding centroid (x,y,z) coordinates in the grid of voxel (i,j,k). | |
| Public Member Functions inherited from pcl::VoxelGrid< PointT > | |
| PCL_MAKE_ALIGNED_OPERATOR_NEW | VoxelGrid () |
| Empty constructor. | |
| ~VoxelGrid () override=default | |
| Destructor. | |
| void | setLeafSize (const Eigen::Vector4f &leaf_size) |
| Set the voxel grid leaf size. | |
| void | setLeafSize (float lx, float ly, float lz) |
| Set the voxel grid leaf size. | |
| Eigen::Vector3f | getLeafSize () const |
| Get the voxel grid leaf size. | |
| void | setDownsampleAllData (bool downsample) |
| Set to true if all fields need to be downsampled, or false if just XYZ. | |
| bool | getDownsampleAllData () const |
| Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ). | |
| void | setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) |
| Set the minimum number of points required for a voxel to be used. | |
| unsigned int | getMinimumPointsNumberPerVoxel () const |
| Return the minimum number of points required for a voxel to be used. | |
| void | setSaveLeafLayout (bool save_leaf_layout) |
| Set to true if leaf layout information needs to be saved for later access. | |
| bool | getSaveLeafLayout () const |
| Returns true if leaf layout information will to be saved for later access. | |
| Eigen::Vector3i | getMinBoxCoordinates () const |
| Get the minimum coordinates of the bounding box (after filtering is performed). | |
| Eigen::Vector3i | getMaxBoxCoordinates () const |
| Get the minimum coordinates of the bounding box (after filtering is performed). | |
| Eigen::Vector3i | getNrDivisions () const |
| Get the number of divisions along all 3 axes (after filtering is performed). | |
| Eigen::Vector3i | getDivisionMultiplier () const |
| Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed). | |
| int | getCentroidIndex (const PointT &p) const |
| Returns the index in the resulting downsampled cloud of the specified point. | |
| std::vector< int > | getNeighborCentroidIndices (const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates) const |
| Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds). | |
| std::vector< int > | getLeafLayout () const |
| Returns the layout of the leafs for fast access to cells relative to current position. | |
| Eigen::Vector3i | getGridCoordinates (float x, float y, float z) const |
| Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). | |
| int | getCentroidIndexAt (const Eigen::Vector3i &ijk) const |
| Returns the index in the downsampled cloud corresponding to a given set of coordinates. | |
| void | setFilterFieldName (const std::string &field_name) |
| Provide the name of the field to be used for filtering data. | |
| std::string const | getFilterFieldName () const |
| Get the name of the field used for filtering. | |
| void | setFilterLimits (const double &limit_min, const double &limit_max) |
| Set the field filter limits. | |
| void | getFilterLimits (double &limit_min, double &limit_max) const |
| Get the field filter limits (min/max) set by the user. | |
| void | setFilterLimitsNegative (const bool limit_negative) |
| Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). | |
| void | getFilterLimitsNegative (bool &limit_negative) const |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). | |
| bool | getFilterLimitsNegative () const |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). | |
| Public Member Functions inherited from pcl::Filter< PointT > | |
| Filter (bool extract_removed_indices=false) | |
| Empty constructor. | |
| IndicesConstPtr const | getRemovedIndices () const |
| Get the point indices being removed. | |
| void | getRemovedIndices (PointIndices &pi) |
| Get the point indices being removed. | |
| void | filter (PointCloud &output) |
| Calls the filtering method and returns the filtered dataset in output. | |
| Public Member Functions inherited from pcl::PCLBase< PointT > | |
| PCLBase () | |
| Empty constructor. | |
| PCLBase (const PCLBase &base) | |
| Copy constructor. | |
| virtual | ~PCLBase ()=default |
| Destructor. | |
| virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
| Provide a pointer to the input dataset. | |
| PointCloudConstPtr const | getInputCloud () const |
| Get a pointer to the input point cloud dataset. | |
| virtual void | setIndices (const IndicesPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| virtual void | setIndices (const IndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| virtual void | setIndices (const PointIndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| virtual void | setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols) |
| Set the indices for the points laying within an interest region of the point cloud. | |
| IndicesPtr | getIndices () |
| Get a pointer to the vector of indices used. | |
| IndicesConstPtr const | getIndices () const |
| Get a pointer to the vector of indices used. | |
| const PointT & | operator[] (std::size_t pos) const |
| Override PointCloud operator[] to shorten code. | |
Protected Types | |
| using | PointCloud = typename Filter<PointT>::PointCloud |
| using | PointCloudPtr = typename PointCloud::Ptr |
| using | PointCloudConstPtr = typename PointCloud::ConstPtr |
| Protected Types inherited from pcl::VoxelGrid< PointT > | |
| using | PointCloud = typename Filter<PointT>::PointCloud |
| using | PointCloudPtr = typename PointCloud::Ptr |
| using | PointCloudConstPtr = typename PointCloud::ConstPtr |
| using | FieldList = typename pcl::traits::fieldList<PointT>::type |
Protected Member Functions | |
| 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) using a ray traversal algorithm. | |
| int | rayTraversal (std::vector< Eigen::Vector3i, Eigen::aligned_allocator< 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 using a ray traversal algorithm. | |
| float | round (float d) |
| Returns a value rounded to the nearest integer. | |
| Eigen::Vector3i | getGridCoordinatesRound (float x, float y, float z) |
| Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). | |
| Protected Member Functions inherited from pcl::VoxelGrid< PointT > | |
| void | applyFilter (PointCloud &output) override |
| Downsample a Point Cloud using a voxelized grid approach. | |
| Protected Member Functions inherited from pcl::Filter< PointT > | |
| const std::string & | getClassName () const |
| Get a string representation of the name of this class. | |
| Protected Member Functions inherited from pcl::PCLBase< PointT > | |
| bool | initCompute () |
| This method should get called before starting the actual computation. | |
| bool | deinitCompute () |
| This method should get called after finishing the actual computation. | |
Protected Attributes | |
| bool | initialized_ |
| Eigen::Vector4f | sensor_origin_ |
| Eigen::Quaternionf | sensor_orientation_ |
| Eigen::Vector4f | b_min_ |
| Eigen::Vector4f | b_max_ |
| PointCloud | filtered_cloud_ |
| Protected Attributes inherited from pcl::VoxelGrid< PointT > | |
| Eigen::Vector4f | leaf_size_ |
| The size of a leaf. | |
| Eigen::Array4f | inverse_leaf_size_ |
| Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. | |
| bool | downsample_all_data_ {true} |
| Set to true if all fields need to be downsampled, or false if just XYZ. | |
| bool | save_leaf_layout_ {false} |
| Set to true if leaf layout information needs to be saved in leaf_layout_. | |
| std::vector< int > | leaf_layout_ |
| The leaf layout information for fast access to cells relative to current position. | |
| Eigen::Vector4i | min_b_ |
| The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. | |
| Eigen::Vector4i | max_b_ |
| Eigen::Vector4i | div_b_ |
| Eigen::Vector4i | divb_mul_ |
| std::string | filter_field_name_ |
| The desired user filter field name. | |
| double | filter_limit_min_ {std::numeric_limits<float>::lowest()} |
| The minimum allowed filter value a point will be considered from. | |
| double | filter_limit_max_ {std::numeric_limits<float>::max()} |
| The maximum allowed filter value a point will be considered from. | |
| bool | filter_limit_negative_ {false} |
| Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). | |
| unsigned int | min_points_per_voxel_ {0} |
| Minimum number of points per voxel for the centroid to be computed. | |
| Protected Attributes inherited from pcl::Filter< PointT > | |
| IndicesPtr | removed_indices_ |
| Indices of the points that are removed. | |
| std::string | filter_name_ |
| The filter name. | |
| bool | extract_removed_indices_ |
| Set to true if we want to return the indices of the removed points. | |
| Protected Attributes inherited from pcl::PCLBase< PointT > | |
| PointCloudConstPtr | input_ |
| The input point cloud dataset. | |
| IndicesPtr | indices_ |
| A pointer to the vector of point indices to use. | |
| bool | use_indices_ |
| Set to true if point indices are used. | |
| bool | fake_indices_ |
| If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. | |
Additional Inherited Members | |
| Public Types inherited from pcl::VoxelGrid< PointT > | |
| using | Ptr = shared_ptr<VoxelGrid<PointT> > |
| using | ConstPtr = shared_ptr<const VoxelGrid<PointT> > |
| Public Types inherited from pcl::Filter< PointT > | |
| using | Ptr = shared_ptr<Filter<PointT> > |
| using | ConstPtr = shared_ptr<const Filter<PointT> > |
| using | PointCloud = pcl::PointCloud<PointT> |
| using | PointCloudPtr = typename PointCloud::Ptr |
| using | PointCloudConstPtr = typename PointCloud::ConstPtr |
| Public Types inherited from pcl::PCLBase< PointT > | |
| using | PointCloud = pcl::PointCloud<PointT> |
| using | PointCloudPtr = typename PointCloud::Ptr |
| using | PointCloudConstPtr = typename PointCloud::ConstPtr |
| using | PointIndicesPtr = PointIndices::Ptr |
| using | PointIndicesConstPtr = PointIndices::ConstPtr |
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' Example code:
Definition at line 63 of file voxel_grid_occlusion_estimation.h.
|
protected |
Definition at line 72 of file voxel_grid_occlusion_estimation.h.
|
protected |
Definition at line 74 of file voxel_grid_occlusion_estimation.h.
|
protected |
Definition at line 73 of file voxel_grid_occlusion_estimation.h.
|
inline |
Empty constructor.
Definition at line 81 of file voxel_grid_occlusion_estimation.h.
References initialized_, and pcl::VoxelGrid< PointT >::setSaveLeafLayout().
|
overridedefault |
Destructor.
|
inline |
Returns the corresponding centroid (x,y,z) coordinates in the grid of voxel (i,j,k).
| [in] | ijk | the coordinate (i, j, k) of the voxel |
Definition at line 156 of file voxel_grid_occlusion_estimation.h.
References b_min_, pcl::VoxelGrid< PointT >::leaf_size_, and pcl::VoxelGrid< PointT >::min_b_.
Referenced by occlusionEstimation(), occlusionEstimation(), occlusionEstimationAll(), rayTraversal(), and rayTraversal().
|
inline |
Returns the voxel grid filtered point cloud.
Definition at line 135 of file voxel_grid_occlusion_estimation.h.
References filtered_cloud_.
|
inlineprotected |
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 235 of file voxel_grid_occlusion_estimation.h.
References pcl::VoxelGrid< PointT >::inverse_leaf_size_, and round().
|
inline |
Returns the maximum bounding of coordinates of the voxel grid (x,y,z).
Definition at line 148 of file voxel_grid_occlusion_estimation.h.
References b_max_.
|
inline |
Returns the minimum bounding of coordinates of the voxel grid (x,y,z).
Definition at line 142 of file voxel_grid_occlusion_estimation.h.
References b_min_.
| 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 46 of file voxel_grid_occlusion_estimation.hpp.
References b_max_, b_min_, pcl::VoxelGrid< PointT >::divb_mul_, pcl::Filter< PointT >::filter(), filtered_cloud_, pcl::VoxelGrid< PointT >::getCentroidIndexAt(), pcl::VoxelGrid< PointT >::getGridCoordinates(), initialized_, pcl::VoxelGrid< PointT >::leaf_layout_, pcl::VoxelGrid< PointT >::leaf_size_, pcl::VoxelGrid< PointT >::max_b_, pcl::VoxelGrid< PointT >::min_b_, sensor_orientation_, and sensor_origin_.
| int pcl::VoxelGridOcclusionEstimation< PointT >::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 a target voxel in (i, j, k) coordinates.
| [out] | out_state | The state of the voxel. |
| [in] | in_target_voxel | The target voxel coordinate (i, j, k) of the voxel. |
Definition at line 76 of file voxel_grid_occlusion_estimation.hpp.
References getCentroidCoordinate(), initialized_, rayBoxIntersection(), rayTraversal(), and sensor_origin_.
| int pcl::VoxelGridOcclusionEstimation< PointT >::occlusionEstimation | ( | int & | out_state, |
| std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > & | out_ray, | ||
| const Eigen::Vector3i & | in_target_voxel ) |
Computes 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] | out_state | The state of the voxel. |
| [out] | out_ray | The voxels penetrated of the ray-traversal algorithm. |
| [in] | in_target_voxel | The target voxel coordinate (i, j, k) of the voxel. |
Definition at line 107 of file voxel_grid_occlusion_estimation.hpp.
References getCentroidCoordinate(), initialized_, rayBoxIntersection(), rayTraversal(), and sensor_origin_.
| int pcl::VoxelGridOcclusionEstimation< PointT >::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.
| [out] | occluded_voxels | the coordinates (i, j, k) of all occluded voxels |
Definition at line 139 of file voxel_grid_occlusion_estimation.hpp.
References pcl::VoxelGrid< PointT >::div_b_, getCentroidCoordinate(), pcl::VoxelGrid< PointT >::getCentroidIndexAt(), initialized_, pcl::VoxelGrid< PointT >::max_b_, pcl::VoxelGrid< PointT >::min_b_, rayBoxIntersection(), rayTraversal(), and sensor_origin_.
|
protected |
Returns the scaling value (tmin) were the ray intersects with the voxel grid bounding box.
(p_entry = origin + tmin * orientation)
| [in] | origin | The sensor origin |
| [in] | direction | The sensor orientation |
Definition at line 182 of file voxel_grid_occlusion_estimation.hpp.
References b_max_, and b_min_.
Referenced by occlusionEstimation(), occlusionEstimation(), and occlusionEstimationAll().
|
protected |
Returns the state of the target voxel (0 = visible, 1 = occupied) using a ray traversal algorithm.
| [in] | target_voxel | The target voxel in the voxel grid with coordinate (i, j, k). |
| [in] | origin | The sensor origin. |
| [in] | direction | The sensor orientation |
| [in] | t_min | The scaling value (tmin). |
Definition at line 248 of file voxel_grid_occlusion_estimation.hpp.
References getCentroidCoordinate(), pcl::VoxelGrid< PointT >::getCentroidIndexAt(), pcl::VoxelGrid< PointT >::getGridCoordinates(), pcl::VoxelGrid< PointT >::leaf_size_, pcl::VoxelGrid< PointT >::max_b_, and pcl::VoxelGrid< PointT >::min_b_.
Referenced by occlusionEstimation(), occlusionEstimation(), and occlusionEstimationAll().
|
protected |
Returns the state of the target voxel (0 = visible, 1 = occupied) and the voxels penetrated by the ray using a ray traversal algorithm.
| [out] | out_ray | The voxels penetrated by the ray in (i, j, k) coordinates |
| [in] | target_voxel | The target voxel in the voxel grid with coordinate (i, j, k). |
| [in] | origin | The sensor origin. |
| [in] | direction | The sensor orientation |
| [in] | t_min | The scaling value (tmin). |
Definition at line 341 of file voxel_grid_occlusion_estimation.hpp.
References pcl::VoxelGrid< PointT >::div_b_, getCentroidCoordinate(), pcl::VoxelGrid< PointT >::getCentroidIndexAt(), pcl::VoxelGrid< PointT >::getGridCoordinates(), pcl::VoxelGrid< PointT >::leaf_size_, pcl::VoxelGrid< PointT >::max_b_, and pcl::VoxelGrid< PointT >::min_b_.
|
inlineprotected |
Returns a value rounded to the nearest integer.
| [in] | d |
Definition at line 224 of file voxel_grid_occlusion_estimation.h.
Referenced by getGridCoordinatesRound().
|
protected |
Definition at line 249 of file voxel_grid_occlusion_estimation.h.
Referenced by getMaxBoundCoordinates(), initializeVoxelGrid(), and rayBoxIntersection().
|
protected |
Definition at line 249 of file voxel_grid_occlusion_estimation.h.
Referenced by getCentroidCoordinate(), getMinBoundCoordinates(), initializeVoxelGrid(), and rayBoxIntersection().
|
protected |
Definition at line 252 of file voxel_grid_occlusion_estimation.h.
Referenced by getFilteredPointCloud(), and initializeVoxelGrid().
|
protected |
Definition at line 243 of file voxel_grid_occlusion_estimation.h.
Referenced by initializeVoxelGrid(), occlusionEstimation(), occlusionEstimation(), occlusionEstimationAll(), and VoxelGridOcclusionEstimation().
|
protected |
Definition at line 246 of file voxel_grid_occlusion_estimation.h.
Referenced by initializeVoxelGrid().
|
protected |
Definition at line 245 of file voxel_grid_occlusion_estimation.h.
Referenced by initializeVoxelGrid(), occlusionEstimation(), occlusionEstimation(), and occlusionEstimationAll().