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
00040 #ifndef PCL_SEARCH_ORGANIZED_NEIGHBOR_SEARCH_H_
00041 #define PCL_SEARCH_ORGANIZED_NEIGHBOR_SEARCH_H_
00042
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/search/search.h>
00046 #include <pcl/common/eigen.h>
00047
00048 #include <algorithm>
00049 #include <queue>
00050 #include <vector>
00051 #include <pcl/common/projection_matrix.h>
00052
00053 namespace pcl
00054 {
00055 namespace search
00056 {
00061 template<typename PointT>
00062 class OrganizedNeighbor : public pcl::search::Search<PointT>
00063 {
00064
00065 public:
00066
00067 typedef pcl::PointCloud<PointT> PointCloud;
00068 typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00069
00070 typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
00071 typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00072
00073 typedef boost::shared_ptr<pcl::search::OrganizedNeighbor<PointT> > Ptr;
00074 typedef boost::shared_ptr<const pcl::search::OrganizedNeighbor<PointT> > ConstPtr;
00075
00076 using pcl::search::Search<PointT>::indices_;
00077 using pcl::search::Search<PointT>::sorted_results_;
00078 using pcl::search::Search<PointT>::input_;
00079
00088 OrganizedNeighbor (bool sorted_results = false, float eps = 1e-4f, unsigned pyramid_level = 5)
00089 : Search<PointT> ("OrganizedNeighbor", sorted_results)
00090 , projection_matrix_ (Eigen::Matrix<float, 3, 4, Eigen::RowMajor>::Zero ())
00091 , KR_ (Eigen::Matrix<float, 3, 3, Eigen::RowMajor>::Zero ())
00092 , KR_KRT_ (Eigen::Matrix<float, 3, 3, Eigen::RowMajor>::Zero ())
00093 , eps_ (eps)
00094 , pyramid_level_ (pyramid_level)
00095 , mask_ ()
00096 {
00097 }
00098
00100 virtual ~OrganizedNeighbor () {}
00101
00107 bool
00108 isValid () const
00109 {
00110
00111
00112
00113 float min_f = 0.043744332f * static_cast<float>(input_->width);
00114
00115 return (determinant3x3Matrix<Eigen::Matrix3f> (KR_ / sqrtf (KR_KRT_.coeff (8))) >= (min_f * min_f));
00116 }
00117
00121 void
00122 computeCameraMatrix (Eigen::Matrix3f& camera_matrix) const;
00123
00128 virtual void
00129 setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr &indices = IndicesConstPtr ())
00130 {
00131 input_ = cloud;
00132
00133 mask_.resize (input_->size ());
00134 input_ = cloud;
00135 indices_ = indices;
00136
00137 if (indices_.get () != NULL && indices_->size () != 0)
00138 {
00139 mask_.assign (input_->size (), 0);
00140 for (std::vector<int>::const_iterator iIt = indices_->begin (); iIt != indices_->end (); ++iIt)
00141 mask_[*iIt] = 1;
00142 }
00143 else
00144 mask_.assign (input_->size (), 1);
00145
00146 estimateProjectionMatrix ();
00147 }
00148
00159 int
00160 radiusSearch (const PointT &p_q,
00161 double radius,
00162 std::vector<int> &k_indices,
00163 std::vector<float> &k_sqr_distances,
00164 unsigned int max_nn = 0) const;
00165
00167 void
00168 estimateProjectionMatrix ();
00169
00179 int
00180 nearestKSearch (const PointT &p_q,
00181 int k,
00182 std::vector<int> &k_indices,
00183 std::vector<float> &k_sqr_distances) const;
00184
00190 bool projectPoint (const PointT& p, pcl::PointXY& q) const;
00191
00192 protected:
00193
00194 struct Entry
00195 {
00196 Entry (int idx, float dist) : index (idx), distance (dist) {}
00197 Entry () : index (0), distance (0) {}
00198 unsigned index;
00199 float distance;
00200
00201 inline bool
00202 operator < (const Entry& other) const
00203 {
00204 return (distance < other.distance);
00205 }
00206 };
00207
00215 inline bool
00216 testPoint (const PointT& query, unsigned k, std::priority_queue<Entry>& queue, unsigned index) const
00217 {
00218 const PointT& point = input_->points [index];
00219 if (mask_ [index] && pcl_isfinite (point.x))
00220 {
00221
00222 float dist_x = point.x - query.x;
00223 float dist_y = point.y - query.y;
00224 float dist_z = point.z - query.z;
00225 float squared_distance = dist_x * dist_x + dist_y * dist_y + dist_z * dist_z;
00226 if (queue.size () < k)
00227 queue.push (Entry (index, squared_distance));
00228 else if (queue.top ().distance > squared_distance)
00229 {
00230 queue.pop ();
00231 queue.push (Entry (index, squared_distance));
00232 return true;
00233 }
00234 }
00235 return false;
00236 }
00237
00238 inline void
00239 clipRange (int& begin, int &end, int min, int max) const
00240 {
00241 begin = std::max (std::min (begin, max), min);
00242 end = std::min (std::max (end, min), max);
00243 }
00244
00253 void
00254 getProjectedRadiusSearchBox (const PointT& point, float squared_radius, unsigned& minX, unsigned& minY,
00255 unsigned& maxX, unsigned& maxY) const;
00256
00257
00259 Eigen::Matrix<float, 3, 4, Eigen::RowMajor> projection_matrix_;
00260
00262 Eigen::Matrix<float, 3, 3, Eigen::RowMajor> KR_;
00263
00265 Eigen::Matrix<float, 3, 3, Eigen::RowMajor> KR_KRT_;
00266
00268 const float eps_;
00269
00271 const unsigned pyramid_level_;
00272
00274 std::vector<unsigned char> mask_;
00275 public:
00276 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00277 };
00278 }
00279 }
00280
00281 #ifdef PCL_NO_PRECOMPILE
00282 #include <pcl/search/impl/organized.hpp>
00283 #endif
00284
00285 #endif
00286