sac.h
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: sac.h 28027 2009-12-21 01:08:19Z rusu $
00028  *
00029  */
00030 
00033 #ifndef _SAMPLE_CONSENSUS_SAC_H_
00034 #define _SAMPLE_CONSENSUS_SAC_H_
00035 
00036 #include <pcl_ros/point_cloud.h>
00037 #include <pcl/point_types.h>
00038 
00039 #include <stdlib.h>
00040 #include <sac_model.h>
00041 
00042 namespace sample_consensus
00043 {
00044   class SAC
00045   {
00046     public:
00047 
00049 
00050       SAC ()
00051       {
00052         //srand ((unsigned)time (0)); // set a random seed
00053       };
00054 
00056 
00059       SAC (SACModel *model) : sac_model_(model)
00060       {
00061         //srand ((unsigned)time (0)); // set a random seed
00062       };
00063 
00065 
00066       virtual ~SAC () { }
00067 
00069 
00072       virtual inline void
00073         setThreshold (double threshold)
00074       {
00075         this->threshold_ = threshold;
00076       }
00077 
00079 
00082       virtual inline void
00083         setMaxIterations (int max_iterations)
00084       {
00085         this->max_iterations_ = max_iterations;
00086       }
00087 
00089 
00092       virtual inline void
00093         setProbability (double probability)
00094       {
00095         this->probability_ = probability;
00096       }
00097 
00099 
00100       virtual bool computeModel (int debug = 0) = 0;
00101 
00103 
00104       virtual void
00105         computeCoefficients (std::vector<double> &coefficients)
00106       {
00107         sac_model_->computeModelCoefficients (sac_model_->getBestModel ());
00108         coefficients = sac_model_->getModelCoefficients ();
00109       }
00110 
00112 
00115       virtual void
00116         refineCoefficients (std::vector<double> &refined_coefficients)
00117       {
00118         sac_model_->refitModel (sac_model_->getBestInliers (), refined_coefficients);
00119       }
00120 
00122 
00123       virtual int removeInliers () { return (sac_model_->removeInliers ()); }
00124 
00126 
00127       virtual std::vector<int>
00128         getInliers ()
00129       {
00130         return (sac_model_->getBestInliers ());
00131       }
00132 
00134 
00137       PointCloud getPointCloud (std::vector<int> indices);
00138 
00140 
00145       virtual void
00146         projectPointsToModel (const std::vector<int> &indices, const std::vector<double> &model_coefficients,
00147                               PointCloud &projected_points)
00148       {
00149         sac_model_->projectPoints (indices, model_coefficients, projected_points);
00150       }
00151 
00152 
00154 
00160       std::set<int>
00161         getRandomSamples (PointCloud points, int nr_samples)
00162       {
00163         std::set<int> random_idx;
00164         for (int i = 0; i < nr_samples; i++)
00165           random_idx.insert ((int) (points.points.size () * (rand () / (RAND_MAX + 1.0))));
00166         return (random_idx);
00167       }
00168 
00170 
00177       std::set<int>
00178         getRandomSamples (PointCloud points, std::vector<int> indices, int nr_samples)
00179       {
00180         std::set<int> random_idx;
00181         for (int i = 0; i < nr_samples; i++)
00182           random_idx.insert ((int) (indices.size () * (rand () / (RAND_MAX + 1.0))));
00183         return (random_idx);
00184       }
00185 
00186     protected:
00188       SACModel *sac_model_;
00189 
00191       double probability_;
00192 
00194       int iterations_;
00195 
00197       int max_iterations_;
00198 
00200       double threshold_;
00201   };
00202 }
00203 
00204 #endif


semantic_point_annotator
Author(s): Radu Bogdan Rusu
autogenerated on Fri Apr 5 2019 02:18:42