rransac.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 <limits>
00034 #include <door_handle_detector/sample_consensus/rransac.h>
00035 
00036 namespace sample_consensus
00037 {
00039 
00043   RRANSAC::RRANSAC (SACModel *model, double threshold) : SAC (model)
00044   {
00045     this->threshold_ = threshold;
00046     // Desired probability of choosing at least one sample free from outliers
00047     this->probability_    = 0.99;
00048     // Maximum number of trials before we give up.
00049     this->max_iterations_ = 10000;
00050 
00051     this->iterations_ = 0;
00052 
00053     // Number of samples to try randomly in percents
00054     fraction_nr_pretest_ = 10;
00055   }
00056 
00058 
00061   RRANSAC::RRANSAC (SACModel* model) : SAC (model) { }
00062 
00064 
00067   bool
00068     RRANSAC::computeModel (int debug)
00069   {
00070     iterations_ = 0;
00071     int n_best_inliers_count = -INT_MAX;
00072     double k = 1.0;
00073 
00074     std::vector<int> best_model;
00075     std::vector<int> best_inliers, inliers;
00076     std::vector<int> selection;
00077 
00078     int n_inliers_count = 0;
00079 
00080     // Number of samples to try randomly in percents
00081     int fraction_nr_points = lrint (sac_model_->getIndices ()->size () * fraction_nr_pretest_ / 100.0);
00082 
00083     // Iterate
00084     while (iterations_ < k)
00085     {
00086       // Get X samples which satisfy the model criteria
00087       sac_model_->getSamples (iterations_, selection);
00088 
00089       if (selection.size () == 0) break;
00090 
00091       // Search for inliers in the point cloud for the current plane model M
00092       sac_model_->computeModelCoefficients (selection);
00093 
00094       // RRANSAC addon: verify a random fraction of the data
00095       // Get X random samples which satisfy the model criteria
00096       std::set<int> fraction_idx = getRandomSamples (*sac_model_->getCloud (), *sac_model_->getIndices (), fraction_nr_points);
00097 
00098       if (!sac_model_->doSamplesVerifyModel (fraction_idx, threshold_))
00099       {
00100         // Unfortunately we cannot "continue" after the first iteration, because k might not be set, while iterations gets incremented
00101         if (k != 1.0)
00102         {
00103           iterations_ += 1;
00104           continue;
00105         }
00106       }
00107 
00108       sac_model_->selectWithinDistance (sac_model_->getModelCoefficients (), threshold_, inliers);
00109       n_inliers_count = inliers.size ();
00110 
00111       // Better match ?
00112       if (n_inliers_count > n_best_inliers_count)
00113       {
00114         n_best_inliers_count = n_inliers_count;
00115         best_inliers = inliers;
00116         //inliers.clear ();
00117         best_model = selection;
00118 
00119         // Compute the k parameter (k=log(z)/log(1-w^n))
00120         double w = (double)((double)n_inliers_count / (double)sac_model_->getIndices ()->size ());
00121         double p_no_outliers = 1 - pow (w, (double)selection.size ());
00122         p_no_outliers = std::max (std::numeric_limits<double>::epsilon (), p_no_outliers);       // Avoid division by -Inf
00123         p_no_outliers = std::min (1 - std::numeric_limits<double>::epsilon (), p_no_outliers);   // Avoid division by 0.
00124         k = log (1 - probability_) / log (p_no_outliers);
00125       }
00126 
00127       iterations_ += 1;
00128       if (debug > 1)
00129         std::cerr << "[RRANSAC::computeModel] Trial " << iterations_ << " out of " << ceil (k) << ": " << n_inliers_count << " inliers (best is: " << n_best_inliers_count << " so far)." << std::endl;
00130       if (iterations_ > max_iterations_)
00131       {
00132         if (debug > 0)
00133           std::cerr << "[RRANSAC::computeModel] RANSAC reached the maximum number of trials." << std::endl;
00134         break;
00135       }
00136     }
00137 
00138     if (best_model.size () != 0)
00139     {
00140       if (debug > 0)
00141         std::cerr << "[RRANSAC::computeModel] Model found: " << n_best_inliers_count << " inliers." << std::endl;
00142       sac_model_->setBestModel (best_model);
00143       sac_model_->setBestInliers (best_inliers);
00144       return (true);
00145     }
00146     else
00147       if (debug > 0)
00148         std::cerr << "[RRANSAC::computeModel] Unable to find a solution!" << std::endl;
00149     return (false);
00150   }
00151 
00153 
00156   void
00157     RRANSAC::setFractionNrPretest (int nr_pretest)
00158   {
00159     fraction_nr_pretest_ = nr_pretest;
00160   }
00161 
00162 }


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