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