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 #ifndef PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_H_
00040 #define PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_H_
00041
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/features/feature.h>
00045
00046 namespace pcl
00047 {
00051 template <typename PointInT, typename PointOutT>
00052 class LinearLeastSquaresNormalEstimation : public Feature<PointInT, PointOutT>
00053 {
00054 public:
00055 typedef boost::shared_ptr<LinearLeastSquaresNormalEstimation<PointInT, PointOutT> > Ptr;
00056 typedef boost::shared_ptr<const LinearLeastSquaresNormalEstimation<PointInT, PointOutT> > ConstPtr;
00057 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00058 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00059 using Feature<PointInT, PointOutT>::input_;
00060 using Feature<PointInT, PointOutT>::feature_name_;
00061 using Feature<PointInT, PointOutT>::tree_;
00062 using Feature<PointInT, PointOutT>::k_;
00063
00065 LinearLeastSquaresNormalEstimation () :
00066 use_depth_dependent_smoothing_(false),
00067 max_depth_change_factor_(1.0f),
00068 normal_smoothing_size_(9.0f)
00069 {
00070 feature_name_ = "LinearLeastSquaresNormalEstimation";
00071 tree_.reset ();
00072 k_ = 1;
00073 };
00074
00076 virtual ~LinearLeastSquaresNormalEstimation ();
00077
00083 void
00084 computePointNormal (const int pos_x, const int pos_y, PointOutT &normal);
00085
00090 void
00091 setNormalSmoothingSize (float normal_smoothing_size)
00092 {
00093 normal_smoothing_size_ = normal_smoothing_size;
00094 }
00095
00099 void
00100 setDepthDependentSmoothing (bool use_depth_dependent_smoothing)
00101 {
00102 use_depth_dependent_smoothing_ = use_depth_dependent_smoothing;
00103 }
00104
00109 void
00110 setMaxDepthChangeFactor (float max_depth_change_factor)
00111 {
00112 max_depth_change_factor_ = max_depth_change_factor;
00113 }
00114
00118 virtual inline void
00119 setInputCloud (const typename PointCloudIn::ConstPtr &cloud)
00120 {
00121 input_ = cloud;
00122 }
00123
00124 protected:
00128 void
00129 computeFeature (PointCloudOut &output);
00130
00131 private:
00132
00134
00135
00137 bool use_depth_dependent_smoothing_;
00138
00140 float max_depth_change_factor_;
00141
00143 float normal_smoothing_size_;
00144 };
00145 }
00146
00147 #ifdef PCL_NO_PRECOMPILE
00148 #include <pcl/features/impl/linear_least_squares_normal.hpp>
00149 #endif
00150
00151 #endif
00152