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_H_
00039 #define PCL_SAMPLE_CONSENSUS_H_
00040
00041 #include "pcl/pcl_base.h"
00042 #include "pcl/sample_consensus/sac_model.h"
00043 #include <set>
00044
00045 namespace pcl
00046 {
00048
00052 template <typename T>
00053 class SampleConsensus
00054 {
00055 typedef typename SampleConsensusModel<T>::Ptr SampleConsensusModelPtr;
00056
00057 private:
00059 SampleConsensus () {};
00060
00061 public:
00062 typedef boost::shared_ptr<SampleConsensus> Ptr;
00063 typedef boost::shared_ptr<const SampleConsensus> ConstPtr;
00064
00068 SampleConsensus (const SampleConsensusModelPtr &model) : sac_model_(model), probability_ (0.99),
00069 iterations_ (0), threshold_ (DBL_MAX), max_iterations_ (1000)
00070 { };
00071
00076 SampleConsensus (const SampleConsensusModelPtr &model, double threshold) : sac_model_(model), probability_ (0.99),
00077 iterations_ (0), threshold_ (threshold),
00078 max_iterations_ (1000)
00079 {};
00080
00082
00083 virtual ~SampleConsensus () {};
00084
00088 inline void setDistanceThreshold (double threshold) { threshold_ = threshold; }
00089
00091 inline double getDistanceThreshold () { return (threshold_); }
00092
00096 inline void setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; }
00097
00099 inline int getMaxIterations () { return (max_iterations_); }
00100
00105 inline void setProbability (double probability) { probability_ = probability; }
00106
00108 inline double getProbability () { return (probability_); }
00109
00111 virtual bool computeModel (int debug_verbosity_level = 0) = 0;
00112
00118 inline void
00119 getRandomSamples (const IndicesPtr &indices, size_t nr_samples, std::set<int> &indices_subset)
00120 {
00121 indices_subset.clear ();
00122 while (indices_subset.size () < nr_samples)
00123 indices_subset.insert ((*indices)[(int) (indices->size () * (rand () / (RAND_MAX + 1.0)))]);
00124 }
00125
00129 inline void getModel (std::vector<int> &model) { model = model_; }
00130
00134 inline void getInliers (std::vector<int> &inliers) { inliers = inliers_; }
00135
00139 inline void getModelCoefficients (Eigen::VectorXf &model_coefficients) { model_coefficients = model_coefficients_; }
00140
00141 protected:
00143 SampleConsensusModelPtr sac_model_;
00144
00146 std::vector<int> model_;
00147
00149 std::vector<int> inliers_;
00150
00152 Eigen::VectorXf model_coefficients_;
00153
00155 double probability_;
00156
00158 int iterations_;
00159
00161 double threshold_;
00162
00164 int max_iterations_;
00165 };
00166 }
00167
00168 #endif //#ifndef PCL_SAMPLE_CONSENSUS_H_