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_BOUNDARY_H_
00041 #define PCL_BOUNDARY_H_
00042
00043 #include <pcl/features/feature.h>
00044 #include <Eigen/Geometry>
00045
00046 namespace pcl
00047 {
00079 template <typename PointInT, typename PointNT, typename PointOutT>
00080 class BoundaryEstimation: public FeatureFromNormals<PointInT, PointNT, PointOutT>
00081 {
00082 public:
00083 using Feature<PointInT, PointOutT>::feature_name_;
00084 using Feature<PointInT, PointOutT>::getClassName;
00085 using Feature<PointInT, PointOutT>::input_;
00086 using Feature<PointInT, PointOutT>::indices_;
00087 using Feature<PointInT, PointOutT>::k_;
00088 using Feature<PointInT, PointOutT>::tree_;
00089 using Feature<PointInT, PointOutT>::search_radius_;
00090 using Feature<PointInT, PointOutT>::search_parameter_;
00091 using Feature<PointInT, PointOutT>::surface_;
00092 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00093
00094 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00095
00096 public:
00100 BoundaryEstimation () : angle_threshold_ (static_cast<float> (M_PI) / 2.0f)
00101 {
00102 feature_name_ = "BoundaryEstimation";
00103 };
00104
00114 bool
00115 isBoundaryPoint (const pcl::PointCloud<PointInT> &cloud,
00116 int q_idx, const std::vector<int> &indices,
00117 const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold);
00118
00128 bool
00129 isBoundaryPoint (const pcl::PointCloud<PointInT> &cloud,
00130 const PointInT &q_point,
00131 const std::vector<int> &indices,
00132 const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold);
00133
00138 inline void
00139 setAngleThreshold (float angle)
00140 {
00141 angle_threshold_ = angle;
00142 }
00143
00145 inline float
00146 getAngleThreshold ()
00147 {
00148 return (angle_threshold_);
00149 }
00150
00156 inline void
00157 getCoordinateSystemOnPlane (const PointNT &p_coeff,
00158 Eigen::Vector4f &u, Eigen::Vector4f &v)
00159 {
00160 pcl::Vector4fMapConst p_coeff_v = p_coeff.getNormalVector4fMap ();
00161 v = p_coeff_v.unitOrthogonal ();
00162 u = p_coeff_v.cross3 (v);
00163 }
00164
00165 protected:
00171 void
00172 computeFeature (PointCloudOut &output);
00173
00175 float angle_threshold_;
00176
00177 private:
00181 void
00182 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00183 };
00184
00199 template <typename PointInT, typename PointNT>
00200 class BoundaryEstimation<PointInT, PointNT, Eigen::MatrixXf>: public BoundaryEstimation<PointInT, PointNT, pcl::Boundary>
00201 {
00202 public:
00203 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::k_;
00204 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::indices_;
00205 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::input_;
00206 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::surface_;
00207 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::angle_threshold_;
00208 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::normals_;
00209 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::search_parameter_;
00210 using BoundaryEstimation<PointInT, PointNT, pcl::Boundary>::compute;
00211
00212 private:
00218 void
00219 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00220
00224 void
00225 compute (pcl::PointCloud<pcl::Boundary> &) {}
00226 };
00227 }
00228
00229 #endif //#ifndef PCL_BOUNDARY_H_
00230
00231