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_SAMPLE_CONSENSUS_MODEL_H_
00039 #define PCL_SAMPLE_CONSENSUS_MODEL_H_
00040
00041 #include <cfloat>
00042 #include <limits.h>
00043 #include <set>
00044
00045 #include "pcl/pcl_base.h"
00046 #include "pcl/point_types.h"
00047 #include "pcl/io/io.h"
00048
00049 #include "model_types.h"
00050
00051 namespace pcl
00052 {
00053
00054 template<class T> class ProgressiveSampleConsensus;
00055
00060 template <typename PointT>
00061 class SampleConsensusModel
00062 {
00063 public:
00064 typedef typename pcl::PointCloud<PointT> PointCloud;
00065 typedef typename pcl::PointCloud<PointT>::ConstPtr PointCloudConstPtr;
00066 typedef typename pcl::PointCloud<PointT>::Ptr PointCloudPtr;
00067
00068 typedef boost::shared_ptr<SampleConsensusModel> Ptr;
00069 typedef boost::shared_ptr<const SampleConsensusModel> ConstPtr;
00070
00071 private:
00073 SampleConsensusModel () : radius_min_ (-DBL_MAX), radius_max_ (DBL_MAX) {};
00074
00075 public:
00079 SampleConsensusModel (const PointCloudConstPtr &cloud) :
00080 radius_min_ (-DBL_MAX), radius_max_ (DBL_MAX)
00081 {
00082
00083 setInputCloud (cloud);
00084 }
00085
00090 SampleConsensusModel (const PointCloudConstPtr &cloud, const std::vector<int> &indices) :
00091 input_ (cloud),
00092 indices_ (boost::make_shared <std::vector<int> > (indices)),
00093 radius_min_ (-DBL_MAX), radius_max_ (DBL_MAX)
00094
00095 {
00096 if (indices_->size () > input_->points.size ())
00097 {
00098 ROS_ERROR ("[pcl::SampleConsensusModel] Invalid index vector given with size %zu while the input PointCloud has size %zu!", indices_->size (), input_->points.size ());
00099 indices_->clear ();
00100 }
00101 };
00102
00104 virtual ~SampleConsensusModel () {};
00105
00111 virtual void
00112 getSamples (int &iterations, std::vector<int> &samples) = 0;
00113
00121 virtual bool
00122 computeModelCoefficients (const std::vector<int> &samples,
00123 Eigen::VectorXf &model_coefficients) = 0;
00124
00136 virtual void
00137 optimizeModelCoefficients (const std::vector<int> &inliers,
00138 const Eigen::VectorXf &model_coefficients,
00139 Eigen::VectorXf &optimized_coefficients) = 0;
00140
00147 virtual void
00148 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00149 std::vector<double> &distances) = 0;
00150
00160 virtual void
00161 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00162 double threshold,
00163 std::vector<int> &inliers) = 0;
00164
00173 virtual void
00174 projectPoints (const std::vector<int> &inliers,
00175 const Eigen::VectorXf &model_coefficients,
00176 PointCloud &projected_points,
00177 bool copy_data_fields = true) = 0;
00178
00187 virtual bool
00188 doSamplesVerifyModel (const std::set<int> &indices,
00189 const Eigen::VectorXf &model_coefficients,
00190 double threshold) = 0;
00191
00195 inline virtual void
00196 setInputCloud (const PointCloudConstPtr &cloud)
00197 {
00198 input_ = cloud;
00199 if (!indices_)
00200 indices_ = boost::make_shared <std::vector<int> > ();
00201 if (indices_->empty ())
00202 {
00203
00204 indices_->resize (cloud->points.size ());
00205 for (size_t i = 0; i < cloud->points.size (); ++i)
00206 (*indices_)[i] = i;
00207 }
00208 }
00209
00211 inline PointCloudConstPtr
00212 getInputCloud () const { return (input_); }
00213
00217 inline void
00218 setIndices (const IndicesPtr &indices) { indices_ = indices; }
00219
00223 inline void
00224 setIndices (std::vector<int> &indices)
00225 {
00226 indices_ = boost::make_shared <std::vector<int> > (indices);
00227 }
00228
00230 inline IndicesPtr
00231 getIndices () const { return (indices_); }
00232
00234 virtual SacModel
00235 getModelType () const = 0;
00236
00238 inline unsigned int
00239 getSampleSize() const { return SAC_SAMPLE_SIZE.at (getModelType ()); }
00240
00247 inline void
00248 setRadiusLimits (const double &min_radius, const double &max_radius)
00249 {
00250 radius_min_ = min_radius;
00251 radius_max_ = max_radius;
00252 }
00253
00260 inline void
00261 getRadiusLimits (double &min_radius, double &max_radius)
00262 {
00263 min_radius = radius_min_;
00264 max_radius = radius_max_;
00265 }
00266
00267 friend class ProgressiveSampleConsensus<PointT>;
00268
00269 protected:
00273 virtual inline bool
00274 isModelValid (const Eigen::VectorXf &model_coefficients) = 0;
00275
00277 PointCloudConstPtr input_;
00278
00280 IndicesPtr indices_;
00281
00285 double radius_min_, radius_max_;
00286 };
00287
00291 template <typename PointT, typename PointNT>
00292 class SampleConsensusModelFromNormals
00293 {
00294 public:
00295 typedef typename pcl::PointCloud<PointNT>::ConstPtr PointCloudNConstPtr;
00296 typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudNPtr;
00297
00298 typedef boost::shared_ptr<SampleConsensusModelFromNormals> Ptr;
00299 typedef boost::shared_ptr<const SampleConsensusModelFromNormals> ConstPtr;
00300
00302 SampleConsensusModelFromNormals () : normal_distance_weight_ (0.0) {};
00303
00309 inline void
00310 setNormalDistanceWeight (double w) { normal_distance_weight_ = w; }
00311
00313 inline double
00314 getNormalDistanceWeight () { return (normal_distance_weight_); }
00315
00321 inline void
00322 setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00323
00325 inline PointCloudNConstPtr
00326 getInputNormals () { return (normals_); }
00327
00328 protected:
00332 double normal_distance_weight_;
00333
00337 PointCloudNConstPtr normals_;
00338 };
00339 }
00340
00341 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_H_