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$
00028  *
00029  */
00030 
00033 #ifndef _SAMPLE_CONSENSUS_SACMODEL_H_
00034 #define _SAMPLE_CONSENSUS_SACMODEL_H_
00035 
00036 #include <geometry_msgs/Point32.h>     // ROS float point type
00037 #include <sensor_msgs/PointCloud.h>  // ROS point cloud type
00038 
00039 #include <set>
00040 
00041 namespace sample_consensus
00042 {
00043   class SACModel
00044   {
00045     public:
00047 
00048       SACModel () : cloud_(NULL) { }
00049       SACModel (sensor_msgs::PointCloud cloud) : cloud_(&cloud) { }
00050 
00052 
00053       virtual ~SACModel () { }
00054 
00056 
00060       virtual void getSamples (int &iterations, std::vector<int> &samples) = 0;
00061 
00063 
00066       virtual bool testModelCoefficients (const std::vector<double> &model_coefficients) = 0;
00067 
00069 
00073       virtual bool computeModelCoefficients (const std::vector<int> &samples) = 0;
00074 
00076 
00081       virtual void refitModel (const std::vector<int> &inliers, std::vector<double> &refit_coefficients) = 0;
00082 
00084 
00088       virtual void getDistancesToModel (const std::vector<double> &model_coefficients, std::vector<double> &distances) = 0;
00089 
00091 
00098       virtual void selectWithinDistance (const std::vector<double> &model_coefficients, double threshold, std::vector<int> &inliers) = 0;
00099 
00101 
00106       virtual void projectPoints (const std::vector<int> &inliers, const std::vector<double> &model_coefficients, sensor_msgs::PointCloud &projected_points) = 0;
00107 
00109 
00113       virtual void projectPointsInPlace (const std::vector<int> &inliers, const std::vector<double> &model_coefficients) = 0;
00114 
00116 
00120       virtual bool doSamplesVerifyModel (const std::set<int> &indices, double threshold) = 0;
00121 
00122 
00124 
00126       inline void
00127         setDataSet (sensor_msgs::PointCloud *cloud)
00128       {
00129         this->cloud_ = cloud;
00130         indices_.clear ();
00131         indices_.resize (cloud_->points.size ());
00132         for (unsigned int i = 0; i < cloud_->points.size (); i++)
00133           indices_[i] = i;
00134       }
00136 
00139       inline void
00140         setDataSet (sensor_msgs::PointCloud *cloud, std::vector<int> indices)
00141       {
00142         this->cloud_   = cloud;
00143         this->indices_ = indices;
00144       }
00146 
00148       void setDataIndices (std::vector<int> indices) { this->indices_ = indices; }
00149 
00151 
00152       virtual int removeInliers ();
00153 
00155 
00156       virtual int getModelType () = 0;
00157 
00159 
00161       void setBestInliers (const std::vector<int> &best_inliers) { this->best_inliers_ = best_inliers; }
00162 
00164 
00165       std::vector<int> getBestInliers () { return (this->best_inliers_); }
00166 
00168 
00170       void setBestModel (std::vector<int> best_model) { this->best_model_ = best_model; }
00171 
00173 
00174       std::vector<int> getBestModel   () { return (this->best_model_); }
00175 
00177 
00178       std::vector<double> getModelCoefficients () { return (this->model_coefficients_); }
00179 
00181       sensor_msgs::PointCloud* getCloud () { return (this->cloud_); }
00182 
00184       std::vector<int>* getIndices () { return (&this->indices_); }
00185 
00186     protected:
00187 
00189       sensor_msgs::PointCloud *cloud_;
00190 
00192       std::vector<int> indices_;
00193 
00195       std::vector<double> model_coefficients_;
00196 
00198       std::vector<int> best_model_;
00200       std::vector<int> best_inliers_;
00201   };
00202 }
00203 
00204 #endif


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