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_RMSAC_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_RMSAC_H_
00040
00041 #include "pcl/sample_consensus/rmsac.h"
00042
00044 template <typename PointT> bool
00045 pcl::RandomizedMEstimatorSampleConsensus<PointT>::computeModel (int debug_verbosity_level)
00046 {
00047
00048 if (threshold_ == DBL_MAX)
00049 {
00050 ROS_ERROR ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] No threshold set!");
00051 return (false);
00052 }
00053
00054 iterations_ = 0;
00055 double d_best_penalty = DBL_MAX;
00056 double k = 1.0;
00057
00058 std::vector<int> best_model;
00059 std::vector<int> selection;
00060 Eigen::VectorXf model_coefficients;
00061 std::vector<double> distances;
00062 std::set<int> indices_subset;
00063
00064 int n_inliers_count = 0;
00065
00066
00067 size_t fraction_nr_points = lrint (sac_model_->getIndices ()->size () * fraction_nr_pretest_ / 100.0);
00068
00069
00070 while (iterations_ < k)
00071 {
00072
00073 sac_model_->getSamples (iterations_, selection);
00074
00075 if (selection.empty ()) break;
00076
00077
00078 if (!sac_model_->computeModelCoefficients (selection, model_coefficients))
00079 {
00080
00081 continue;
00082 }
00083
00084
00085
00086 getRandomSamples (sac_model_->getIndices (), fraction_nr_points, indices_subset);
00087
00088 if (!sac_model_->doSamplesVerifyModel (indices_subset, model_coefficients, threshold_))
00089 {
00090
00091 if (k != 1.0)
00092 {
00093 ++iterations_;
00094 continue;
00095 }
00096 }
00097
00098 double d_cur_penalty = 0;
00099
00100 sac_model_->getDistancesToModel (model_coefficients, distances);
00101
00102 if (distances.empty () && k > 1.0)
00103 continue;
00104
00105 for (size_t i = 0; i < distances.size (); ++i)
00106 d_cur_penalty += (std::min) (distances[i], threshold_);
00107
00108
00109 if (d_cur_penalty < d_best_penalty)
00110 {
00111 d_best_penalty = d_cur_penalty;
00112
00113
00114 model_ = selection;
00115 model_coefficients_ = model_coefficients;
00116
00117 n_inliers_count = 0;
00118
00119 for (size_t i = 0; i < distances.size (); ++i)
00120 if (distances[i] <= threshold_)
00121 n_inliers_count++;
00122
00123
00124 double w = (double)((double)n_inliers_count / (double)sac_model_->getIndices ()->size ());
00125 double p_no_outliers = 1 - pow (w, (double)selection.size ());
00126 p_no_outliers = (std::max) (std::numeric_limits<double>::epsilon (), p_no_outliers);
00127 p_no_outliers = (std::min) (1 - std::numeric_limits<double>::epsilon (), p_no_outliers);
00128 k = log (1 - probability_) / log (p_no_outliers);
00129 }
00130
00131 ++iterations_;
00132 if (debug_verbosity_level > 1)
00133 ROS_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Trial %d out of %d. Best penalty is %f.", iterations_, (int)ceil (k), d_best_penalty);
00134 if (iterations_ > max_iterations_)
00135 {
00136 if (debug_verbosity_level > 0)
00137 ROS_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] MSAC reached the maximum number of trials.");
00138 break;
00139 }
00140 }
00141
00142 if (model_.empty ())
00143 {
00144 if (debug_verbosity_level > 0)
00145 ROS_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Unable to find a solution!");
00146 return (false);
00147 }
00148
00149
00150 sac_model_->getDistancesToModel (model_coefficients_, distances);
00151 std::vector<int> &indices = *sac_model_->getIndices ();
00152 if (distances.size () != indices.size ())
00153 {
00154 ROS_ERROR ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Estimated distances (%zu) differs than the normal of indices (%zu).", distances.size (), indices.size ());
00155 return (false);
00156 }
00157
00158 inliers_.resize (distances.size ());
00159
00160 n_inliers_count = 0;
00161 for (size_t i = 0; i < distances.size (); ++i)
00162 if (distances[i] <= threshold_)
00163 inliers_[n_inliers_count++] = indices[i];
00164
00165
00166 inliers_.resize (n_inliers_count);
00167
00168 if (debug_verbosity_level > 0)
00169 ROS_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Model: %zu size, %d inliers.", model_.size (), n_inliers_count);
00170
00171 return (true);
00172 }
00173
00174 #define PCL_INSTANTIATE_RandomizedMEstimatorSampleConsensus(T) template class pcl::RandomizedMEstimatorSampleConsensus<T>;
00175
00176 #endif // PCL_SAMPLE_CONSENSUS_IMPL_RMSAC_H_
00177