Point Cloud Library (PCL)  1.11.1-dev
octree_pointcloud.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  * $Id$
37  */
38 
39 #pragma once
40 
41 #include <pcl/octree/octree_base.h>
42 #include <pcl/point_cloud.h>
43 #include <pcl/point_types.h>
44 
45 #include <vector>
46 
47 namespace pcl {
48 namespace octree {
49 
50 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
51 /** \brief @b Octree pointcloud class
52  * \note Octree implementation for pointclouds. Only indices are stored by the octree
53  * leaf nodes (zero-copy).
54  * \note The octree pointcloud class needs to be initialized with its voxel resolution.
55  * Its bounding box is automatically adjusted
56  * \note according to the pointcloud dimension or it can be predefined.
57  * \note Note: The tree depth equates to the resolution and the bounding box dimensions
58  * of the octree.
59  * \tparam PointT: type of point used in pointcloud
60  * \tparam LeafContainerT: leaf node container
61  * \tparam BranchContainerT: branch node container
62  * \tparam OctreeT: octree implementation
63  * \ingroup octree
64  * \author Julius Kammerl * (julius@kammerl.de)
65  */
66 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
67 template <typename PointT,
68  typename LeafContainerT = OctreeContainerPointIndices,
69  typename BranchContainerT = OctreeContainerEmpty,
70  typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
71 
72 class OctreePointCloud : public OctreeT {
73 public:
74  using Base = OctreeT;
75 
76  using LeafNode = typename OctreeT::LeafNode;
77  using BranchNode = typename OctreeT::BranchNode;
78 
79  /** \brief Octree pointcloud constructor.
80  * \param[in] resolution_arg octree resolution at lowest octree level
81  */
82  OctreePointCloud(const double resolution_arg);
83 
84  // public typedefs
85  using IndicesPtr = shared_ptr<std::vector<int>>;
86  using IndicesConstPtr = shared_ptr<const std::vector<int>>;
87 
89  using PointCloudPtr = typename PointCloud::Ptr;
91 
92  // public typedefs for single/double buffering
94  LeafContainerT,
95  BranchContainerT,
97  // using DoubleBuffer = OctreePointCloud<PointT, LeafContainerT, BranchContainerT,
98  // Octree2BufBase<LeafContainerT> >;
99 
100  // Boost shared pointers
101  using Ptr =
102  shared_ptr<OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>>;
103  using ConstPtr = shared_ptr<
105 
106  // Eigen aligned allocator
107  using AlignedPointTVector = std::vector<PointT, Eigen::aligned_allocator<PointT>>;
108  using AlignedPointXYZVector =
109  std::vector<PointXYZ, Eigen::aligned_allocator<PointXYZ>>;
110 
111  /** \brief Provide a pointer to the input data set.
112  * \param[in] cloud_arg the const boost shared pointer to a PointCloud message
113  * \param[in] indices_arg the point indices subset that is to be used from \a cloud -
114  * if 0 the whole point cloud is used
115  */
116  inline void
118  const IndicesConstPtr& indices_arg = IndicesConstPtr())
119  {
120  input_ = cloud_arg;
121  indices_ = indices_arg;
122  }
123 
124  /** \brief Get a pointer to the vector of indices used.
125  * \return pointer to vector of indices used.
126  */
127  inline IndicesConstPtr const
128  getIndices() const
129  {
130  return (indices_);
131  }
132 
133  /** \brief Get a pointer to the input point cloud dataset.
134  * \return pointer to pointcloud input class.
135  */
136  inline PointCloudConstPtr
138  {
139  return (input_);
140  }
141 
142  /** \brief Set the search epsilon precision (error bound) for nearest neighbors
143  * searches.
144  * \param[in] eps precision (error bound) for nearest neighbors searches
145  */
146  inline void
147  setEpsilon(double eps)
148  {
149  epsilon_ = eps;
150  }
151 
152  /** \brief Get the search epsilon precision (error bound) for nearest neighbors
153  * searches. */
154  inline double
155  getEpsilon() const
156  {
157  return (epsilon_);
158  }
159 
160  /** \brief Set/change the octree voxel resolution
161  * \param[in] resolution_arg side length of voxels at lowest tree level
162  */
163  inline void
164  setResolution(double resolution_arg)
165  {
166  // octree needs to be empty to change its resolution
167  assert(this->leaf_count_ == 0);
168 
169  resolution_ = resolution_arg;
170 
171  getKeyBitSize();
172  }
173 
174  /** \brief Get octree voxel resolution
175  * \return voxel resolution at lowest tree level
176  */
177  inline double
179  {
180  return (resolution_);
181  }
182 
183  /** \brief Get the maximum depth of the octree.
184  * \return depth_arg: maximum depth of octree
185  * */
186  inline unsigned int
187  getTreeDepth() const
188  {
189  return this->octree_depth_;
190  }
191 
192  /** \brief Add points from input point cloud to octree. */
193  void
195 
196  /** \brief Add point at given index from input point cloud to octree. Index will be
197  * also added to indices vector.
198  * \param[in] point_idx_arg index of point to be added
199  * \param[in] indices_arg pointer to indices vector of the dataset (given by \a
200  * setInputCloud)
201  */
202  void
203  addPointFromCloud(const int point_idx_arg, IndicesPtr indices_arg);
204 
205  /** \brief Add point simultaneously to octree and input point cloud.
206  * \param[in] point_arg point to be added
207  * \param[in] cloud_arg pointer to input point cloud dataset (given by \a
208  * setInputCloud)
209  */
210  void
211  addPointToCloud(const PointT& point_arg, PointCloudPtr cloud_arg);
212 
213  /** \brief Add point simultaneously to octree and input point cloud. A corresponding
214  * index will be added to the indices vector.
215  * \param[in] point_arg point to be added
216  * \param[in] cloud_arg pointer to input point cloud dataset (given by \a
217  * setInputCloud)
218  * \param[in] indices_arg pointer to indices vector of the dataset (given by \a
219  * setInputCloud)
220  */
221  void
222  addPointToCloud(const PointT& point_arg,
223  PointCloudPtr cloud_arg,
224  IndicesPtr indices_arg);
225 
226  /** \brief Check if voxel at given point exist.
227  * \param[in] point_arg point to be checked
228  * \return "true" if voxel exist; "false" otherwise
229  */
230  bool
231  isVoxelOccupiedAtPoint(const PointT& point_arg) const;
232 
233  /** \brief Delete the octree structure and its leaf nodes.
234  * */
235  void
237  {
238  // reset bounding box
239  min_x_ = min_y_ = max_y_ = min_z_ = max_z_ = 0;
240  this->bounding_box_defined_ = false;
241 
243  }
244 
245  /** \brief Check if voxel at given point coordinates exist.
246  * \param[in] point_x_arg X coordinate of point to be checked
247  * \param[in] point_y_arg Y coordinate of point to be checked
248  * \param[in] point_z_arg Z coordinate of point to be checked
249  * \return "true" if voxel exist; "false" otherwise
250  */
251  bool
252  isVoxelOccupiedAtPoint(const double point_x_arg,
253  const double point_y_arg,
254  const double point_z_arg) const;
255 
256  /** \brief Check if voxel at given point from input cloud exist.
257  * \param[in] point_idx_arg point to be checked
258  * \return "true" if voxel exist; "false" otherwise
259  */
260  bool
261  isVoxelOccupiedAtPoint(const int& point_idx_arg) const;
262 
263  /** \brief Get a PointT vector of centers of all occupied voxels.
264  * \param[out] voxel_center_list_arg results are written to this vector of PointT
265  * elements
266  * \return number of occupied voxels
267  */
268  int
269  getOccupiedVoxelCenters(AlignedPointTVector& voxel_center_list_arg) const;
270 
271  /** \brief Get a PointT vector of centers of voxels intersected by a line segment.
272  * This returns a approximation of the actual intersected voxels by walking
273  * along the line with small steps. Voxels are ordered, from closest to
274  * furthest w.r.t. the origin.
275  * \param[in] origin origin of the line segment
276  * \param[in] end end of the line segment
277  * \param[out] voxel_center_list results are written to this vector of PointT elements
278  * \param[in] precision determines the size of the steps: step_size =
279  * octree_resolution x precision
280  * \return number of intersected voxels
281  */
282  int
283  getApproxIntersectedVoxelCentersBySegment(const Eigen::Vector3f& origin,
284  const Eigen::Vector3f& end,
285  AlignedPointTVector& voxel_center_list,
286  float precision = 0.2);
287 
288  /** \brief Delete leaf node / voxel at given point
289  * \param[in] point_arg point addressing the voxel to be deleted.
290  */
291  void
292  deleteVoxelAtPoint(const PointT& point_arg);
293 
294  /** \brief Delete leaf node / voxel at given point from input cloud
295  * \param[in] point_idx_arg index of point addressing the voxel to be deleted.
296  */
297  void
298  deleteVoxelAtPoint(const int& point_idx_arg);
299 
300  //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
301  // Bounding box methods
302  //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
303 
304  /** \brief Investigate dimensions of pointcloud data set and define corresponding
305  * bounding box for octree. */
306  void
308 
309  /** \brief Define bounding box for octree
310  * \note Bounding box cannot be changed once the octree contains elements.
311  * \param[in] min_x_arg X coordinate of lower bounding box corner
312  * \param[in] min_y_arg Y coordinate of lower bounding box corner
313  * \param[in] min_z_arg Z coordinate of lower bounding box corner
314  * \param[in] max_x_arg X coordinate of upper bounding box corner
315  * \param[in] max_y_arg Y coordinate of upper bounding box corner
316  * \param[in] max_z_arg Z coordinate of upper bounding box corner
317  */
318  void
319  defineBoundingBox(const double min_x_arg,
320  const double min_y_arg,
321  const double min_z_arg,
322  const double max_x_arg,
323  const double max_y_arg,
324  const double max_z_arg);
325 
326  /** \brief Define bounding box for octree
327  * \note Lower bounding box point is set to (0, 0, 0)
328  * \note Bounding box cannot be changed once the octree contains elements.
329  * \param[in] max_x_arg X coordinate of upper bounding box corner
330  * \param[in] max_y_arg Y coordinate of upper bounding box corner
331  * \param[in] max_z_arg Z coordinate of upper bounding box corner
332  */
333  void
334  defineBoundingBox(const double max_x_arg,
335  const double max_y_arg,
336  const double max_z_arg);
337 
338  /** \brief Define bounding box cube for octree
339  * \note Lower bounding box corner is set to (0, 0, 0)
340  * \note Bounding box cannot be changed once the octree contains elements.
341  * \param[in] cubeLen_arg side length of bounding box cube.
342  */
343  void
344  defineBoundingBox(const double cubeLen_arg);
345 
346  /** \brief Get bounding box for octree
347  * \note Bounding box cannot be changed once the octree contains elements.
348  * \param[in] min_x_arg X coordinate of lower bounding box corner
349  * \param[in] min_y_arg Y coordinate of lower bounding box corner
350  * \param[in] min_z_arg Z coordinate of lower bounding box corner
351  * \param[in] max_x_arg X coordinate of upper bounding box corner
352  * \param[in] max_y_arg Y coordinate of upper bounding box corner
353  * \param[in] max_z_arg Z coordinate of upper bounding box corner
354  */
355  void
356  getBoundingBox(double& min_x_arg,
357  double& min_y_arg,
358  double& min_z_arg,
359  double& max_x_arg,
360  double& max_y_arg,
361  double& max_z_arg) const;
362 
363  /** \brief Calculates the squared diameter of a voxel at given tree depth
364  * \param[in] tree_depth_arg depth/level in octree
365  * \return squared diameter
366  */
367  double
368  getVoxelSquaredDiameter(unsigned int tree_depth_arg) const;
369 
370  /** \brief Calculates the squared diameter of a voxel at leaf depth
371  * \return squared diameter
372  */
373  inline double
375  {
377  }
378 
379  /** \brief Calculates the squared voxel cube side length at given tree depth
380  * \param[in] tree_depth_arg depth/level in octree
381  * \return squared voxel cube side length
382  */
383  double
384  getVoxelSquaredSideLen(unsigned int tree_depth_arg) const;
385 
386  /** \brief Calculates the squared voxel cube side length at leaf level
387  * \return squared voxel cube side length
388  */
389  inline double
391  {
393  }
394 
395  /** \brief Generate bounds of the current voxel of an octree iterator
396  * \param[in] iterator: octree iterator
397  * \param[out] min_pt lower bound of voxel
398  * \param[out] max_pt upper bound of voxel
399  */
400  inline void
402  Eigen::Vector3f& min_pt,
403  Eigen::Vector3f& max_pt) const
404  {
406  iterator.getCurrentOctreeDepth(),
407  min_pt,
408  max_pt);
409  }
410 
411  /** \brief Enable dynamic octree structure
412  * \note Leaf nodes are kept as close to the root as possible and are only expanded
413  * if the number of DataT objects within a leaf node exceeds a fixed limit.
414  * \param maxObjsPerLeaf: maximum number of DataT objects per leaf
415  * */
416  inline void
417  enableDynamicDepth(std::size_t maxObjsPerLeaf)
418  {
419  assert(this->leaf_count_ == 0);
420  max_objs_per_leaf_ = maxObjsPerLeaf;
421 
423  }
424 
425 protected:
426  /** \brief Add point at index from input pointcloud dataset to octree
427  * \param[in] point_idx_arg the index representing the point in the dataset given by
428  * \a setInputCloud to be added
429  */
430  virtual void
431  addPointIdx(const int point_idx_arg);
432 
433  /** \brief Add point at index from input pointcloud dataset to octree
434  * \param[in] leaf_node to be expanded
435  * \param[in] parent_branch parent of leaf node to be expanded
436  * \param[in] child_idx child index of leaf node (in parent branch)
437  * \param[in] depth_mask of leaf node to be expanded
438  */
439  void
440  expandLeafNode(LeafNode* leaf_node,
441  BranchNode* parent_branch,
442  unsigned char child_idx,
443  unsigned int depth_mask);
444 
445  /** \brief Get point at index from input pointcloud dataset
446  * \param[in] index_arg index representing the point in the dataset given by \a
447  * setInputCloud
448  * \return PointT from input pointcloud dataset
449  */
450  const PointT&
451  getPointByIndex(const unsigned int index_arg) const;
452 
453  /** \brief Find octree leaf node at a given point
454  * \param[in] point_arg query point
455  * \return pointer to leaf node. If leaf node does not exist, pointer is 0.
456  */
457  LeafContainerT*
458  findLeafAtPoint(const PointT& point_arg) const
459  {
460  OctreeKey key;
461 
462  // generate key for point
463  this->genOctreeKeyforPoint(point_arg, key);
464 
465  return (this->findLeaf(key));
466  }
467 
468  //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
469  // Protected octree methods based on octree keys
470  //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
471 
472  /** \brief Define octree key setting and octree depth based on defined bounding box.
473  */
474  void
475  getKeyBitSize();
476 
477  /** \brief Grow the bounding box/octree until point fits
478  * \param[in] point_idx_arg point that should be within bounding box;
479  */
480  void
481  adoptBoundingBoxToPoint(const PointT& point_idx_arg);
482 
483  /** \brief Checks if given point is within the bounding box of the octree
484  * \param[in] point_idx_arg point to be checked for bounding box violations
485  * \return "true" - no bound violation
486  */
487  inline bool
488  isPointWithinBoundingBox(const PointT& point_idx_arg) const
489  {
490  return (!((point_idx_arg.x < min_x_) || (point_idx_arg.y < min_y_) ||
491  (point_idx_arg.z < min_z_) || (point_idx_arg.x >= max_x_) ||
492  (point_idx_arg.y >= max_y_) || (point_idx_arg.z >= max_z_)));
493  }
494 
495  /** \brief Generate octree key for voxel at a given point
496  * \param[in] point_arg the point addressing a voxel
497  * \param[out] key_arg write octree key to this reference
498  */
499  void
500  genOctreeKeyforPoint(const PointT& point_arg, OctreeKey& key_arg) const;
501 
502  /** \brief Generate octree key for voxel at a given point
503  * \param[in] point_x_arg X coordinate of point addressing a voxel
504  * \param[in] point_y_arg Y coordinate of point addressing a voxel
505  * \param[in] point_z_arg Z coordinate of point addressing a voxel
506  * \param[out] key_arg write octree key to this reference
507  */
508  void
509  genOctreeKeyforPoint(const double point_x_arg,
510  const double point_y_arg,
511  const double point_z_arg,
512  OctreeKey& key_arg) const;
513 
514  /** \brief Virtual method for generating octree key for a given point index.
515  * \note This method enables to assign indices to leaf nodes during octree
516  * deserialization.
517  * \param[in] data_arg index value representing a point in the dataset given by \a
518  * setInputCloud
519  * \param[out] key_arg write octree key to this reference \return "true" - octree keys
520  * are assignable
521  */
522  virtual bool
523  genOctreeKeyForDataT(const int& data_arg, OctreeKey& key_arg) const;
524 
525  /** \brief Generate a point at center of leaf node voxel
526  * \param[in] key_arg octree key addressing a leaf node.
527  * \param[out] point_arg write leaf node voxel center to this point reference
528  */
529  void
530  genLeafNodeCenterFromOctreeKey(const OctreeKey& key_arg, PointT& point_arg) const;
531 
532  /** \brief Generate a point at center of octree voxel at given tree level
533  * \param[in] key_arg octree key addressing an octree node.
534  * \param[in] tree_depth_arg octree depth of query voxel
535  * \param[out] point_arg write leaf node center point to this reference
536  */
537  void
538  genVoxelCenterFromOctreeKey(const OctreeKey& key_arg,
539  unsigned int tree_depth_arg,
540  PointT& point_arg) const;
541 
542  /** \brief Generate bounds of an octree voxel using octree key and tree depth
543  * arguments
544  * \param[in] key_arg octree key addressing an octree node.
545  * \param[in] tree_depth_arg octree depth of query voxel
546  * \param[out] min_pt lower bound of voxel
547  * \param[out] max_pt upper bound of voxel
548  */
549  void
550  genVoxelBoundsFromOctreeKey(const OctreeKey& key_arg,
551  unsigned int tree_depth_arg,
552  Eigen::Vector3f& min_pt,
553  Eigen::Vector3f& max_pt) const;
554 
555  /** \brief Recursively search the tree for all leaf nodes and return a vector of voxel
556  * centers.
557  * \param[in] node_arg current octree node to be explored
558  * \param[in] key_arg octree key addressing a leaf node.
559  * \param[out] voxel_center_list_arg results are written to this vector of PointT
560  * elements
561  * \return number of voxels found
562  */
563  int
565  const OctreeKey& key_arg,
566  AlignedPointTVector& voxel_center_list_arg) const;
567 
568  //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
569  // Globals
570  //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
571  /** \brief Pointer to input point cloud dataset. */
573 
574  /** \brief A pointer to the vector of point indices to use. */
576 
577  /** \brief Epsilon precision (error bound) for nearest neighbors searches. */
578  double epsilon_;
579 
580  /** \brief Octree resolution. */
581  double resolution_;
582 
583  // Octree bounding box coordinates
584  double min_x_;
585  double max_x_;
586 
587  double min_y_;
588  double max_y_;
589 
590  double min_z_;
591  double max_z_;
592 
593  /** \brief Flag indicating if octree has defined bounding box. */
595 
596  /** \brief Amount of DataT objects per leafNode before expanding branch
597  * \note zero indicates a fixed/maximum depth octree structure
598  * **/
599  std::size_t max_objs_per_leaf_;
600 };
601 
602 } // namespace octree
603 } // namespace pcl
604 
605 #ifdef PCL_NO_PRECOMPILE
606 #include <pcl/octree/impl/octree_pointcloud.hpp>
607 #endif
pcl::octree::OctreePointCloud::getVoxelSquaredDiameter
double getVoxelSquaredDiameter() const
Calculates the squared diameter of a voxel at leaf depth.
Definition: octree_pointcloud.h:374
pcl
Definition: convolution.h:46
pcl::octree::OctreePointCloud::max_objs_per_leaf_
std::size_t max_objs_per_leaf_
Amount of DataT objects per leafNode before expanding branch.
Definition: octree_pointcloud.h:599
point_types.h
pcl::IndicesPtr
shared_ptr< Indices > IndicesPtr
Definition: pcl_base.h:58
pcl::octree::OctreePointCloud::deleteVoxelAtPoint
void deleteVoxelAtPoint(const PointT &point_arg)
Delete leaf node / voxel at given point.
Definition: octree_pointcloud.hpp:215
pcl::octree::OctreePointCloud::genOctreeKeyforPoint
void genOctreeKeyforPoint(const PointT &point_arg, OctreeKey &key_arg) const
Generate octree key for voxel at a given point.
Definition: octree_pointcloud.hpp:792
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::deleteTree
void deleteTree()
Delete the octree structure and its leaf nodes.
Definition: octree_base.hpp:161
pcl::octree::OctreePointCloud::getOccupiedVoxelCenters
int getOccupiedVoxelCenters(AlignedPointTVector &voxel_center_list_arg) const
Get a PointT vector of centers of all occupied voxels.
Definition: octree_pointcloud.hpp:252
pcl::octree::OctreePointCloud::isPointWithinBoundingBox
bool isPointWithinBoundingBox(const PointT &point_idx_arg) const
Checks if given point is within the bounding box of the octree.
Definition: octree_pointcloud.h:488
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::PointCloudConstPtr
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: octree_pointcloud.h:90
pcl::octree::OctreePointCloud::resolution_
double resolution_
Octree resolution.
Definition: octree_pointcloud.h:581
pcl::octree::OctreePointCloud
Octree pointcloud class
Definition: octree_pointcloud.h:72
pcl::octree::OctreePointCloud::getKeyBitSize
void getKeyBitSize()
Define octree key setting and octree depth based on defined bounding box.
Definition: octree_pointcloud.hpp:716
pcl::IndicesConstPtr
shared_ptr< const Indices > IndicesConstPtr
Definition: pcl_base.h:59
pcl::octree::OctreePointCloud::deleteTree
void deleteTree()
Delete the octree structure and its leaf nodes.
Definition: octree_pointcloud.h:236
pcl::octree::OctreePointCloud::genOctreeKeyForDataT
virtual bool genOctreeKeyForDataT(const int &data_arg, OctreeKey &key_arg) const
Virtual method for generating octree key for a given point index.
Definition: octree_pointcloud.hpp:836
pcl::octree::OctreePointCloud::getOccupiedVoxelCentersRecursive
int getOccupiedVoxelCentersRecursive(const BranchNode *node_arg, const OctreeKey &key_arg, AlignedPointTVector &voxel_center_list_arg) const
Recursively search the tree for all leaf nodes and return a vector of voxel centers.
Definition: octree_pointcloud.hpp:967
pcl::octree::OctreePointCloud::addPointsFromInputCloud
void addPointsFromInputCloud()
Add points from input point cloud to octree.
Definition: octree_pointcloud.hpp:78
pcl::octree::OctreePointCloud::getApproxIntersectedVoxelCentersBySegment
int getApproxIntersectedVoxelCentersBySegment(const Eigen::Vector3f &origin, const Eigen::Vector3f &end, AlignedPointTVector &voxel_center_list, float precision=0.2)
Get a PointT vector of centers of voxels intersected by a line segment.
Definition: octree_pointcloud.hpp:269
pcl::octree::OctreePointCloud::findLeafAtPoint
LeafContainerT * findLeafAtPoint(const PointT &point_arg) const
Find octree leaf node at a given point.
Definition: octree_pointcloud.h:458
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::octree_depth_
unsigned int octree_depth_
Octree depth.
Definition: octree_base.h:90
pcl::octree::OctreeKey
Octree key class
Definition: octree_key.h:52
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
pcl::octree::OctreePointCloud::adoptBoundingBoxToPoint
void adoptBoundingBoxToPoint(const PointT &point_idx_arg)
Grow the bounding box/octree until point fits.
Definition: octree_pointcloud.hpp:511
pcl::octree::OctreePointCloud::addPointToCloud
void addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg)
Add point simultaneously to octree and input point cloud.
Definition: octree_pointcloud.hpp:121
pcl::octree::OctreePointCloud::defineBoundingBox
void defineBoundingBox()
Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.
Definition: octree_pointcloud.hpp:332
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:628
pcl::octree::OctreePointCloud::addPointIdx
virtual void addPointIdx(const int point_idx_arg)
Add point at index from input pointcloud dataset to octree.
Definition: octree_pointcloud.hpp:654
pcl::octree::OctreePointCloud::min_y_
double min_y_
Definition: octree_pointcloud.h:587
pcl::octree::OctreePointCloud::getPointByIndex
const PointT & getPointByIndex(const unsigned int index_arg) const
Get point at index from input pointcloud dataset.
Definition: octree_pointcloud.hpp:702
pcl::octree::OctreeLeafNode
Abstract octree leaf class
Definition: octree_nodes.h:80
pcl::octree::OctreePointCloud::setInputCloud
void setInputCloud(const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr())
Provide a pointer to the input data set.
Definition: octree_pointcloud.h:117
pcl::octree::OctreePointCloud::bounding_box_defined_
bool bounding_box_defined_
Flag indicating if octree has defined bounding box.
Definition: octree_pointcloud.h:594
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::ConstPtr
shared_ptr< const OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > > > ConstPtr
Definition: octree_pointcloud.h:104
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::end
const Iterator end()
Definition: octree_base.h:118
pcl::octree::OctreePointCloud::getIndices
const IndicesConstPtr getIndices() const
Get a pointer to the vector of indices used.
Definition: octree_pointcloud.h:128
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::IndicesConstPtr
shared_ptr< const std::vector< int > > IndicesConstPtr
Definition: octree_pointcloud.h:86
pcl::octree::OctreePointCloud::setEpsilon
void setEpsilon(double eps)
Set the search epsilon precision (error bound) for nearest neighbors searches.
Definition: octree_pointcloud.h:147
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::findLeaf
OctreeContainerPointIndices * findLeaf(unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg)
Find leaf node at (idx_x_arg, idx_y_arg, idx_z_arg).
Definition: octree_base.hpp:105
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::LeafNode
OctreeLeafNode< OctreeContainerPointIndices > LeafNode
Definition: octree_base.h:67
pcl::octree::OctreeBranchNode
Abstract octree branch class
Definition: octree_nodes.h:179
pcl::octree::OctreePointCloud::getEpsilon
double getEpsilon() const
Get the search epsilon precision (error bound) for nearest neighbors searches.
Definition: octree_pointcloud.h:155
pcl::octree::OctreeIteratorBase
Abstract octree iterator class
Definition: octree_iterator.h:71
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::dynamic_depth_enabled_
bool dynamic_depth_enabled_
Enable dynamic_depth.
Definition: octree_base.h:93
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::BranchNode
OctreeBranchNode< OctreeContainerEmpty > BranchNode
Definition: octree_base.h:66
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::PointCloudPtr
typename PointCloud::Ptr PointCloudPtr
Definition: octree_pointcloud.h:89
pcl::octree::OctreePointCloud::min_z_
double min_z_
Definition: octree_pointcloud.h:590
pcl::octree::OctreePointCloud::max_x_
double max_x_
Definition: octree_pointcloud.h:585
pcl::octree::OctreePointCloud::BranchNode
typename OctreeT::BranchNode BranchNode
Definition: octree_pointcloud.h:77
pcl::octree::OctreePointCloud::getVoxelSquaredSideLen
double getVoxelSquaredSideLen() const
Calculates the squared voxel cube side length at leaf level.
Definition: octree_pointcloud.h:390
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::Ptr
shared_ptr< OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > > > Ptr
Definition: octree_pointcloud.h:102
pcl::octree::OctreePointCloud::isVoxelOccupiedAtPoint
bool isVoxelOccupiedAtPoint(const PointT &point_arg) const
Check if voxel at given point exist.
Definition: octree_pointcloud.hpp:156
pcl::octree::OctreePointCloud::addPointFromCloud
void addPointFromCloud(const int point_idx_arg, IndicesPtr indices_arg)
Add point at given index from input point cloud to octree.
Definition: octree_pointcloud.hpp:107
pcl::octree::OctreePointCloud::max_z_
double max_z_
Definition: octree_pointcloud.h:591
pcl::octree::OctreePointCloud::epsilon_
double epsilon_
Epsilon precision (error bound) for nearest neighbors searches.
Definition: octree_pointcloud.h:578
pcl::octree::OctreePointCloud::max_y_
double max_y_
Definition: octree_pointcloud.h:588
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:406
pcl::octree::OctreePointCloud::indices_
IndicesConstPtr indices_
A pointer to the vector of point indices to use.
Definition: octree_pointcloud.h:575
pcl::octree::OctreePointCloud::genVoxelBoundsFromOctreeKey
void genVoxelBoundsFromOctreeKey(const OctreeKey &key_arg, unsigned int tree_depth_arg, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const
Generate bounds of an octree voxel using octree key and tree depth arguments.
Definition: octree_pointcloud.hpp:900
pcl::octree::OctreePointCloud::genLeafNodeCenterFromOctreeKey
void genLeafNodeCenterFromOctreeKey(const OctreeKey &key_arg, PointT &point_arg) const
Generate a point at center of leaf node voxel.
Definition: octree_pointcloud.hpp:853
pcl::octree::OctreePointCloud::setResolution
void setResolution(double resolution_arg)
Set/change the octree voxel resolution.
Definition: octree_pointcloud.h:164
pcl::octree::OctreePointCloud::getTreeDepth
unsigned int getTreeDepth() const
Get the maximum depth of the octree.
Definition: octree_pointcloud.h:187
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:407
pcl::octree::OctreePointCloud::getBoundingBox
void getBoundingBox(double &min_x_arg, double &min_y_arg, double &min_z_arg, double &max_x_arg, double &max_y_arg, double &max_z_arg) const
Get bounding box for octree.
Definition: octree_pointcloud.hpp:488
pcl::octree::OctreeIteratorBase::getCurrentOctreeDepth
unsigned int getCurrentOctreeDepth() const
Get the current depth level of octree.
Definition: octree_iterator.h:173
pcl::octree::OctreePointCloud::getResolution
double getResolution() const
Get octree voxel resolution.
Definition: octree_pointcloud.h:178
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::IndicesPtr
shared_ptr< std::vector< int > > IndicesPtr
Definition: octree_pointcloud.h:85
pcl::octree::OctreePointCloud::getInputCloud
PointCloudConstPtr getInputCloud() const
Get a pointer to the input point cloud dataset.
Definition: octree_pointcloud.h:137
pcl::octree::OctreePointCloud::getVoxelBounds
void getVoxelBounds(const OctreeIteratorBase< OctreeT > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const
Generate bounds of the current voxel of an octree iterator.
Definition: octree_pointcloud.h:401
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::AlignedPointXYZVector
std::vector< PointXYZ, Eigen::aligned_allocator< PointXYZ > > AlignedPointXYZVector
Definition: octree_pointcloud.h:109
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::leaf_count_
std::size_t leaf_count_
Amount of leaf nodes
Definition: octree_base.h:78
pcl::octree::OctreePointCloud::enableDynamicDepth
void enableDynamicDepth(std::size_t maxObjsPerLeaf)
Enable dynamic octree structure.
Definition: octree_pointcloud.h:417
pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::AlignedPointTVector
std::vector< PointT, Eigen::aligned_allocator< PointT > > AlignedPointTVector
Definition: octree_pointcloud.h:107
pcl::octree::OctreePointCloud::expandLeafNode
void expandLeafNode(LeafNode *leaf_node, BranchNode *parent_branch, unsigned char child_idx, unsigned int depth_mask)
Add point at index from input pointcloud dataset to octree.
Definition: octree_pointcloud.hpp:604
pcl::octree::OctreePointCloud::OctreePointCloud
OctreePointCloud(const double resolution_arg)
Octree pointcloud constructor.
Definition: octree_pointcloud.hpp:53
pcl::octree::OctreePointCloud::input_
PointCloudConstPtr input_
Pointer to input point cloud dataset.
Definition: octree_pointcloud.h:572
pcl::octree::OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty >::OctreeT
OctreeBase< OctreeContainerPointIndices, OctreeContainerEmpty > OctreeT
Definition: octree_base.h:64
pcl::octree::OctreePointCloud::LeafNode
typename OctreeT::LeafNode LeafNode
Definition: octree_pointcloud.h:76
pcl::octree::OctreePointCloud::genVoxelCenterFromOctreeKey
void genVoxelCenterFromOctreeKey(const OctreeKey &key_arg, unsigned int tree_depth_arg, PointT &point_arg) const
Generate a point at center of octree voxel at given tree level.
Definition: octree_pointcloud.hpp:871
pcl::octree::OctreeIteratorBase::getCurrentOctreeKey
const OctreeKey & getCurrentOctreeKey() const
Get octree key for the current iterator octree node.
Definition: octree_iterator.h:161
pcl::octree::OctreePointCloud::min_x_
double min_x_
Definition: octree_pointcloud.h:584