sac_model.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_model.h 21050 2009-08-07 21:24:30Z jfaustwg $
00028  *
00029  */
00030 
00033 #ifndef _SAMPLE_CONSENSUS_SACMODEL_H_
00034 #define _SAMPLE_CONSENSUS_SACMODEL_H_
00035 
00036 #include <pcl_ros/point_cloud.h>
00037 #include <pcl/point_types.h>
00038 
00039 #include <set>
00040 
00041 namespace sample_consensus
00042 {
00043   typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00044 
00045   class SACModel
00046   {
00047     public:
00049 
00050       SACModel () : cloud_(NULL) { }
00051       SACModel (PointCloud cloud) : cloud_(&cloud) { }
00052 
00054 
00055       virtual ~SACModel () { }
00056 
00058 
00062       virtual void getSamples (int &iterations, std::vector<int> &samples) = 0;
00063 
00065 
00068       virtual bool testModelCoefficients (const std::vector<double> &model_coefficients) = 0;
00069 
00071 
00075       virtual bool computeModelCoefficients (const std::vector<int> &samples) = 0;
00076 
00078 
00083       virtual void refitModel (const std::vector<int> &inliers, std::vector<double> &refit_coefficients) = 0;
00084 
00086 
00090       virtual void getDistancesToModel (const std::vector<double> &model_coefficients, std::vector<double> &distances) = 0;
00091 
00093 
00100       virtual void selectWithinDistance (const std::vector<double> &model_coefficients, double threshold, std::vector<int> &inliers) = 0;
00101 
00103 
00108       virtual void projectPoints (const std::vector<int> &inliers, const std::vector<double> &model_coefficients, PointCloud &projected_points) = 0;
00109 
00111 
00115       virtual void projectPointsInPlace (const std::vector<int> &inliers, const std::vector<double> &model_coefficients) = 0;
00116 
00118 
00122       virtual bool doSamplesVerifyModel (const std::set<int> &indices, double threshold) = 0;
00123 
00124 
00126 
00128       inline void
00129         setDataSet (PointCloud *cloud)
00130       {
00131         this->cloud_ = cloud;
00132         indices_.clear ();
00133         indices_.resize (cloud_->points.size ());
00134         for (unsigned int i = 0; i < cloud_->points.size (); i++)
00135           indices_[i] = i;
00136       }
00138 
00141       inline void
00142         setDataSet (PointCloud *cloud, std::vector<int> indices)
00143       {
00144         this->cloud_   = cloud;
00145         this->indices_ = indices;
00146       }
00148 
00150       void setDataIndices (std::vector<int> indices) { this->indices_ = indices; }
00151 
00153 
00154       virtual int removeInliers ();
00155 
00157 
00158       virtual int getModelType () = 0;
00159 
00161 
00163       void setBestInliers (const std::vector<int> &best_inliers) { this->best_inliers_ = best_inliers; }
00164 
00166 
00167       std::vector<int> getBestInliers () { return (this->best_inliers_); }
00168 
00170 
00172       void setBestModel (std::vector<int> best_model) { this->best_model_ = best_model; }
00173 
00175 
00176       std::vector<int> getBestModel   () { return (this->best_model_); }
00177 
00179 
00180       std::vector<double> getModelCoefficients () { return (this->model_coefficients_); }
00181 
00183       PointCloud* getCloud () { return (this->cloud_); }
00184 
00186       std::vector<int>* getIndices () { return (&this->indices_); }
00187 
00188     protected:
00189 
00191       PointCloud *cloud_;
00192 
00194       std::vector<int> indices_;
00195 
00197       std::vector<double> model_coefficients_;
00198 
00200       std::vector<int> best_model_;
00202       std::vector<int> best_inliers_;
00203   };
00204 }
00205 
00206 #endif


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