rmsac.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008 Radu Bogdan Rusu <rusu -=- cs.tum.edu>
00003  *
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  *
00027  * $Id$
00028  *
00029  */
00030 
00033 #include <cfloat>
00034 #include <limits>
00035 #include <door_handle_detector/sample_consensus/rmsac.h>
00036 
00037 namespace sample_consensus
00038 {
00040 
00044   RMSAC::RMSAC (SACModel *model, double threshold) : SAC (model)
00045   {
00046     this->threshold_ = threshold;
00047     // Desired probability of choosing at least one sample free from outliers
00048     this->probability_    = 0.99;
00049     // Maximum number of trials before we give up.
00050     this->max_iterations_ = 10000;
00051 
00052     this->iterations_ = 0;
00053 
00054     // Number of samples to try randomly in percents
00055     fraction_nr_pretest_ = 10;
00056   }
00057 
00059 
00062   RMSAC::RMSAC (SACModel* model) : SAC (model) { }
00063 
00065 
00068   bool
00069     RMSAC::computeModel (int debug)
00070   {
00071     iterations_ = 0;
00072     double d_best_penalty = DBL_MAX;
00073 
00074     double k = 1.0;
00075 
00076     std::vector<int> best_model;
00077     std::vector<int> best_inliers, inliers;
00078     std::vector<int> selection;
00079     std::vector<double> distances;
00080 
00081     int n_inliers_count = 0;
00082 
00083     // Number of samples to try randomly in percents
00084     int fraction_nr_points = lrint (sac_model_->getIndices ()->size () * fraction_nr_pretest_ / 100.0);
00085 
00086     // Iterate
00087     while (iterations_ < k)
00088     {
00089       // Get X samples which satisfy the model criteria
00090       sac_model_->getSamples (iterations_, selection);
00091 
00092       if (selection.size () == 0) break;
00093 
00094       // Search for inliers in the point cloud for the current plane model M
00095       sac_model_->computeModelCoefficients (selection);
00096 
00097       // RMSAC addon: verify a random fraction of the data
00098       // Get X random samples which satisfy the model criteria
00099       std::set<int> fraction_idx = getRandomSamples (*sac_model_->getCloud (), *sac_model_->getIndices (), fraction_nr_points);
00100 
00101       if (!sac_model_->doSamplesVerifyModel (fraction_idx, threshold_))
00102       {
00103         // Unfortunately we cannot "continue" after the first iteration, because k might not be set, while iterations gets incremented
00104         if (k != 1.0)
00105         {
00106           iterations_ += 1;
00107           continue;
00108         }
00109       }
00110 
00111       double d_cur_penalty = 0;
00112       // d_cur_penalty = sum (min (dist, threshold))
00113 
00114       // Iterate through the 3d points and calculate the distances from them to the model
00115       sac_model_->getDistancesToModel (sac_model_->getModelCoefficients (), distances);
00116       if (distances.size () == 0 && k != 1.0)
00117       {
00118         iterations_ += 1;
00119         continue;
00120       }
00121 
00122       for (unsigned int i = 0; i < sac_model_->getIndices ()->size (); i++)
00123         d_cur_penalty += std::min ((double)distances[i], threshold_);
00124 
00125       // Better match ?
00126       if (d_cur_penalty < d_best_penalty)
00127       {
00128         d_best_penalty = d_cur_penalty;
00129         best_model = selection;
00130 
00131         // Save the inliers
00132         best_inliers.resize (sac_model_->getIndices ()->size ());
00133         n_inliers_count = 0;
00134         for (unsigned int i = 0; i < sac_model_->getIndices ()->size (); i++)
00135         {
00136           if (distances[i] <= threshold_)
00137           {
00138             best_inliers[n_inliers_count] = sac_model_->getIndices ()->at (i);
00139             n_inliers_count++;
00140           }
00141         }
00142         best_inliers.resize (n_inliers_count);
00143 
00144         // Compute the k parameter (k=log(z)/log(1-w^n))
00145         double w = (double)((double)n_inliers_count / (double)sac_model_->getIndices ()->size ());
00146         double p_no_outliers = 1 - pow (w, (double)selection.size ());
00147         p_no_outliers = std::max (std::numeric_limits<double>::epsilon (), p_no_outliers);       // Avoid division by -Inf
00148         p_no_outliers = std::min (1 - std::numeric_limits<double>::epsilon (), p_no_outliers);   // Avoid division by 0
00149         k = log (1 - probability_) / log (p_no_outliers);
00150       }
00151 
00152       iterations_ += 1;
00153       if (debug > 1)
00154         std::cerr << "[RMSAC::computeModel] Trial " << iterations_ << " out of " << ceil (k) << ": best number of inliers so far is " << best_inliers.size () << "." << std::endl;
00155       if (iterations_ > max_iterations_)
00156       {
00157         if (debug > 0)
00158           std::cerr << "[RMSAC::computeModel] MSAC reached the maximum number of trials." << std::endl;
00159         break;
00160       }
00161     }
00162 
00163     if (best_model.size () != 0)
00164     {
00165       if (debug > 0)
00166         std::cerr << "[RMSAC::computeModel] Model found: " << best_inliers.size () << " inliers." << std::endl;
00167       sac_model_->setBestModel (best_model);
00168       sac_model_->setBestInliers (best_inliers);
00169       return (true);
00170     }
00171     else
00172       if (debug > 0)
00173         std::cerr << "[RMSAC::computeModel] Unable to find a solution!" << std::endl;
00174     return (false);
00175   }
00176 
00178 
00181   void
00182     RMSAC::setFractionNrPretest (int nr_pretest)
00183   {
00184     fraction_nr_pretest_ = nr_pretest;
00185   }
00186 }


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Wed Dec 11 2013 14:17:01