00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_OCTREE_SEARCH_H_
00040 #define PCL_OCTREE_SEARCH_H_
00041
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044
00045 #include "octree_pointcloud.h"
00046
00047 namespace pcl
00048 {
00049 namespace octree
00050 {
00057 template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices , typename BranchContainerT = OctreeContainerEmpty >
00058 class OctreePointCloudSearch : public OctreePointCloud<PointT, LeafContainerT, BranchContainerT>
00059 {
00060 public:
00061
00062 typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00063 typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00064
00065 typedef pcl::PointCloud<PointT> PointCloud;
00066 typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00067 typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
00068
00069
00070 typedef boost::shared_ptr<OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT> > Ptr;
00071 typedef boost::shared_ptr<const OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT> > ConstPtr;
00072
00073
00074 typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > AlignedPointTVector;
00075
00076 typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT> OctreeT;
00077 typedef typename OctreeT::LeafNode LeafNode;
00078 typedef typename OctreeT::BranchNode BranchNode;
00079
00083 OctreePointCloudSearch (const double resolution) :
00084 OctreePointCloud<PointT, LeafContainerT, BranchContainerT> (resolution)
00085 {
00086 }
00087
00089 virtual
00090 ~OctreePointCloudSearch ()
00091 {
00092 }
00093
00099 bool
00100 voxelSearch (const PointT& point, std::vector<int>& point_idx_data);
00101
00107 bool
00108 voxelSearch (const int index, std::vector<int>& point_idx_data);
00109
00119 inline int
00120 nearestKSearch (const PointCloud &cloud, int index, int k, std::vector<int> &k_indices,
00121 std::vector<float> &k_sqr_distances)
00122 {
00123 return (nearestKSearch (cloud[index], k, k_indices, k_sqr_distances));
00124 }
00125
00133 int
00134 nearestKSearch (const PointT &p_q, int k, std::vector<int> &k_indices,
00135 std::vector<float> &k_sqr_distances);
00136
00146 int
00147 nearestKSearch (int index, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances);
00148
00156 inline void
00157 approxNearestSearch (const PointCloud &cloud, int query_index, int &result_index, float &sqr_distance)
00158 {
00159 return (approxNearestSearch (cloud.points[query_index], result_index, sqr_distance));
00160 }
00161
00167 void
00168 approxNearestSearch (const PointT &p_q, int &result_index, float &sqr_distance);
00169
00177 void
00178 approxNearestSearch (int query_index, int &result_index, float &sqr_distance);
00179
00189 int
00190 radiusSearch (const PointCloud &cloud, int index, double radius, std::vector<int> &k_indices,
00191 std::vector<float> &k_sqr_distances, unsigned int max_nn = 0)
00192 {
00193 return (radiusSearch (cloud.points[index], radius, k_indices, k_sqr_distances, max_nn));
00194 }
00195
00204 int
00205 radiusSearch (const PointT &p_q, const double radius, std::vector<int> &k_indices,
00206 std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const;
00207
00217 int
00218 radiusSearch (int index, const double radius, std::vector<int> &k_indices,
00219 std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const;
00220
00228 int
00229 getIntersectedVoxelCenters (Eigen::Vector3f origin, Eigen::Vector3f direction,
00230 AlignedPointTVector &voxel_center_list, int max_voxel_count = 0) const;
00231
00239 int
00240 getIntersectedVoxelIndices (Eigen::Vector3f origin, Eigen::Vector3f direction,
00241 std::vector<int> &k_indices,
00242 int max_voxel_count = 0) const;
00243
00244
00251 int
00252 boxSearch (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, std::vector<int> &k_indices) const;
00253
00254 protected:
00256
00258
00262 class prioBranchQueueEntry
00263 {
00264 public:
00266 prioBranchQueueEntry () :
00267 node (), point_distance (0), key ()
00268 {
00269 }
00270
00276 prioBranchQueueEntry (OctreeNode* _node, OctreeKey& _key, float _point_distance) :
00277 node (_node), point_distance (_point_distance), key (_key)
00278 {
00279 }
00280
00284 bool
00285 operator < (const prioBranchQueueEntry rhs) const
00286 {
00287 return (this->point_distance > rhs.point_distance);
00288 }
00289
00291 const OctreeNode* node;
00292
00294 float point_distance;
00295
00297 OctreeKey key;
00298 };
00299
00301
00305 class prioPointQueueEntry
00306 {
00307 public:
00308
00310 prioPointQueueEntry () :
00311 point_idx_ (0), point_distance_ (0)
00312 {
00313 }
00314
00319 prioPointQueueEntry (unsigned int& point_idx, float point_distance) :
00320 point_idx_ (point_idx), point_distance_ (point_distance)
00321 {
00322 }
00323
00327 bool
00328 operator< (const prioPointQueueEntry& rhs) const
00329 {
00330 return (this->point_distance_ < rhs.point_distance_);
00331 }
00332
00334 int point_idx_;
00335
00337 float point_distance_;
00338 };
00339
00345 float
00346 pointSquaredDist (const PointT& point_a, const PointT& point_b) const;
00347
00349
00351
00362 void
00363 getNeighborsWithinRadiusRecursive (const PointT& point, const double radiusSquared,
00364 const BranchNode* node, const OctreeKey& key,
00365 unsigned int tree_depth, std::vector<int>& k_indices,
00366 std::vector<float>& k_sqr_distances, unsigned int max_nn) const;
00367
00378 double
00379 getKNearestNeighborRecursive (const PointT& point, unsigned int K, const BranchNode* node,
00380 const OctreeKey& key, unsigned int tree_depth,
00381 const double squared_search_radius,
00382 std::vector<prioPointQueueEntry>& point_candidates) const;
00383
00392 void
00393 approxNearestSearchRecursive (const PointT& point, const BranchNode* node, const OctreeKey& key,
00394 unsigned int tree_depth, int& result_index, float& sqr_distance);
00395
00412 int
00413 getIntersectedVoxelCentersRecursive (double min_x, double min_y, double min_z, double max_x, double max_y,
00414 double max_z, unsigned char a, const OctreeNode* node,
00415 const OctreeKey& key, AlignedPointTVector &voxel_center_list,
00416 int max_voxel_count) const;
00417
00418
00427 void
00428 boxSearchRecursive (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, const BranchNode* node,
00429 const OctreeKey& key, unsigned int tree_depth, std::vector<int>& k_indices) const;
00430
00447 int
00448 getIntersectedVoxelIndicesRecursive (double min_x, double min_y, double min_z,
00449 double max_x, double max_y, double max_z,
00450 unsigned char a, const OctreeNode* node, const OctreeKey& key,
00451 std::vector<int> &k_indices,
00452 int max_voxel_count) const;
00453
00465 inline void
00466 initIntersectedVoxel (Eigen::Vector3f &origin, Eigen::Vector3f &direction,
00467 double &min_x, double &min_y, double &min_z,
00468 double &max_x, double &max_y, double &max_z,
00469 unsigned char &a) const
00470 {
00471
00472 const float epsilon = 1e-10f;
00473 if (direction.x () == 0.0)
00474 direction.x () = epsilon;
00475 if (direction.y () == 0.0)
00476 direction.y () = epsilon;
00477 if (direction.z () == 0.0)
00478 direction.z () = epsilon;
00479
00480
00481 a = 0;
00482
00483
00484 if (direction.x () < 0.0)
00485 {
00486 origin.x () = static_cast<float> (this->min_x_) + static_cast<float> (this->max_x_) - origin.x ();
00487 direction.x () = -direction.x ();
00488 a |= 4;
00489 }
00490 if (direction.y () < 0.0)
00491 {
00492 origin.y () = static_cast<float> (this->min_y_) + static_cast<float> (this->max_y_) - origin.y ();
00493 direction.y () = -direction.y ();
00494 a |= 2;
00495 }
00496 if (direction.z () < 0.0)
00497 {
00498 origin.z () = static_cast<float> (this->min_z_) + static_cast<float> (this->max_z_) - origin.z ();
00499 direction.z () = -direction.z ();
00500 a |= 1;
00501 }
00502 min_x = (this->min_x_ - origin.x ()) / direction.x ();
00503 max_x = (this->max_x_ - origin.x ()) / direction.x ();
00504 min_y = (this->min_y_ - origin.y ()) / direction.y ();
00505 max_y = (this->max_y_ - origin.y ()) / direction.y ();
00506 min_z = (this->min_z_ - origin.z ()) / direction.z ();
00507 max_z = (this->max_z_ - origin.z ()) / direction.z ();
00508 }
00509
00519 inline int
00520 getFirstIntersectedNode (double min_x, double min_y, double min_z, double mid_x, double mid_y, double mid_z) const
00521 {
00522 int currNode = 0;
00523
00524 if (min_x > min_y)
00525 {
00526 if (min_x > min_z)
00527 {
00528
00529 if (mid_y < min_x)
00530 currNode |= 2;
00531 if (mid_z < min_x)
00532 currNode |= 1;
00533 }
00534 else
00535 {
00536
00537 if (mid_x < min_z)
00538 currNode |= 4;
00539 if (mid_y < min_z)
00540 currNode |= 2;
00541 }
00542 }
00543 else
00544 {
00545 if (min_y > min_z)
00546 {
00547
00548 if (mid_x < min_y)
00549 currNode |= 4;
00550 if (mid_z < min_y)
00551 currNode |= 1;
00552 }
00553 else
00554 {
00555
00556 if (mid_x < min_z)
00557 currNode |= 4;
00558 if (mid_y < min_z)
00559 currNode |= 2;
00560 }
00561 }
00562
00563 return currNode;
00564 }
00565
00578 inline int
00579 getNextIntersectedNode (double x, double y, double z, int a, int b, int c) const
00580 {
00581 if (x < y)
00582 {
00583 if (x < z)
00584 return a;
00585 else
00586 return c;
00587 }
00588 else
00589 {
00590 if (y < z)
00591 return b;
00592 else
00593 return c;
00594 }
00595
00596 return 0;
00597 }
00598
00599 };
00600 }
00601 }
00602
00603 #define PCL_INSTANTIATE_OctreePointCloudSearch(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudSearch<T>;
00604
00605 #endif // PCL_OCTREE_SEARCH_H_