Go to the documentation of this file.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
00041 #ifndef PCL_BOUNDARY_H_
00042 #define PCL_BOUNDARY_H_
00043
00044 #include <pcl/features/eigen.h>
00045 #include <pcl/features/feature.h>
00046
00047 namespace pcl
00048 {
00080 template <typename PointInT, typename PointNT, typename PointOutT>
00081 class BoundaryEstimation: public FeatureFromNormals<PointInT, PointNT, PointOutT>
00082 {
00083 public:
00084 typedef boost::shared_ptr<BoundaryEstimation<PointInT, PointNT, PointOutT> > Ptr;
00085 typedef boost::shared_ptr<const BoundaryEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00086
00087 using Feature<PointInT, PointOutT>::feature_name_;
00088 using Feature<PointInT, PointOutT>::getClassName;
00089 using Feature<PointInT, PointOutT>::input_;
00090 using Feature<PointInT, PointOutT>::indices_;
00091 using Feature<PointInT, PointOutT>::k_;
00092 using Feature<PointInT, PointOutT>::tree_;
00093 using Feature<PointInT, PointOutT>::search_radius_;
00094 using Feature<PointInT, PointOutT>::search_parameter_;
00095 using Feature<PointInT, PointOutT>::surface_;
00096 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00097
00098 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00099
00100 public:
00104 BoundaryEstimation () : angle_threshold_ (static_cast<float> (M_PI) / 2.0f)
00105 {
00106 feature_name_ = "BoundaryEstimation";
00107 };
00108
00118 bool
00119 isBoundaryPoint (const pcl::PointCloud<PointInT> &cloud,
00120 int q_idx, const std::vector<int> &indices,
00121 const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold);
00122
00132 bool
00133 isBoundaryPoint (const pcl::PointCloud<PointInT> &cloud,
00134 const PointInT &q_point,
00135 const std::vector<int> &indices,
00136 const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold);
00137
00142 inline void
00143 setAngleThreshold (float angle)
00144 {
00145 angle_threshold_ = angle;
00146 }
00147
00149 inline float
00150 getAngleThreshold ()
00151 {
00152 return (angle_threshold_);
00153 }
00154
00160 inline void
00161 getCoordinateSystemOnPlane (const PointNT &p_coeff,
00162 Eigen::Vector4f &u, Eigen::Vector4f &v)
00163 {
00164 pcl::Vector4fMapConst p_coeff_v = p_coeff.getNormalVector4fMap ();
00165 v = p_coeff_v.unitOrthogonal ();
00166 u = p_coeff_v.cross3 (v);
00167 }
00168
00169 protected:
00175 void
00176 computeFeature (PointCloudOut &output);
00177
00179 float angle_threshold_;
00180 };
00181 }
00182
00183 #ifdef PCL_NO_PRECOMPILE
00184 #include <pcl/features/impl/boundary.hpp>
00185 #endif
00186
00187 #endif //#ifndef PCL_BOUNDARY_H_