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 #ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_
00039 #define PCL_SEGMENTATION_SAC_SEGMENTATION_H_
00040
00041 #include "pcl/pcl_base.h"
00042 #include "pcl/PointIndices.h"
00043 #include "pcl/ModelCoefficients.h"
00044
00045
00046 #include "pcl/sample_consensus/sac.h"
00047
00048 #include "pcl/sample_consensus/sac_model.h"
00049
00050 namespace pcl
00051 {
00057 template <typename PointT>
00058 class SACSegmentation : public PCLBase<PointT>
00059 {
00060 using PCLBase<PointT>::initCompute;
00061 using PCLBase<PointT>::deinitCompute;
00062
00063 public:
00064 using PCLBase<PointT>::input_;
00065 using PCLBase<PointT>::indices_;
00066
00067 typedef pcl::PointCloud<PointT> PointCloud;
00068 typedef typename PointCloud::Ptr PointCloudPtr;
00069 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00070
00071 typedef typename SampleConsensus<PointT>::Ptr SampleConsensusPtr;
00072 typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;
00073
00075 SACSegmentation () : model_type_ (-1), method_type_ (0), optimize_coefficients_ (true),
00076 radius_min_ (-DBL_MAX), radius_max_ (DBL_MAX), eps_angle_ (0.0),
00077 max_iterations_ (50), probability_ (0.99)
00078 {
00079 axis_.setZero ();
00080
00081 }
00082
00084 virtual ~SACSegmentation () { };
00085
00089 inline void setModelType (int model) { model_type_ = model; }
00090
00092 inline int
00093 getModelType () { return (model_type_); }
00094
00096 inline SampleConsensusPtr
00097 getMethod () { return (sac_); }
00098
00100 inline SampleConsensusModelPtr
00101 getModel () { return (model_); }
00102
00106 inline void
00107 setMethodType (int method) { method_type_ = method; }
00108
00110 inline int
00111 getMethodType () { return (method_type_); }
00112
00116 inline void
00117 setDistanceThreshold (double threshold) { threshold_ = threshold; }
00118
00120 inline double
00121 getDistanceThreshold () { return (threshold_); }
00122
00126 inline void
00127 setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; }
00128
00130 inline int
00131 getMaxIterations () { return (max_iterations_); }
00132
00136 inline void
00137 setProbability (double probability) { probability_ = probability; }
00138
00140 inline double
00141 getProbability () { return (probability_); }
00142
00146 inline void
00147 setOptimizeCoefficients (bool optimize) { optimize_coefficients_ = optimize; }
00148
00150 inline bool
00151 getOptimizeCoefficients () { return (optimize_coefficients_); }
00152
00159 inline void
00160 setRadiusLimits (const double &min_radius, const double &max_radius)
00161 {
00162 radius_min_ = min_radius;
00163 radius_max_ = max_radius;
00164 }
00165
00170 inline void
00171 getRadiusLimits (double &min_radius, double &max_radius)
00172 {
00173 min_radius = radius_min_;
00174 max_radius = radius_max_;
00175 }
00176
00180 inline void
00181 setAxis (const Eigen::Vector3f &ax) { axis_ = ax; }
00182
00184 inline Eigen::Vector3f
00185 getAxis () { return (axis_); }
00186
00190 inline void
00191 setEpsAngle (double ea) { eps_angle_ = ea; }
00192
00194 inline double
00195 getEpsAngle () { return (eps_angle_); }
00196
00201 virtual void
00202 segment (PointIndices &inliers, ModelCoefficients &model_coefficients);
00203
00204 protected:
00208 virtual bool
00209 initSACModel (const int model_type);
00210
00214 virtual void
00215 initSAC (const int method_type);
00216
00218 SampleConsensusModelPtr model_;
00219
00221 SampleConsensusPtr sac_;
00222
00224 int model_type_;
00225
00227 int method_type_;
00228
00230 double threshold_;
00231
00233 bool optimize_coefficients_;
00234
00236 double radius_min_, radius_max_;
00237
00239 double eps_angle_;
00240
00242 Eigen::Vector3f axis_;
00243
00245 int max_iterations_;
00246
00248 double probability_;
00249
00251 virtual std::string
00252 getClassName () const { return ("SACSegmentation"); }
00253 };
00254
00258 template <typename PointT, typename PointNT>
00259 class SACSegmentationFromNormals: public SACSegmentation<PointT>
00260 {
00261 using SACSegmentation<PointT>::model_;
00262 using SACSegmentation<PointT>::model_type_;
00263 using SACSegmentation<PointT>::radius_min_;
00264 using SACSegmentation<PointT>::radius_max_;
00265 using SACSegmentation<PointT>::eps_angle_;
00266 using SACSegmentation<PointT>::axis_;
00267
00268 public:
00269 using PCLBase<PointT>::input_;
00270 using PCLBase<PointT>::indices_;
00271
00272 typedef typename SACSegmentation<PointT>::PointCloud PointCloud;
00273 typedef typename PointCloud::Ptr PointCloudPtr;
00274 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00275
00276 typedef typename pcl::PointCloud<PointNT> PointCloudN;
00277 typedef typename PointCloudN::Ptr PointCloudNPtr;
00278 typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00279
00280 typedef typename SampleConsensus<PointT>::Ptr SampleConsensusPtr;
00281 typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;
00282 typedef typename SampleConsensusModelFromNormals<PointT, PointNT>::Ptr SampleConsensusModelFromNormalsPtr;
00283
00285 SACSegmentationFromNormals () : distance_weight_ (0.1) {};
00286
00291 inline void
00292 setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00293
00295 inline PointCloudNConstPtr
00296 getInputNormals () { return (normals_); }
00297
00302 inline void
00303 setNormalDistanceWeight (double distance_weight) { distance_weight_ = distance_weight; }
00304
00307 inline double
00308 getNormalDistanceWeight () { return (distance_weight_); }
00309
00310 protected:
00312 PointCloudNConstPtr normals_;
00313
00317 double distance_weight_;
00318
00322 virtual bool
00323 initSACModel (const int model_type);
00324
00326 virtual std::string
00327 getClassName () const { return ("SACSegmentationFromNormals"); }
00328 };
00329 }
00330
00331 #endif //#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_