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 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_PROSAC_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_PROSAC_H_
00040
00041 #include <boost/math/distributions/binomial.hpp>
00042 #include <pcl/sample_consensus/prosac.h>
00043
00045
00046 template<typename PointT> bool
00047 pcl::ProgressiveSampleConsensus<PointT>::computeModel (int debug_verbosity_level)
00048 {
00049
00050 if (threshold_ == DBL_MAX)
00051 {
00052 PCL_ERROR ("[pcl::ProgressiveSampleConsensus::computeModel] No threshold set!\n");
00053 return (false);
00054 }
00055
00056
00057 const int T_N = 200000;
00058 const size_t N = sac_model_->indices_->size ();
00059 const size_t m = sac_model_->getSampleSize ();
00060 float T_n = static_cast<float> (T_N);
00061 for (unsigned int i = 0; i < m; ++i)
00062 T_n *= static_cast<float> (m - i) / static_cast<float> (N - i);
00063 float T_prime_n = 1.0f;
00064 size_t I_N_best = 0;
00065 float n = static_cast<float> (m);
00066
00067
00068 float n_star = static_cast<float> (N);
00069 float epsilon_n_star = 0.0;
00070 size_t k_n_star = T_N;
00071
00072
00073 std::vector<unsigned int> I_n_star_min (N);
00074
00075
00076 iterations_ = 0;
00077
00078 std::vector<int> inliers;
00079 std::vector<int> selection;
00080 Eigen::VectorXf model_coefficients;
00081
00082
00083 std::vector<int> index_pool;
00084 index_pool.reserve (N);
00085 for (unsigned int i = 0; i < n; ++i)
00086 index_pool.push_back (sac_model_->indices_->operator[](i));
00087
00088
00089 while (static_cast<unsigned int> (iterations_) < k_n_star)
00090 {
00091
00092
00093
00094
00095 if ((iterations_ == T_prime_n) && (n < n_star))
00096 {
00097
00098 ++n;
00099 if (n >= N)
00100 break;
00101 index_pool.push_back (sac_model_->indices_->at(static_cast<unsigned int> (n - 1)));
00102
00103 float T_n_minus_1 = T_n;
00104 T_n *= (static_cast<float>(n) + 1.0f) / (static_cast<float>(n) + 1.0f - static_cast<float>(m));
00105 T_prime_n += ceilf (T_n - T_n_minus_1);
00106 }
00107
00108
00109 sac_model_->indices_->swap (index_pool);
00110 selection.clear ();
00111 sac_model_->getSamples (iterations_, selection);
00112 if (T_prime_n < iterations_)
00113 {
00114 selection.pop_back ();
00115 selection.push_back (sac_model_->indices_->at(static_cast<unsigned int> (n - 1)));
00116 }
00117
00118
00119 sac_model_->indices_->swap (index_pool);
00120
00121 if (selection.empty ())
00122 {
00123 PCL_ERROR ("[pcl::ProgressiveSampleConsensus::computeModel] No samples could be selected!\n");
00124 break;
00125 }
00126
00127
00128 if (!sac_model_->computeModelCoefficients (selection, model_coefficients))
00129 {
00130 ++iterations_;
00131 continue;
00132 }
00133
00134
00135 inliers.clear ();
00136 sac_model_->selectWithinDistance (model_coefficients, threshold_, inliers);
00137
00138 size_t I_N = inliers.size ();
00139
00140
00141 if (I_N > I_N_best)
00142 {
00143 I_N_best = I_N;
00144
00145
00146 inliers_ = inliers;
00147 model_ = selection;
00148 model_coefficients_ = model_coefficients;
00149
00150
00151 std::sort (inliers.begin (), inliers.end ());
00152
00153
00154
00155 size_t possible_n_star_best = N, I_possible_n_star_best = I_N;
00156 float epsilon_possible_n_star_best = static_cast<float>(I_possible_n_star_best) / static_cast<float>(possible_n_star_best);
00157
00158
00159 size_t I_possible_n_star = I_N;
00160 for (std::vector<int>::const_reverse_iterator last_inlier = inliers.rbegin (),
00161 inliers_end = inliers.rend ();
00162 last_inlier != inliers_end;
00163 ++last_inlier, --I_possible_n_star)
00164 {
00165
00166 unsigned int possible_n_star = (*last_inlier) + 1;
00167 if (possible_n_star <= m)
00168 break;
00169
00170
00171 float epsilon_possible_n_star = static_cast<float>(I_possible_n_star) / static_cast<float>(possible_n_star);
00172
00173 if ((epsilon_possible_n_star > epsilon_n_star) && (epsilon_possible_n_star > epsilon_possible_n_star_best))
00174 {
00175 using namespace boost::math;
00176
00177 size_t I_possible_n_star_min = m
00178 + static_cast<size_t> (ceil (quantile (complement (binomial_distribution<float>(static_cast<float> (possible_n_star), 0.1f), 0.05))));
00179
00180 if (I_possible_n_star < I_possible_n_star_min)
00181 break;
00182
00183 possible_n_star_best = possible_n_star;
00184 I_possible_n_star_best = I_possible_n_star;
00185 epsilon_possible_n_star_best = epsilon_possible_n_star;
00186 }
00187 }
00188
00189
00190 if (epsilon_possible_n_star_best > epsilon_n_star)
00191 {
00192
00193 epsilon_n_star = epsilon_possible_n_star_best;
00194
00195
00196 float bottom_log = 1 - std::pow (epsilon_n_star, static_cast<float>(m));
00197 if (bottom_log == 0)
00198 k_n_star = 1;
00199 else if (bottom_log == 1)
00200 k_n_star = T_N;
00201 else
00202 k_n_star = static_cast<int> (ceil (log (0.05) / log (bottom_log)));
00203
00204 k_n_star = (std::max)(k_n_star, 2 * m);
00205 }
00206 }
00207
00208 ++iterations_;
00209 if (debug_verbosity_level > 1)
00210 PCL_DEBUG ("[pcl::ProgressiveSampleConsensus::computeModel] Trial %d out of %d: %d inliers (best is: %d so far).\n", iterations_, k_n_star, I_N, I_N_best);
00211 if (iterations_ > max_iterations_)
00212 {
00213 if (debug_verbosity_level > 0)
00214 PCL_DEBUG ("[pcl::ProgressiveSampleConsensus::computeModel] RANSAC reached the maximum number of trials.\n");
00215 break;
00216 }
00217 }
00218
00219 if (debug_verbosity_level > 0)
00220 PCL_DEBUG ("[pcl::ProgressiveSampleConsensus::computeModel] Model: %zu size, %d inliers.\n", model_.size (), I_N_best);
00221
00222 if (model_.empty ())
00223 {
00224 inliers_.clear ();
00225 return (false);
00226 }
00227
00228
00229
00230 return (true);
00231 }
00232
00233 #define PCL_INSTANTIATE_ProgressiveSampleConsensus(T) template class PCL_EXPORTS pcl::ProgressiveSampleConsensus<T>;
00234
00235 #endif // PCL_SAMPLE_CONSENSUS_IMPL_PROSAC_H_