42#include <pcl/common/point_tests.h>
43#include <pcl/octree/impl/octree_base.hpp>
50 typename LeafContainerT,
51 typename BranchContainerT,
59, resolution_(resolution)
66, bounding_box_defined_(false)
67, max_objs_per_leaf_(0)
69 if (resolution <= 0.0) {
71 "[pcl::octree::OctreePointCloud::OctreePointCloud] Resolution "
72 << resolution <<
" must be > 0!");
78 typename LeafContainerT,
79 typename BranchContainerT,
86 for (
const auto& index : *indices_) {
87 assert((index >= 0) && (
static_cast<std::size_t
>(index) < input_->size()));
91 this->addPointIdx(index);
96 for (
index_t i = 0; i < static_cast<index_t>(input_->size()); i++) {
107 typename LeafContainerT,
108 typename BranchContainerT,
114 this->addPointIdx(point_idx_arg);
116 indices_arg->push_back(point_idx_arg);
121 typename LeafContainerT,
122 typename BranchContainerT,
128 assert(cloud_arg == input_);
130 cloud_arg->push_back(point_arg);
132 this->addPointIdx(cloud_arg->size() - 1);
137 typename LeafContainerT,
138 typename BranchContainerT,
146 assert(cloud_arg == input_);
147 assert(indices_arg == indices_);
149 cloud_arg->push_back(point_arg);
151 this->addPointFromCloud(cloud_arg->size() - 1, indices_arg);
156 typename LeafContainerT,
157 typename BranchContainerT,
163 if (!isPointWithinBoundingBox(point_arg)) {
170 this->genOctreeKeyforPoint(point_arg, key);
173 return (this->existLeaf(key));
178 typename LeafContainerT,
179 typename BranchContainerT,
186 const PointT& point = (*this->input_)[point_idx_arg];
189 return (this->isVoxelOccupiedAtPoint(point));
194 typename LeafContainerT,
195 typename BranchContainerT,
200 const double point_y_arg,
201 const double point_z_arg)
const
205 point.x = point_x_arg;
206 point.y = point_y_arg;
207 point.z = point_z_arg;
210 return (this->isVoxelOccupiedAtPoint(point));
215 typename LeafContainerT,
216 typename BranchContainerT,
222 if (!isPointWithinBoundingBox(point_arg)) {
229 this->genOctreeKeyforPoint(point_arg, key);
231 this->removeLeaf(key);
236 typename LeafContainerT,
237 typename BranchContainerT,
244 const PointT& point = (*this->input_)[point_idx_arg];
247 this->deleteVoxelAtPoint(point);
252 typename LeafContainerT,
253 typename BranchContainerT,
260 key.
x = key.
y = key.
z = 0;
262 voxel_center_list_arg.clear();
264 return getOccupiedVoxelCentersRecursive(this->root_node_, key, voxel_center_list_arg);
269 typename LeafContainerT,
270 typename BranchContainerT,
275 const Eigen::Vector3f& end,
279 Eigen::Vector3f direction = end - origin;
280 float norm = direction.norm();
281 direction.normalize();
283 const float step_size =
static_cast<float>(resolution_) * precision;
285 const auto nsteps = std::max<std::size_t>(1, norm / step_size);
289 bool bkeyDefined =
false;
292 for (std::size_t i = 0; i < nsteps; ++i) {
293 Eigen::Vector3f p = origin + (direction * step_size *
static_cast<float>(i));
301 this->genOctreeKeyforPoint(octree_p, key);
304 if ((key == prev_key) && (bkeyDefined))
311 genLeafNodeCenterFromOctreeKey(key, center);
312 voxel_center_list.push_back(center);
320 this->genOctreeKeyforPoint(end_p, end_key);
321 if (!(end_key == prev_key)) {
323 genLeafNodeCenterFromOctreeKey(end_key, center);
324 voxel_center_list.push_back(center);
327 return (
static_cast<uindex_t>(voxel_center_list.size()));
332 typename LeafContainerT,
333 typename BranchContainerT,
340 double minX, minY, minZ, maxX, maxY, maxZ;
346 if (this->leaf_count_ != 0) {
347 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
355 float minValue = std::numeric_limits<float>::epsilon() * 512.0f;
361 maxX = max_pt.x + minValue;
362 maxY = max_pt.y + minValue;
363 maxZ = max_pt.z + minValue;
366 defineBoundingBox(minX, minY, minZ, maxX, maxY, maxZ);
371 typename LeafContainerT,
372 typename BranchContainerT,
377 const double min_y_arg,
378 const double min_z_arg,
379 const double max_x_arg,
380 const double max_y_arg,
381 const double max_z_arg)
384 if (this->leaf_count_ != 0) {
385 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
391 min_x_ = std::min(min_x_arg, max_x_arg);
392 min_y_ = std::min(min_y_arg, max_y_arg);
393 min_z_ = std::min(min_z_arg, max_z_arg);
395 max_x_ = std::max(min_x_arg, max_x_arg);
396 max_y_ = std::max(min_y_arg, max_y_arg);
397 max_z_ = std::max(min_z_arg, max_z_arg);
402 bounding_box_defined_ =
true;
407 typename LeafContainerT,
408 typename BranchContainerT,
413 const double max_y_arg,
414 const double max_z_arg)
417 if (this->leaf_count_ != 0) {
418 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
424 min_x_ = std::min(0.0, max_x_arg);
425 min_y_ = std::min(0.0, max_y_arg);
426 min_z_ = std::min(0.0, max_z_arg);
428 max_x_ = std::max(0.0, max_x_arg);
429 max_y_ = std::max(0.0, max_y_arg);
430 max_z_ = std::max(0.0, max_z_arg);
435 bounding_box_defined_ =
true;
440 typename LeafContainerT,
441 typename BranchContainerT,
448 if (this->leaf_count_ != 0) {
449 PCL_ERROR(
"[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
455 min_x_ = std::min(0.0, cubeLen_arg);
456 min_y_ = std::min(0.0, cubeLen_arg);
457 min_z_ = std::min(0.0, cubeLen_arg);
459 max_x_ = std::max(0.0, cubeLen_arg);
460 max_y_ = std::max(0.0, cubeLen_arg);
461 max_z_ = std::max(0.0, cubeLen_arg);
466 bounding_box_defined_ =
true;
471 typename LeafContainerT,
472 typename BranchContainerT,
481 double& max_z_arg)
const
494 typename LeafContainerT,
495 typename BranchContainerT,
502 constexpr float minValue = std::numeric_limits<float>::epsilon();
506 bool bLowerBoundViolationX = (point_arg.x < min_x_);
507 bool bLowerBoundViolationY = (point_arg.y < min_y_);
508 bool bLowerBoundViolationZ = (point_arg.z < min_z_);
510 bool bUpperBoundViolationX = (point_arg.x >= max_x_);
511 bool bUpperBoundViolationY = (point_arg.y >= max_y_);
512 bool bUpperBoundViolationZ = (point_arg.z >= max_z_);
515 if (bLowerBoundViolationX || bLowerBoundViolationY || bLowerBoundViolationZ ||
516 bUpperBoundViolationX || bUpperBoundViolationY || bUpperBoundViolationZ ||
517 (!bounding_box_defined_)) {
519 if (bounding_box_defined_) {
521 double octreeSideLen;
522 unsigned char child_idx;
526 child_idx =
static_cast<unsigned char>(((!bUpperBoundViolationX) << 2) |
527 ((!bUpperBoundViolationY) << 1) |
528 ((!bUpperBoundViolationZ)));
533 this->branch_count_++;
535 this->setBranchChildPtr(*newRootBranch, child_idx, this->root_node_);
537 this->root_node_ = newRootBranch;
539 octreeSideLen =
static_cast<double>(1 << this->octree_depth_) * resolution_;
541 if (!bUpperBoundViolationX)
542 min_x_ -= octreeSideLen;
544 if (!bUpperBoundViolationY)
545 min_y_ -= octreeSideLen;
547 if (!bUpperBoundViolationZ)
548 min_z_ -= octreeSideLen;
551 this->octree_depth_++;
552 this->setTreeDepth(this->octree_depth_);
556 static_cast<double>(1 << this->octree_depth_) * resolution_ - minValue;
559 max_x_ = min_x_ + octreeSideLen;
560 max_y_ = min_y_ + octreeSideLen;
561 max_z_ = min_z_ + octreeSideLen;
566 this->min_x_ = point_arg.x - this->resolution_ / 2;
567 this->min_y_ = point_arg.y - this->resolution_ / 2;
568 this->min_z_ = point_arg.z - this->resolution_ / 2;
570 this->max_x_ = point_arg.x + this->resolution_ / 2;
571 this->max_y_ = point_arg.y + this->resolution_ / 2;
572 this->max_z_ = point_arg.z + this->resolution_ / 2;
576 bounding_box_defined_ =
true;
587 typename LeafContainerT,
588 typename BranchContainerT,
594 unsigned char child_idx,
600 std::size_t leaf_obj_count = (*leaf_node)->getSize();
604 leafIndices.reserve(leaf_obj_count);
606 (*leaf_node)->getPointIndices(leafIndices);
609 this->deleteBranchChild(*parent_branch, child_idx);
613 BranchNode* childBranch = this->createBranchChild(*parent_branch, child_idx);
614 this->branch_count_++;
619 for (
const auto& leafIndex : leafIndices) {
621 const PointT& point_from_index = (*input_)[leafIndex];
623 genOctreeKeyforPoint(point_from_index, new_index_key);
627 this->createLeafRecursive(
628 new_index_key, depth_mask, childBranch, newLeaf, newBranchParent);
630 (*newLeaf)->addPointIndex(leafIndex);
637 typename LeafContainerT,
638 typename BranchContainerT,
646 assert(point_idx_arg < input_->size());
648 const PointT& point = (*input_)[point_idx_arg];
651 adoptBoundingBoxToPoint(point);
654 genOctreeKeyforPoint(point, key);
658 auto depth_mask = this->createLeafRecursive(
659 key, this->depth_mask_, this->root_node_, leaf_node, parent_branch_of_leaf_node);
661 if (this->dynamic_depth_enabled_ && depth_mask) {
663 std::size_t leaf_obj_count = (*leaf_node)->getSize();
665 while (leaf_obj_count >= max_objs_per_leaf_ && depth_mask) {
669 expandLeafNode(leaf_node, parent_branch_of_leaf_node, child_idx, depth_mask);
671 depth_mask = this->createLeafRecursive(key,
675 parent_branch_of_leaf_node);
676 leaf_obj_count = (*leaf_node)->getSize();
680 (*leaf_node)->addPointIndex(point_idx_arg);
685 typename LeafContainerT,
686 typename BranchContainerT,
693 assert(index_arg < input_->size());
694 return ((*this->input_)[index_arg]);
699 typename LeafContainerT,
700 typename BranchContainerT,
706 constexpr float minValue = std::numeric_limits<float>::epsilon();
709 const auto max_key_x =
710 static_cast<uindex_t>(std::ceil((max_x_ - min_x_ - minValue) / resolution_));
711 const auto max_key_y =
712 static_cast<uindex_t>(std::ceil((max_y_ - min_y_ - minValue) / resolution_));
713 const auto max_key_z =
714 static_cast<uindex_t>(std::ceil((max_z_ - min_z_ - minValue) / resolution_));
717 const auto max_voxels =
718 std::max<uindex_t>(std::max(std::max(max_key_x, max_key_y), max_key_z), 2);
721 this->octree_depth_ = std::max<uindex_t>(
723 std::ceil(std::log2(max_voxels) - minValue)),
726 const auto octree_side_len =
727 static_cast<double>(1 << this->octree_depth_) * resolution_;
729 if (this->leaf_count_ == 0) {
730 double octree_oversize_x;
731 double octree_oversize_y;
732 double octree_oversize_z;
734 octree_oversize_x = (octree_side_len - (max_x_ - min_x_)) / 2.0;
735 octree_oversize_y = (octree_side_len - (max_y_ - min_y_)) / 2.0;
736 octree_oversize_z = (octree_side_len - (max_z_ - min_z_)) / 2.0;
738 assert(octree_oversize_x > -minValue);
739 assert(octree_oversize_y > -minValue);
740 assert(octree_oversize_z > -minValue);
742 if (octree_oversize_x > minValue) {
743 min_x_ -= octree_oversize_x;
744 max_x_ += octree_oversize_x;
746 if (octree_oversize_y > minValue) {
747 min_y_ -= octree_oversize_y;
748 max_y_ += octree_oversize_y;
750 if (octree_oversize_z > minValue) {
751 min_z_ -= octree_oversize_z;
752 max_z_ += octree_oversize_z;
756 max_x_ = min_x_ + octree_side_len;
757 max_y_ = min_y_ + octree_side_len;
758 max_z_ = min_z_ + octree_side_len;
762 this->setTreeDepth(this->octree_depth_);
767 typename LeafContainerT,
768 typename BranchContainerT,
775 key_arg.
x =
static_cast<uindex_t>((point_arg.x - this->min_x_) / this->resolution_);
776 key_arg.
y =
static_cast<uindex_t>((point_arg.y - this->min_y_) / this->resolution_);
777 key_arg.
z =
static_cast<uindex_t>((point_arg.z - this->min_z_) / this->resolution_);
779 assert(key_arg.
x <= this->max_key_.x);
780 assert(key_arg.
y <= this->max_key_.y);
781 assert(key_arg.
z <= this->max_key_.z);
786 typename LeafContainerT,
787 typename BranchContainerT,
792 const double point_y_arg,
793 const double point_z_arg,
798 temp_point.x =
static_cast<float>(point_x_arg);
799 temp_point.y =
static_cast<float>(point_y_arg);
800 temp_point.z =
static_cast<float>(point_z_arg);
803 genOctreeKeyforPoint(temp_point, key_arg);
808 typename LeafContainerT,
809 typename BranchContainerT,
815 const PointT temp_point = getPointByIndex(data_arg);
818 genOctreeKeyforPoint(temp_point, key_arg);
825 typename LeafContainerT,
826 typename BranchContainerT,
833 point.x =
static_cast<float>((
static_cast<double>(key.
x) + 0.5f) * this->resolution_ +
835 point.y =
static_cast<float>((
static_cast<double>(key.
y) + 0.5f) * this->resolution_ +
837 point.z =
static_cast<float>((
static_cast<double>(key.
z) + 0.5f) * this->resolution_ +
843 typename LeafContainerT,
844 typename BranchContainerT,
853 point_arg.x =
static_cast<float>(
854 (
static_cast<double>(key_arg.
x) + 0.5f) *
856 static_cast<double>(1 << (this->octree_depth_ - tree_depth_arg))) +
858 point_arg.y =
static_cast<float>(
859 (
static_cast<double>(key_arg.
y) + 0.5f) *
861 static_cast<double>(1 << (this->octree_depth_ - tree_depth_arg))) +
863 point_arg.z =
static_cast<float>(
864 (
static_cast<double>(key_arg.
z) + 0.5f) *
866 static_cast<double>(1 << (this->octree_depth_ - tree_depth_arg))) +
872 typename LeafContainerT,
873 typename BranchContainerT,
879 Eigen::Vector3f& min_pt,
880 Eigen::Vector3f& max_pt)
const
883 double voxel_side_len =
885 static_cast<double>(1 << (this->octree_depth_ - tree_depth_arg));
888 min_pt(0) =
static_cast<float>(
static_cast<double>(key_arg.
x) * voxel_side_len +
890 min_pt(1) =
static_cast<float>(
static_cast<double>(key_arg.
y) * voxel_side_len +
892 min_pt(2) =
static_cast<float>(
static_cast<double>(key_arg.
z) * voxel_side_len +
895 max_pt(0) =
static_cast<float>(
static_cast<double>(key_arg.
x + 1) * voxel_side_len +
897 max_pt(1) =
static_cast<float>(
static_cast<double>(key_arg.
y + 1) * voxel_side_len +
899 max_pt(2) =
static_cast<float>(
static_cast<double>(key_arg.
z + 1) * voxel_side_len +
905 typename LeafContainerT,
906 typename BranchContainerT,
915 side_len = this->resolution_ *
916 static_cast<double>(1 << (this->octree_depth_ - tree_depth_arg));
919 side_len *= side_len;
926 typename LeafContainerT,
927 typename BranchContainerT,
934 return (getVoxelSquaredSideLen(tree_depth_arg) * 3);
939 typename LeafContainerT,
940 typename BranchContainerT,
951 for (
unsigned char child_idx = 0; child_idx < 8; child_idx++) {
952 if (!this->branchHasChild(*node_arg, child_idx))
956 child_node = this->getBranchChildPtr(*node_arg, child_idx);
960 new_key.
x = (key_arg.
x << 1) | (!!(child_idx & (1 << 2)));
961 new_key.
y = (key_arg.
y << 1) | (!!(child_idx & (1 << 1)));
962 new_key.
z = (key_arg.
z << 1) | (!!(child_idx & (1 << 0)));
967 voxel_count += getOccupiedVoxelCentersRecursive(
968 static_cast<const BranchNode*
>(child_node), new_key, voxel_center_list_arg);
974 genLeafNodeCenterFromOctreeKey(new_key, new_point);
975 voxel_center_list_arg.push_back(new_point);
984 return (voxel_count);
987#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithLeafDataTVector(T) \
988 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
990 pcl::octree::OctreeContainerPointIndices, \
991 pcl::octree::OctreeContainerEmpty, \
992 pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndices, \
993 pcl::octree::OctreeContainerEmpty>>;
994#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithLeafDataTVector(T) \
995 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
997 pcl::octree::OctreeContainerPointIndices, \
998 pcl::octree::OctreeContainerEmpty, \
999 pcl::octree::Octree2BufBase<pcl::octree::OctreeContainerPointIndices, \
1000 pcl::octree::OctreeContainerEmpty>>;
1002#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithLeafDataT(T) \
1003 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1005 pcl::octree::OctreeContainerPointIndex, \
1006 pcl::octree::OctreeContainerEmpty, \
1007 pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndex, \
1008 pcl::octree::OctreeContainerEmpty>>;
1009#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithLeafDataT(T) \
1010 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1012 pcl::octree::OctreeContainerPointIndex, \
1013 pcl::octree::OctreeContainerEmpty, \
1014 pcl::octree::Octree2BufBase<pcl::octree::OctreeContainerPointIndex, \
1015 pcl::octree::OctreeContainerEmpty>>;
1017#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithEmptyLeaf(T) \
1018 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1020 pcl::octree::OctreeContainerEmpty, \
1021 pcl::octree::OctreeContainerEmpty, \
1022 pcl::octree::OctreeBase<pcl::octree::OctreeContainerEmpty, \
1023 pcl::octree::OctreeContainerEmpty>>;
1024#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithEmptyLeaf(T) \
1025 template class PCL_EXPORTS pcl::octree::OctreePointCloud< \
1027 pcl::octree::OctreeContainerEmpty, \
1028 pcl::octree::OctreeContainerEmpty, \
1029 pcl::octree::Octree2BufBase<pcl::octree::OctreeContainerEmpty, \
1030 pcl::octree::OctreeContainerEmpty>>;
An exception thrown when init can not be performed should be used in all the PCLBase class inheritant...
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.
void adoptBoundingBoxToPoint(const PointT &point_idx_arg)
Grow the bounding box/octree until point fits.
uindex_t getOccupiedVoxelCenters(AlignedPointTVector &voxel_center_list_arg) const
Get a PointT vector of centers of all occupied voxels.
const PointT & getPointByIndex(uindex_t index_arg) const
Get point at index from input pointcloud dataset.
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.
void deleteVoxelAtPoint(const PointT &point_arg)
Delete leaf node / voxel at given point.
void genLeafNodeCenterFromOctreeKey(const OctreeKey &key_arg, PointT &point_arg) const
Generate a point at center of leaf node voxel.
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.
typename PointCloud::Ptr PointCloudPtr
void addPointFromCloud(uindex_t point_idx_arg, IndicesPtr indices_arg)
Add point at given index from input point cloud to octree.
OctreePointCloud(const double resolution_arg)
Octree pointcloud constructor.
shared_ptr< Indices > IndicesPtr
void addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg)
Add point simultaneously to octree and input point cloud.
typename PointCloud::ConstPtr PointCloudConstPtr
void defineBoundingBox()
Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.
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.
typename OctreeT::LeafNode LeafNode
virtual void addPointIdx(uindex_t point_idx_arg)
Add point at index from input pointcloud dataset to octree.
double getVoxelSquaredSideLen() const
Calculates the squared voxel cube side length at leaf level.
bool isVoxelOccupiedAtPoint(const PointT &point_arg) const
Check if voxel at given point exist.
std::vector< PointT, Eigen::aligned_allocator< PointT > > AlignedPointTVector
void addPointsFromInputCloud()
Add points from input point cloud to octree.
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.
typename OctreeT::BranchNode BranchNode
void genOctreeKeyforPoint(const PointT &point_arg, OctreeKey &key_arg) const
Generate octree key for voxel at a given point.
shared_ptr< const Indices > IndicesConstPtr
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.
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.
virtual bool genOctreeKeyForDataT(const index_t &data_arg, OctreeKey &key_arg) const
Virtual method for generating octree key for a given point index.
void getKeyBitSize()
Define octree key setting and octree depth based on defined bounding box.
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.
detail::int_type_t< detail::index_type_size, false > uindex_t
Type used for an unsigned index in PCL.
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.
A point structure representing Euclidean xyz coordinates, and the RGB color.
Defines basic non-point types used by PCL.