mlesac.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/mlesac.h>
00036 #include <door_handle_detector/geometry/statistics.h>
00037 
00038 namespace sample_consensus
00039 {
00041 
00045   MLESAC::MLESAC (SACModel *model, double threshold) : SAC (model)
00046   {
00047     this->threshold_      = threshold;
00048     // Desired probability of choosing at least one sample free from outliers
00049     this->probability_    = 0.99;
00050     // Maximum number of trials before we give up.
00051     this->max_iterations_ = 10000;
00052 
00053     // Max number of EM (Expectation Maximization) iterations
00054     this->iterations_EM_  = 3;
00055     this->iterations_     = 0;
00056   }
00057 
00059 
00062   MLESAC::MLESAC (SACModel* model) : SAC (model) { }
00063 
00065 
00068   bool
00069     MLESAC::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     // Compute sigma - remember to set threshold_ correctly !
00084     sigma_ = cloud_geometry::statistics::computeMedianAbsoluteDeviation (*sac_model_->getCloud (), *sac_model_->getIndices (), threshold_);
00085     if (debug)
00086       std::cerr << "[MLESAC::computeModel] Estimated sigma value : " << sigma_ << "." << std::endl;
00087 
00088     // Compute the bounding box diagonal: V = sqrt (sum (max(pointCloud) - min(pointCloud)^2))
00089     geometry_msgs::Point32 min_pt, max_pt;
00090     cloud_geometry::statistics::getMinMax (*sac_model_->getCloud (), *sac_model_->getIndices (), min_pt, max_pt);
00091 
00092     double v = sqrt ( (max_pt.x - min_pt.x) * (max_pt.x - min_pt.x) +
00093                       (max_pt.y - min_pt.y) * (max_pt.y - min_pt.y) +
00094                       (max_pt.z - min_pt.z) * (max_pt.z - min_pt.z)
00095                     );
00096 
00097 
00098     // Iterate
00099     while (iterations_ < k)
00100     {
00101       // Get X samples which satisfy the model criteria
00102       sac_model_->getSamples (iterations_, selection);
00103 
00104       if (selection.size () == 0) break;
00105 
00106       // Search for inliers in the point cloud for the current plane model M
00107       sac_model_->computeModelCoefficients (selection);
00108 
00109       // Iterate through the 3d points and calculate the distances from them to the model
00110       sac_model_->getDistancesToModel (sac_model_->getModelCoefficients (), distances);
00111       if (distances.size () == 0 && k != 1.0)
00112       {
00113         iterations_ += 1;
00114         continue;
00115       }
00116 
00117       // Use Expectiation-Maximization to find out the right value for d_cur_penalty
00118       // ---[ Initial estimate for the gamma mixing parameter = 1/2
00119       double gamma = 0.5;
00120       double p_outlier_prob = 0;
00121 
00122       std::vector<double> p_inlier_prob (sac_model_->getIndices ()->size ());
00123       for (int j = 0; j < iterations_EM_; j++)
00124       {
00125         // Likelihood of a datum given that it is an inlier
00126         for (unsigned int i = 0; i < sac_model_->getIndices ()->size (); i++)
00127           p_inlier_prob[i] = gamma * exp (- (distances.at (i) * distances.at (i) ) / 2 * (sigma_ * sigma_) ) /
00128                              (sqrt (2 * M_PI) * sigma_);
00129 
00130         // Likelihood of a datum given that it is an outlier
00131         p_outlier_prob = (1 - gamma) / v;
00132 
00133         gamma = 0;
00134         for (unsigned int i = 0; i < sac_model_->getIndices ()->size (); i++)
00135           gamma += p_inlier_prob [i] / (p_inlier_prob[i] + p_outlier_prob);
00136         gamma /= sac_model_->getIndices ()->size ();
00137       }
00138 
00139       // Find the log likelihood of the model -L = -sum [log (pInlierProb + pOutlierProb)]
00140       double d_cur_penalty = 0;
00141       for (unsigned int i = 0; i < sac_model_->getIndices ()->size (); i++)
00142         d_cur_penalty += log (p_inlier_prob[i] + p_outlier_prob);
00143       d_cur_penalty = - d_cur_penalty;
00144 
00145       // Better match ?
00146       if (d_cur_penalty < d_best_penalty)
00147       {
00148         d_best_penalty = d_cur_penalty;
00149         best_model = selection;
00150 
00151         // Save the inliers
00152         best_inliers.resize (sac_model_->getIndices ()->size ());
00153         n_inliers_count = 0;
00154         for (unsigned int i = 0; i < sac_model_->getIndices ()->size (); i++)
00155         {
00156           if (distances[i] <= 2 * sigma_)
00157           {
00158             best_inliers[n_inliers_count] = sac_model_->getIndices ()->at (i);
00159             n_inliers_count++;
00160           }
00161         }
00162         best_inliers.resize (n_inliers_count);
00163 
00164         // Compute the k parameter (k=log(z)/log(1-w^n))
00165         double w = (double)((double)n_inliers_count / (double)sac_model_->getIndices ()->size ());
00166         double p_no_outliers = 1 - pow (w, (double)selection.size ());
00167         p_no_outliers = std::max (std::numeric_limits<double>::epsilon (), p_no_outliers);       // Avoid division by -Inf
00168         p_no_outliers = std::min (1 - std::numeric_limits<double>::epsilon (), p_no_outliers);   // Avoid division by 0
00169         k = log (1 - probability_) / log (p_no_outliers);
00170       }
00171 
00172       iterations_ += 1;
00173       if (debug > 1)
00174         std::cerr << "[MLESAC::computeModel] Trial " << iterations_ << " out of " << ceil (k) << ": best number of inliers so far is " << best_inliers.size () << "." << std::endl;
00175       if (iterations_ > max_iterations_)
00176       {
00177         if (debug > 0)
00178           std::cerr << "[MLESAC::computeModel] MSAC reached the maximum number of trials." << std::endl;
00179         break;
00180       }
00181     }
00182 
00183     if (best_model.size () != 0)
00184     {
00185       if (debug > 0)
00186         std::cerr << "[MLESAC::computeModel] Model found: " << best_inliers.size () << " inliers." << std::endl;
00187       sac_model_->setBestModel (best_model);
00188       sac_model_->setBestInliers (best_inliers);
00189       return (true);
00190     }
00191     else
00192       if (debug > 0)
00193         std::cerr << "[MLESAC::computeModel] Unable to find a solution!" << std::endl;
00194     return (false);
00195   }
00196 }


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