42#include <pcl/common/point_tests.h>
43#include <pcl/octree/impl/octree_base.hpp>
49template <
typename PointT,
50 typename LeafContainerT,
51 typename BranchContainerT,
63 if (resolution <= 0.0) {
65 "[pcl::octree::OctreePointCloud::OctreePointCloud] Resolution "
66 << resolution <<
" must be > 0!");
71template <
typename PointT,
72 typename LeafContainerT,
73 typename BranchContainerT,
80 for (
const auto& index : *
indices_) {
81 assert((index >= 0) && (
static_cast<std::size_t
>(index) <
input_->size()));
90 for (
index_t i = 0; i < static_cast<index_t>(input_->size()); i++) {
100template <
typename PointT,
101 typename LeafContainerT,
102 typename BranchContainerT,
110 indices_arg->push_back(point_idx_arg);
114template <
typename PointT,
115 typename LeafContainerT,
116 typename BranchContainerT,
122 assert(cloud_arg ==
input_);
124 cloud_arg->push_back(point_arg);
130template <
typename PointT,
131 typename LeafContainerT,
132 typename BranchContainerT,
140 assert(cloud_arg ==
input_);
143 cloud_arg->push_back(point_arg);
149template <
typename PointT,
150 typename LeafContainerT,
151 typename BranchContainerT,
171template <
typename PointT,
172 typename LeafContainerT,
173 typename BranchContainerT,
180 const PointT& point = (*this->
input_)[point_idx_arg];
187template <
typename PointT,
188 typename LeafContainerT,
189 typename BranchContainerT,
194 const double point_y_arg,
195 const double point_z_arg)
const
199 point.x = point_x_arg;
200 point.y = point_y_arg;
201 point.z = point_z_arg;
208template <
typename PointT,
209 typename LeafContainerT,
210 typename BranchContainerT,
229template <
typename PointT,
230 typename LeafContainerT,
231 typename BranchContainerT,
238 const PointT& point = (*this->
input_)[point_idx_arg];
245template <
typename PointT,
246 typename LeafContainerT,
247 typename BranchContainerT,
254 key.
x = key.
y = key.
z = 0;
256 voxel_center_list_arg.clear();
262template <
typename PointT,
263 typename LeafContainerT,
264 typename BranchContainerT,
269 const Eigen::Vector3f&
end,
273 Eigen::Vector3f direction =
end - origin;
274 float norm = direction.norm();
275 direction.normalize();
277 const float step_size =
static_cast<float>(
resolution_) * precision;
279 const auto nsteps = std::max<std::size_t>(1, norm / step_size);
283 bool bkeyDefined =
false;
286 for (std::size_t i = 0; i < nsteps; ++i) {
287 Eigen::Vector3f p = origin + (direction * step_size *
static_cast<float>(i));
298 if ((key == prev_key) && (bkeyDefined))
306 voxel_center_list.push_back(center);
315 if (!(end_key == prev_key)) {
318 voxel_center_list.push_back(center);
321 return (
static_cast<uindex_t>(voxel_center_list.size()));
325template <
typename PointT,
326 typename LeafContainerT,
327 typename BranchContainerT,
334 double minX, minY, minZ, maxX, maxY, maxZ;
341 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
349 float minValue = std::numeric_limits<float>::epsilon() * 512.0f;
355 maxX = max_pt.x + minValue;
356 maxY = max_pt.y + minValue;
357 maxZ = max_pt.z + minValue;
364template <
typename PointT,
365 typename LeafContainerT,
366 typename BranchContainerT,
371 const double min_y_arg,
372 const double min_z_arg,
373 const double max_x_arg,
374 const double max_y_arg,
375 const double max_z_arg)
379 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
385 min_x_ = std::min(min_x_arg, max_x_arg);
386 min_y_ = std::min(min_y_arg, max_y_arg);
387 min_z_ = std::min(min_z_arg, max_z_arg);
389 max_x_ = std::max(min_x_arg, max_x_arg);
390 max_y_ = std::max(min_y_arg, max_y_arg);
391 max_z_ = std::max(min_z_arg, max_z_arg);
400template <
typename PointT,
401 typename LeafContainerT,
402 typename BranchContainerT,
407 const double max_y_arg,
408 const double max_z_arg)
412 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
418 min_x_ = std::min(0.0, max_x_arg);
419 min_y_ = std::min(0.0, max_y_arg);
420 min_z_ = std::min(0.0, max_z_arg);
422 max_x_ = std::max(0.0, max_x_arg);
423 max_y_ = std::max(0.0, max_y_arg);
424 max_z_ = std::max(0.0, max_z_arg);
433template <
typename PointT,
434 typename LeafContainerT,
435 typename BranchContainerT,
443 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
449 min_x_ = std::min(0.0, cubeLen_arg);
450 min_y_ = std::min(0.0, cubeLen_arg);
451 min_z_ = std::min(0.0, cubeLen_arg);
453 max_x_ = std::max(0.0, cubeLen_arg);
454 max_y_ = std::max(0.0, cubeLen_arg);
455 max_z_ = std::max(0.0, cubeLen_arg);
464template <
typename PointT,
465 typename LeafContainerT,
466 typename BranchContainerT,
475 double& max_z_arg)
const
487template <
typename PointT,
488 typename LeafContainerT,
489 typename BranchContainerT,
496 constexpr float minValue = std::numeric_limits<float>::epsilon();
500 bool bLowerBoundViolationX = (point_arg.x <
min_x_);
501 bool bLowerBoundViolationY = (point_arg.y <
min_y_);
502 bool bLowerBoundViolationZ = (point_arg.z <
min_z_);
504 bool bUpperBoundViolationX = (point_arg.x >=
max_x_);
505 bool bUpperBoundViolationY = (point_arg.y >=
max_y_);
506 bool bUpperBoundViolationZ = (point_arg.z >=
max_z_);
509 if (bLowerBoundViolationX || bLowerBoundViolationY || bLowerBoundViolationZ ||
510 bUpperBoundViolationX || bUpperBoundViolationY || bUpperBoundViolationZ ||
515 double octreeSideLen;
516 unsigned char child_idx;
520 child_idx =
static_cast<unsigned char>(((bLowerBoundViolationX) << 2) |
521 ((bLowerBoundViolationY) << 1) |
522 ((bLowerBoundViolationZ)));
535 if (bLowerBoundViolationX)
538 if (bLowerBoundViolationY)
541 if (bLowerBoundViolationZ)
580template <
typename PointT,
581 typename LeafContainerT,
582 typename BranchContainerT,
588 unsigned char child_idx,
594 std::size_t leaf_obj_count = (*leaf_node)->getSize();
598 leafIndices.reserve(leaf_obj_count);
600 (*leaf_node)->getPointIndices(leafIndices);
613 for (
const auto& leafIndex : leafIndices) {
615 const PointT& point_from_index = (*input_)[leafIndex];
622 new_index_key, depth_mask, childBranch, newLeaf, newBranchParent);
624 (*newLeaf)->addPointIndex(leafIndex);
630template <
typename PointT,
631 typename LeafContainerT,
632 typename BranchContainerT,
640 assert(point_idx_arg < input_->size());
642 const PointT& point = (*input_)[point_idx_arg];
657 std::size_t leaf_obj_count = (*leaf_node)->getSize();
663 expandLeafNode(leaf_node, parent_branch_of_leaf_node, child_idx, depth_mask);
669 parent_branch_of_leaf_node);
670 leaf_obj_count = (*leaf_node)->getSize();
674 (*leaf_node)->addPointIndex(point_idx_arg);
678template <
typename PointT,
679 typename LeafContainerT,
680 typename BranchContainerT,
687 assert(index_arg < input_->size());
688 return ((*this->
input_)[index_arg]);
692template <
typename PointT,
693 typename LeafContainerT,
694 typename BranchContainerT,
700 constexpr float minValue = std::numeric_limits<float>::epsilon();
703 const auto max_key_x =
705 const auto max_key_y =
707 const auto max_key_z =
711 const auto max_voxels =
712 std::max<uindex_t>(std::max(std::max(max_key_x, max_key_y), max_key_z), 2);
717 std::ceil(std::log2(max_voxels) - minValue)),
720 const auto octree_side_len =
724 double octree_oversize_x;
725 double octree_oversize_y;
726 double octree_oversize_z;
728 octree_oversize_x = (octree_side_len - (
max_x_ -
min_x_)) / 2.0;
729 octree_oversize_y = (octree_side_len - (
max_y_ -
min_y_)) / 2.0;
730 octree_oversize_z = (octree_side_len - (
max_z_ -
min_z_)) / 2.0;
732 assert(octree_oversize_x > -minValue);
733 assert(octree_oversize_y > -minValue);
734 assert(octree_oversize_z > -minValue);
736 if (octree_oversize_x > minValue) {
737 min_x_ -= octree_oversize_x;
738 max_x_ += octree_oversize_x;
740 if (octree_oversize_y > minValue) {
741 min_y_ -= octree_oversize_y;
742 max_y_ += octree_oversize_y;
744 if (octree_oversize_z > minValue) {
745 min_z_ -= octree_oversize_z;
746 max_z_ += octree_oversize_z;
760template <
typename PointT,
761 typename LeafContainerT,
762 typename BranchContainerT,
773 assert(key_arg.
x <= this->max_key_.x);
774 assert(key_arg.
y <= this->max_key_.y);
775 assert(key_arg.
z <= this->max_key_.z);
779template <
typename PointT,
780 typename LeafContainerT,
781 typename BranchContainerT,
786 const double point_y_arg,
787 const double point_z_arg,
792 temp_point.x =
static_cast<float>(point_x_arg);
793 temp_point.y =
static_cast<float>(point_y_arg);
794 temp_point.z =
static_cast<float>(point_z_arg);
801template <
typename PointT,
802 typename LeafContainerT,
803 typename BranchContainerT,
818template <
typename PointT,
819 typename LeafContainerT,
820 typename BranchContainerT,
827 point.x =
static_cast<float>((
static_cast<double>(key.
x) + 0.5f) * this->
resolution_ +
829 point.y =
static_cast<float>((
static_cast<double>(key.
y) + 0.5f) * this->
resolution_ +
831 point.z =
static_cast<float>((
static_cast<double>(key.
z) + 0.5f) * this->
resolution_ +
836template <
typename PointT,
837 typename LeafContainerT,
838 typename BranchContainerT,
844 PointT& point_arg)
const
847 point_arg.x =
static_cast<float>(
848 (
static_cast<double>(key_arg.
x) + 0.5f) *
850 static_cast<double>(1 << (this->
octree_depth_ - tree_depth_arg))) +
852 point_arg.y =
static_cast<float>(
853 (
static_cast<double>(key_arg.
y) + 0.5f) *
855 static_cast<double>(1 << (this->
octree_depth_ - tree_depth_arg))) +
857 point_arg.z =
static_cast<float>(
858 (
static_cast<double>(key_arg.
z) + 0.5f) *
860 static_cast<double>(1 << (this->
octree_depth_ - tree_depth_arg))) +
865template <
typename PointT,
866 typename LeafContainerT,
867 typename BranchContainerT,
873 Eigen::Vector3f& min_pt,
874 Eigen::Vector3f& max_pt)
const
877 double voxel_side_len =
879 static_cast<double>(1 << (this->
octree_depth_ - tree_depth_arg));
882 min_pt(0) =
static_cast<float>(
static_cast<double>(key_arg.
x) * voxel_side_len +
884 min_pt(1) =
static_cast<float>(
static_cast<double>(key_arg.
y) * voxel_side_len +
886 min_pt(2) =
static_cast<float>(
static_cast<double>(key_arg.
z) * voxel_side_len +
889 max_pt(0) = min_pt(0) + voxel_side_len;
890 max_pt(1) = min_pt(1) + voxel_side_len;
891 max_pt(2) = min_pt(2) + voxel_side_len;
895template <
typename PointT,
896 typename LeafContainerT,
897 typename BranchContainerT,
907 static_cast<double>(1 << (this->
octree_depth_ - tree_depth_arg));
910 side_len *= side_len;
916template <
typename PointT,
917 typename LeafContainerT,
918 typename BranchContainerT,
929template <
typename PointT,
930 typename LeafContainerT,
931 typename BranchContainerT,
942 for (
unsigned char child_idx = 0; child_idx < 8; child_idx++) {
951 new_key.
x = (key_arg.
x << 1) | (!!(child_idx & (1 << 2)));
952 new_key.
y = (key_arg.
y << 1) | (!!(child_idx & (1 << 1)));
953 new_key.
z = (key_arg.
z << 1) | (!!(child_idx & (1 << 0)));
959 static_cast<const BranchNode*
>(child_node), new_key, voxel_center_list_arg);
966 voxel_center_list_arg.push_back(new_point);
975 return (voxel_count);
978#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithLeafDataTVector(T) \
979 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
981 pcl::octree::OctreeContainerPointIndices, \
982 pcl::octree::OctreeContainerEmpty, \
983 pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndices, \
984 pcl::octree::OctreeContainerEmpty>>;
985#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithLeafDataTVector(T) \
986 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
988 pcl::octree::OctreeContainerPointIndices, \
989 pcl::octree::OctreeContainerEmpty, \
990 pcl::octree::Octree2BufBase<pcl::octree::OctreeContainerPointIndices, \
991 pcl::octree::OctreeContainerEmpty>>;
993#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithLeafDataT(T) \
994 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
996 pcl::octree::OctreeContainerPointIndex, \
997 pcl::octree::OctreeContainerEmpty, \
998 pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndex, \
999 pcl::octree::OctreeContainerEmpty>>;
1000#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithLeafDataT(T) \
1001 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1003 pcl::octree::OctreeContainerPointIndex, \
1004 pcl::octree::OctreeContainerEmpty, \
1005 pcl::octree::Octree2BufBase<pcl::octree::OctreeContainerPointIndex, \
1006 pcl::octree::OctreeContainerEmpty>>;
1008#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithEmptyLeaf(T) \
1009 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1011 pcl::octree::OctreeContainerEmpty, \
1012 pcl::octree::OctreeContainerEmpty, \
1013 pcl::octree::OctreeBase<pcl::octree::OctreeContainerEmpty, \
1014 pcl::octree::OctreeContainerEmpty>>;
1015#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithEmptyLeaf(T) \
1016 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1018 pcl::octree::OctreeContainerEmpty, \
1019 pcl::octree::OctreeContainerEmpty, \
1020 pcl::octree::Octree2BufBase<pcl::octree::OctreeContainerEmpty, \
1021 pcl::octree::OctreeContainerEmpty>>;
An exception thrown when init can not be performed should be used in all the PCLBase class inheritant...
void setTreeDepth(uindex_t depth_arg)
Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > OctreeT
void setBranchChildPtr(BranchNode &branch_arg, unsigned char child_idx_arg, OctreeNode *new_child_arg)
std::size_t branch_count_
void removeLeaf(uindex_t idx_x_arg, uindex_t idx_y_arg, uindex_t idx_z_arg)
void setTreeDepth(uindex_t max_depth_arg)
Set the maximum depth of the octree.
std::size_t leaf_count_
Amount of leaf nodes.
BranchNode * root_node_
Pointer to root branch node of octree.
uindex_t depth_mask_
Depth mask based on octree depth.
bool branchHasChild(const BranchNode &branch_arg, unsigned char child_idx_arg) const
Check if branch is pointing to a particular child node.
std::size_t branch_count_
Amount of branch nodes.
bool dynamic_depth_enabled_
Enable dynamic_depth.
uindex_t createLeafRecursive(const OctreeKey &key_arg, uindex_t depth_mask_arg, BranchNode *branch_arg, LeafNode *&return_leaf_arg, BranchNode *&parent_of_leaf_arg)
Create a leaf node at octree key.
BranchNode * createBranchChild(BranchNode &branch_arg, unsigned char child_idx_arg)
Create and add a new branch child to a branch class.
OctreeBase< LeafContainerT, BranchContainerT > OctreeT
uindex_t octree_depth_
Octree depth.
bool existLeaf(uindex_t idx_x_arg, uindex_t idx_y_arg, uindex_t idx_z_arg) const
idx_x_arg for the existence of leaf node at (idx_x_arg, idx_y_arg, idx_z_arg).
OctreeNode * getBranchChildPtr(const BranchNode &branch_arg, unsigned char child_idx_arg) const
Retrieve a child node pointer for child node at child_idx.
void deleteBranchChild(BranchNode &branch_arg, unsigned char child_idx_arg)
Delete child node and all its subchilds from octree.
static const unsigned char maxDepth
unsigned char getChildIdxWithDepthMask(uindex_t depthMask) const
get child node index using depthMask
Abstract octree node class
virtual node_type_t getNodeType() const =0
Pure virtual method for retrieving the type of octree node (branch or leaf)
double getVoxelSquaredDiameter() const
Calculates the squared diameter of a voxel at leaf depth.
std::vector< PointT, Eigen::aligned_allocator< PointT > > AlignedPointTVector
bool isPointWithinBoundingBox(const PointT &point_idx_arg) const
Checks if given point is within the bounding box of the octree.
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.
const PointT & getPointByIndex(uindex_t index_arg) const
Get point at index from input pointcloud dataset.
void addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg)
Add point simultaneously to octree and input point cloud.
virtual bool genOctreeKeyForDataT(const index_t &data_arg, OctreeKey &key_arg) const
Virtual method for generating octree key for a given point index.
std::size_t max_objs_per_leaf_
Amount of DataT objects per leafNode before expanding branch.
void addPointsFromInputCloud()
Add points from input point cloud to octree.
PointCloudConstPtr input_
Pointer to input point cloud dataset.
void genLeafNodeCenterFromOctreeKey(const OctreeKey &key_arg, PointT &point_arg) const
void genOctreeKeyforPoint(const PointT &point_arg, OctreeKey &key_arg) const
Generate octree key for voxel at a given point.
typename PointCloud::Ptr PointCloudPtr
IndicesConstPtr indices_
A pointer to the vector of point indices to use.
shared_ptr< Indices > IndicesPtr
typename PointCloud::ConstPtr PointCloudConstPtr
void genVoxelCenterFromOctreeKey(const OctreeKey &key_arg, uindex_t tree_depth_arg, PointT &point_arg) const
Generate a point at center of octree voxel at given tree level.
uindex_t 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.
OctreePointCloud(const double resolution_arg)
Octree pointcloud constructor.
double getVoxelSquaredSideLen(uindex_t tree_depth_arg) const
Calculates the squared voxel cube side length at given tree depth.
void adoptBoundingBoxToPoint(const PointT &point_idx_arg)
Grow the bounding box/octree until point fits.
bool bounding_box_defined_
uindex_t getOccupiedVoxelCenters(AlignedPointTVector &voxel_center_list_arg) const
Get a PointT vector of centers of all occupied voxels.
void addPointFromCloud(uindex_t point_idx_arg, IndicesPtr indices_arg)
Add point at given index from input point cloud to octree.
typename OctreeT::LeafNode LeafNode
double getVoxelSquaredSideLen() const
Calculates the squared voxel cube side length at leaf level.
void defineBoundingBox()
Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.
bool isVoxelOccupiedAtPoint(const PointT &point_arg) const
Check if voxel at given point exist.
void deleteVoxelAtPoint(const PointT &point_arg)
Delete leaf node / voxel at given point.
typename Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty >::BranchNode BranchNode
void genVoxelBoundsFromOctreeKey(const OctreeKey &key_arg, uindex_t 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.
shared_ptr< const Indices > IndicesConstPtr
void expandLeafNode(LeafNode *leaf_node, BranchNode *parent_branch, unsigned char child_idx, uindex_t depth_mask)
Add point at index from input pointcloud dataset to octree.
uindex_t 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.
double resolution_
Octree resolution.
virtual void addPointIdx(uindex_t point_idx_arg)
Define standard C methods and C++ classes that are common to all methods.
void getMinMax3D(const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
bool isFinite(const PointT &pt)
Tests if the 3D components of a point are all finite param[in] pt point to be tested return true if f...
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
IndicesAllocator<> Indices
Type used for indices in PCL.
detail::int_type_t< detail::index_type_size, false > uindex_t
Type used for an unsigned index in PCL.
Defines basic non-point types used by PCL.