Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00033 #ifndef _SAMPLE_CONSENSUS_SACMODEL_H_
00034 #define _SAMPLE_CONSENSUS_SACMODEL_H_
00035
00036 #include <geometry_msgs/Point32.h>
00037 #include <sensor_msgs/PointCloud.h>
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