sac.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008 Radu Bogdan Rusu <rusu -=- cs.tum.edu>
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  *
27  * $Id: sac.h 28027 2009-12-21 01:08:19Z rusu $
28  *
29  */
30 
33 #ifndef _SAMPLE_CONSENSUS_SAC_H_
34 #define _SAMPLE_CONSENSUS_SAC_H_
35 
36 #include <pcl_ros/point_cloud.h>
37 #include <pcl/point_types.h>
38 
39 #include <stdlib.h>
40 #include <sac_model.h>
41 
42 namespace sample_consensus
43 {
44  class SAC
45  {
46  public:
47 
49 
50  SAC ()
51  {
52  //srand ((unsigned)time (0)); // set a random seed
53  };
54 
56 
59  SAC (SACModel *model) : sac_model_(model)
60  {
61  //srand ((unsigned)time (0)); // set a random seed
62  };
63 
65 
66  virtual ~SAC () { }
67 
69 
72  virtual inline void
73  setThreshold (double threshold)
74  {
75  this->threshold_ = threshold;
76  }
77 
79 
82  virtual inline void
83  setMaxIterations (int max_iterations)
84  {
85  this->max_iterations_ = max_iterations;
86  }
87 
89 
92  virtual inline void
93  setProbability (double probability)
94  {
95  this->probability_ = probability;
96  }
97 
99 
100  virtual bool computeModel (int debug = 0) = 0;
101 
103 
104  virtual void
105  computeCoefficients (std::vector<double> &coefficients)
106  {
108  coefficients = sac_model_->getModelCoefficients ();
109  }
110 
112 
115  virtual void
116  refineCoefficients (std::vector<double> &refined_coefficients)
117  {
118  sac_model_->refitModel (sac_model_->getBestInliers (), refined_coefficients);
119  }
120 
122 
123  virtual int removeInliers () { return (sac_model_->removeInliers ()); }
124 
126 
127  virtual std::vector<int>
129  {
130  return (sac_model_->getBestInliers ());
131  }
132 
134 
137  PointCloud getPointCloud (std::vector<int> indices);
138 
140 
145  virtual void
146  projectPointsToModel (const std::vector<int> &indices, const std::vector<double> &model_coefficients,
147  PointCloud &projected_points)
148  {
149  sac_model_->projectPoints (indices, model_coefficients, projected_points);
150  }
151 
152 
154 
160  std::set<int>
161  getRandomSamples (PointCloud points, int nr_samples)
162  {
163  std::set<int> random_idx;
164  for (int i = 0; i < nr_samples; i++)
165  random_idx.insert ((int) (points.points.size () * (rand () / (RAND_MAX + 1.0))));
166  return (random_idx);
167  }
168 
170 
177  std::set<int>
178  getRandomSamples (PointCloud points, std::vector<int> indices, int nr_samples)
179  {
180  std::set<int> random_idx;
181  for (int i = 0; i < nr_samples; i++)
182  random_idx.insert ((int) (indices.size () * (rand () / (RAND_MAX + 1.0))));
183  return (random_idx);
184  }
185 
186  protected:
189 
191  double probability_;
192 
195 
198 
200  double threshold_;
201  };
202 }
203 
204 #endif
virtual int removeInliers()
Remove the inliers found from the initial set of given point indices.
Definition: sac_model.cpp:41
std::set< int > getRandomSamples(PointCloud points, std::vector< int > indices, int nr_samples)
Get a vector of randomly selected indices.
Definition: sac.h:178
std::set< int > getRandomSamples(PointCloud points, int nr_samples)
Get a set of randomly selected indices.
Definition: sac.h:161
std::vector< int > getBestInliers()
Return the best set of inliers found so far for this model.
Definition: sac_model.h:167
SAC()
Constructor for base SAC.
Definition: sac.h:50
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: sac_model.h:43
int max_iterations_
Maximum number of iterations before giving up.
Definition: sac.h:197
virtual void computeCoefficients(std::vector< double > &coefficients)
Compute the coefficients of the model and return them.
Definition: sac.h:105
virtual void projectPoints(const std::vector< int > &inliers, const std::vector< double > &model_coefficients, PointCloud &projected_points)=0
Create a new point cloud with inliers projected onto the model. Pure virtual.
double threshold_
Distance to model threshold.
Definition: sac.h:200
virtual void setProbability(double probability)
Set the desired probability of choosing at least one sample free from outliers.
Definition: sac.h:93
PointCloud getPointCloud(std::vector< int > indices)
Return the point cloud representing a set of given indices.
Definition: sac.cpp:41
virtual bool computeModelCoefficients(const std::vector< int > &samples)=0
Check whether the given index samples can form a valid model, compute the model coefficients from the...
SACModel * sac_model_
The underlying data model used (i.e. what is it that we attempt to search for).
Definition: sac.h:188
std::vector< int > getBestModel()
Return the best model found so far.
Definition: sac_model.h:176
SAC(SACModel *model)
Constructor for base SAC.
Definition: sac.h:59
virtual void setMaxIterations(int max_iterations)
Set the maximum number of iterations.
Definition: sac.h:83
int iterations_
Total number of internal loop iterations that we&#39;ve done so far.
Definition: sac.h:194
virtual bool computeModel(int debug=0)=0
Compute the actual model. Pure virtual.
virtual int removeInliers()
Remove the model inliers from the list of data indices. Returns the number of indices left...
Definition: sac.h:123
virtual void refitModel(const std::vector< int > &inliers, std::vector< double > &refit_coefficients)=0
Recompute the model coefficients using the given inlier set and return them to the user...
virtual void refineCoefficients(std::vector< double > &refined_coefficients)
Use Least-Squares optimizations to refine the coefficients of the model, and return them...
Definition: sac.h:116
virtual void projectPointsToModel(const std::vector< int > &indices, const std::vector< double > &model_coefficients, PointCloud &projected_points)
Project a set of given points (using their indices) onto the model and return their projections...
Definition: sac.h:146
virtual std::vector< int > getInliers()
Get a list of the model inliers, found after computeModel ()
Definition: sac.h:128
virtual void setThreshold(double threshold)
Set the threshold to model.
Definition: sac.h:73
double probability_
Desired probability of choosing at least one sample free from outliers.
Definition: sac.h:191
std::vector< double > getModelCoefficients()
Return the model coefficients of the best model found so far.
Definition: sac_model.h:180
virtual ~SAC()
Destructor for base SAC.
Definition: sac.h:66


semantic_point_annotator
Author(s): Radu Bogdan Rusu
autogenerated on Mon Jun 10 2019 14:29:03