Point Cloud Library (PCL)  1.13.1-dev
voxel_grid_occlusion_estimation.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author : Christian Potthast
37  * Email : potthast@usc.edu
38  *
39  */
40 
41 #pragma once
42 
43 #include <pcl/filters/voxel_grid.h>
44 
45 namespace pcl
46 {
47  /** \brief VoxelGrid to estimate occluded space in the scene.
48  * The ray traversal algorithm is implemented by the work of
49  * 'John Amanatides and Andrew Woo, A Fast Voxel Traversal Algorithm for Ray Tracing'
50  *
51  * \author Christian Potthast
52  * \ingroup filters
53  */
54  template <typename PointT>
56  {
57  protected:
63 
65  using PointCloudPtr = typename PointCloud::Ptr;
67 
68  public:
69 
71 
72  /** \brief Empty constructor. */
74  {
75  initialized_ = false;
76  this->setSaveLeafLayout (true);
77  }
78 
79  /** \brief Destructor. */
80  ~VoxelGridOcclusionEstimation () override = default;
81 
82  /** \brief Initialize the voxel grid, needs to be called first
83  * Builts the voxel grid and computes additional values for
84  * the ray traversal algorithm.
85  */
86  void
88 
89  /** \brief Computes the state (free = 0, occluded = 1) of the voxel
90  * after utilizing a ray traversal algorithm to a target voxel
91  * in (i, j, k) coordinates.
92  * \param[out] out_state The state of the voxel.
93  * \param[in] in_target_voxel The target voxel coordinate (i, j, k) of the voxel.
94  * \return 0 upon success and -1 if an error occurs
95  */
96  int
97  occlusionEstimation (int& out_state,
98  const Eigen::Vector3i& in_target_voxel);
99 
100  /** \brief Computes the state (free = 0, occluded = 1) of the voxel
101  * after utilizing a ray traversal algorithm to a target voxel
102  * in (i, j, k) coordinates. Additionally, this function returns
103  * the voxels penetrated of the ray-traversal algorithm till reaching
104  * the target voxel.
105  * \param[out] out_state The state of the voxel.
106  * \param[out] out_ray The voxels penetrated of the ray-traversal algorithm.
107  * \param[in] in_target_voxel The target voxel coordinate (i, j, k) of the voxel.
108  * \return 0 upon success and -1 if an error occurs
109  */
110  int
111  occlusionEstimation (int& out_state,
112  std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> >& out_ray,
113  const Eigen::Vector3i& in_target_voxel);
114 
115  /** \brief Computes the voxel coordinates (i, j, k) of all occluded
116  * voxels in the voxel grid.
117  * \param[out] occluded_voxels the coordinates (i, j, k) of all occluded voxels
118  * \return 0 upon success and -1 if an error occurs
119  */
120  int
121  occlusionEstimationAll (std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> >& occluded_voxels);
122 
123  /** \brief Returns the voxel grid filtered point cloud
124  * \return The voxel grid filtered point cloud
125  */
126  inline PointCloud
128 
129 
130  /** \brief Returns the minimum bounding of coordinates of the voxel grid (x,y,z).
131  * \return the minimum coordinates (x,y,z)
132  */
133  inline Eigen::Vector3f
134  getMinBoundCoordinates () { return (b_min_.head<3> ()); }
135 
136  /** \brief Returns the maximum bounding of coordinates of the voxel grid (x,y,z).
137  * \return the maximum coordinates (x,y,z)
138  */
139  inline Eigen::Vector3f
140  getMaxBoundCoordinates () { return (b_max_.head<3> ()); }
141 
142  /** \brief Returns the corresponding centroid (x,y,z) coordinates
143  * in the grid of voxel (i,j,k).
144  * \param[in] ijk the coordinate (i, j, k) of the voxel
145  * \return the (x,y,z) coordinate of the voxel centroid
146  */
147  inline Eigen::Vector4f
148  getCentroidCoordinate (const Eigen::Vector3i& ijk)
149  {
150  int i,j,k;
151  i = ((b_min_[0] < 0) ? (std::abs (min_b_[0]) + ijk[0]) : (ijk[0] - min_b_[0]));
152  j = ((b_min_[1] < 0) ? (std::abs (min_b_[1]) + ijk[1]) : (ijk[1] - min_b_[1]));
153  k = ((b_min_[2] < 0) ? (std::abs (min_b_[2]) + ijk[2]) : (ijk[2] - min_b_[2]));
154 
155  Eigen::Vector4f xyz;
156  xyz[0] = b_min_[0] + (leaf_size_[0] * 0.5f) + (static_cast<float> (i) * leaf_size_[0]);
157  xyz[1] = b_min_[1] + (leaf_size_[1] * 0.5f) + (static_cast<float> (j) * leaf_size_[1]);
158  xyz[2] = b_min_[2] + (leaf_size_[2] * 0.5f) + (static_cast<float> (k) * leaf_size_[2]);
159  xyz[3] = 0;
160  return xyz;
161  }
162 
163  // inline void
164  // setSensorOrigin (const Eigen::Vector4f origin) { sensor_origin_ = origin; }
165 
166  // inline void
167  // setSensorOrientation (const Eigen::Quaternionf orientation) { sensor_orientation_ = orientation; }
168 
169  protected:
170 
171  /** \brief Returns the scaling value (tmin) were the ray intersects with the
172  * voxel grid bounding box. (p_entry = origin + tmin * orientation)
173  * \param[in] origin The sensor origin
174  * \param[in] direction The sensor orientation
175  * \return the scaling value
176  */
177  float
178  rayBoxIntersection (const Eigen::Vector4f& origin,
179  const Eigen::Vector4f& direction);
180 
181  /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied)
182  * using a ray traversal algorithm.
183  * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k).
184  * \param[in] origin The sensor origin.
185  * \param[in] direction The sensor orientation
186  * \param[in] t_min The scaling value (tmin).
187  * \return The estimated voxel state.
188  */
189  int
190  rayTraversal (const Eigen::Vector3i& target_voxel,
191  const Eigen::Vector4f& origin,
192  const Eigen::Vector4f& direction,
193  const float t_min);
194 
195  /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied) and
196  * the voxels penetrated by the ray using a ray traversal algorithm.
197  * \param[out] out_ray The voxels penetrated by the ray in (i, j, k) coordinates
198  * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k).
199  * \param[in] origin The sensor origin.
200  * \param[in] direction The sensor orientation
201  * \param[in] t_min The scaling value (tmin).
202  * \return The estimated voxel state.
203  */
204  int
205  rayTraversal (std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> >& out_ray,
206  const Eigen::Vector3i& target_voxel,
207  const Eigen::Vector4f& origin,
208  const Eigen::Vector4f& direction,
209  const float t_min);
210 
211  /** \brief Returns a rounded value.
212  * \param[in] d
213  * \return rounded value
214  */
215  inline float
216  round (float d)
217  {
218  return static_cast<float> (std::floor (d + 0.5f));
219  }
220 
221  // We use round here instead of std::floor due to some numerical issues.
222  /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
223  * \param[in] x the X point coordinate to get the (i, j, k) index at
224  * \param[in] y the Y point coordinate to get the (i, j, k) index at
225  * \param[in] z the Z point coordinate to get the (i, j, k) index at
226  */
227  inline Eigen::Vector3i
228  getGridCoordinatesRound (float x, float y, float z)
229  {
230  return {static_cast<int> (round (x * inverse_leaf_size_[0])),
231  static_cast<int> (round (y * inverse_leaf_size_[1])),
232  static_cast<int> (round (z * inverse_leaf_size_[2]))};
233  }
234 
235  // initialization flag
237 
238  Eigen::Vector4f sensor_origin_;
239  Eigen::Quaternionf sensor_orientation_;
240 
241  // minimum and maximum bounding box coordinates
242  Eigen::Vector4f b_min_, b_max_;
243 
244  // voxel grid filtered cloud
246  };
247 }
248 
249 #ifdef PCL_NO_PRECOMPILE
250 #include <pcl/filters/impl/voxel_grid_occlusion_estimation.hpp>
251 #endif
typename PointCloud::Ptr PointCloudPtr
Definition: pcl_base.h:73
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_base.h:74
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition: voxel_grid.h:177
Eigen::Vector4i min_b_
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
Definition: voxel_grid.h:465
void setSaveLeafLayout(bool save_leaf_layout)
Set to true if leaf layout information needs to be saved for later access.
Definition: voxel_grid.h:271
Eigen::Vector4f leaf_size_
The size of a leaf.
Definition: voxel_grid.h:450
Eigen::Array4f inverse_leaf_size_
Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
Definition: voxel_grid.h:453
VoxelGrid to estimate occluded space in the scene.
typename Filter< PointT >::PointCloud PointCloud
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.
PCL_MAKE_ALIGNED_OPERATOR_NEW VoxelGridOcclusionEstimation()
Empty constructor.
float round(float d)
Returns a rounded value.
Eigen::Vector3i getGridCoordinatesRound(float x, float y, float z)
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
PointCloud getFilteredPointCloud()
Returns the voxel grid filtered point cloud.
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.
Eigen::Vector3f getMaxBoundCoordinates()
Returns the maximum bounding of coordinates of the voxel grid (x,y,z).
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.
~VoxelGridOcclusionEstimation() override=default
Destructor.
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::Vector3f getMinBoundCoordinates()
Returns the minimum 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).
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63