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 #ifndef PCL_SAMPLE_CONSENSUS_H_
00041 #define PCL_SAMPLE_CONSENSUS_H_
00042
00043 #include <pcl/sample_consensus/sac_model.h>
00044 #include <boost/random.hpp>
00045 #include <ctime>
00046 #include <set>
00047
00048 namespace pcl
00049 {
00054 template <typename T>
00055 class SampleConsensus
00056 {
00057 typedef typename SampleConsensusModel<T>::Ptr SampleConsensusModelPtr;
00058
00059 private:
00061 SampleConsensus () {};
00062
00063 public:
00064 typedef boost::shared_ptr<SampleConsensus> Ptr;
00065 typedef boost::shared_ptr<const SampleConsensus> ConstPtr;
00066
00071 SampleConsensus (const SampleConsensusModelPtr &model, bool random = false) :
00072 sac_model_ (model),
00073 model_ (),
00074 inliers_ (),
00075 model_coefficients_ (),
00076 probability_ (0.99),
00077 iterations_ (0),
00078 threshold_ (std::numeric_limits<double>::max()),
00079 max_iterations_ (1000),
00080 rng_alg_ (),
00081 rng_ (new boost::uniform_01<boost::mt19937> (rng_alg_))
00082 {
00083
00084 if (random)
00085 rng_->base ().seed (static_cast<unsigned> (std::time(0)));
00086 else
00087 rng_->base ().seed (12345u);
00088 };
00089
00095 SampleConsensus (const SampleConsensusModelPtr &model, double threshold, bool random = false) :
00096 sac_model_ (model),
00097 model_ (),
00098 inliers_ (),
00099 model_coefficients_ (),
00100 probability_ (0.99),
00101 iterations_ (0),
00102 threshold_ (threshold),
00103 max_iterations_ (1000),
00104 rng_alg_ (),
00105 rng_ (new boost::uniform_01<boost::mt19937> (rng_alg_))
00106 {
00107
00108 if (random)
00109 rng_->base ().seed (static_cast<unsigned> (std::time(0)));
00110 else
00111 rng_->base ().seed (12345u);
00112 };
00113
00115 virtual ~SampleConsensus () {};
00116
00120 inline void
00121 setDistanceThreshold (double threshold) { threshold_ = threshold; }
00122
00124 inline double
00125 getDistanceThreshold () { return (threshold_); }
00126
00130 inline void
00131 setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; }
00132
00134 inline int
00135 getMaxIterations () { return (max_iterations_); }
00136
00141 inline void
00142 setProbability (double probability) { probability_ = probability; }
00143
00145 inline double
00146 getProbability () { return (probability_); }
00147
00149 virtual bool
00150 computeModel (int debug_verbosity_level = 0) = 0;
00151
00157 inline void
00158 getRandomSamples (const boost::shared_ptr <std::vector<int> > &indices,
00159 size_t nr_samples,
00160 std::set<int> &indices_subset)
00161 {
00162 indices_subset.clear ();
00163 while (indices_subset.size () < nr_samples)
00164
00165 indices_subset.insert ((*indices)[static_cast<int> (static_cast<double>(indices->size ()) * rnd ())]);
00166 }
00167
00171 inline void
00172 getModel (std::vector<int> &model) { model = model_; }
00173
00177 inline void
00178 getInliers (std::vector<int> &inliers) { inliers = inliers_; }
00179
00183 inline void
00184 getModelCoefficients (Eigen::VectorXf &model_coefficients) { model_coefficients = model_coefficients_; }
00185
00186 protected:
00188 SampleConsensusModelPtr sac_model_;
00189
00191 std::vector<int> model_;
00192
00194 std::vector<int> inliers_;
00195
00197 Eigen::VectorXf model_coefficients_;
00198
00200 double probability_;
00201
00203 int iterations_;
00204
00206 double threshold_;
00207
00209 int max_iterations_;
00210
00212 boost::mt19937 rng_alg_;
00213
00215 boost::shared_ptr<boost::uniform_01<boost::mt19937> > rng_;
00216
00218 inline double
00219 rnd ()
00220 {
00221 return ((*rng_) ());
00222 }
00223 };
00224 }
00225
00226 #endif //#ifndef PCL_SAMPLE_CONSENSUS_H_