models.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
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 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #ifndef OPENCV_UTIL_MODELS_H_
31 #define OPENCV_UTIL_MODELS_H_
32 
33 #include <vector>
34 
35 #include <opencv2/core/core.hpp>
36 
37 namespace swri_opencv_util
38 {
39 
41  {
42  public:
43  typedef cv::Mat T; // An Nx4 float matrix
44  typedef cv::Mat M;
45 
46  explicit Correspondence2d(const T& data) : data_(data) {}
47 
48  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const = 0;
49  int32_t GetInlierCount(const M& model, double max_error);
50  void GetInliers(const M& model, double max_error, std::vector<uint32_t>& indices);
51  int32_t Size() const { return data_.rows; }
52  virtual std::string GetModelString(M& model) const { return ""; }
53 
54  static void CopyTo(const M& src, M& dst)
55  {
56  src.copyTo(dst);
57  }
58 
59  protected:
60  virtual void CalculateNorms(const M& model, cv::Mat& norms);
61 
62  const T& data_;
63 
64  // Buffer matrices to avoid repeated memory allocations.
65  cv::Mat norms__;
66  cv::Mat predicted__;
67  cv::Mat delta__;
68  cv::Mat delta_squared__;
69  cv::Mat thresholded__;
70  };
71 
73  {
74  public:
75  enum { MIN_SIZE = 4 };
76 
77  explicit Homography(const T& data) : Correspondence2d(data) {}
78  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
79  bool ValidData() const
80  {
81  return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
82  }
83 
84  protected:
85  virtual void CalculateNorms(const M& model, cv::Mat& norms);
86  };
87 
89  {
90  public:
91  enum { MIN_SIZE = 3 };
92 
93  explicit AffineTransform2d(const T& data) : Correspondence2d(data) {}
94  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
95  bool ValidData() const
96  {
97  return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
98  }
99  };
100 
102  {
103  public:
104  enum { MIN_SIZE = 2 };
105 
106  explicit RigidTransform2d(const T& data) : Correspondence2d(data) {}
107  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
108  bool ValidData() const
109  {
110  return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
111  }
112  };
113 
115  {
116  public:
117  enum { MIN_SIZE = 1 };
118 
119  explicit Translation2d(const T& data) : Correspondence2d(data) {}
120  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
121  bool ValidData() const
122  {
123  return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
124  }
125  };
126 
128  const cv::Mat& points1,
129  const cv::Mat& points2);
130 
132  const cv::Mat& points1,
133  const cv::Mat& points2);
134 
135  bool ZipCorrespondences(
136  const cv::Mat& points1,
137  const cv::Mat& points2,
138  cv::Mat& correspondences);
139 
140  template <class Model>
141  class Fit3d
142  {
143  public:
144  typedef cv::Mat T; // An Nx3 float matrix
145  typedef Model M; // A geometric model
146 
147  explicit Fit3d(const T& data) : data_(data) {}
148 
149  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const = 0;
150  int32_t GetInlierCount(const M& model, double max_error)
151  {
152  CalculateNorms(model, norms__);
153 
154  cv::compare(norms__, cv::Scalar(max_error), thresholded__, cv::CMP_LT);
155 
156  return cv::countNonZero(thresholded__);
157  }
158 
159  void GetInliers(const M& model, double max_error, std::vector<uint32_t>& indices)
160  {
161  CalculateNorms(model, norms__);
162 
163  indices.clear();
164  indices.reserve(norms__.rows);
165  double threshold = max_error;
166  for (int i = 0; i < norms__.rows; i++)
167  {
168  if (norms__.at<float>(i) < threshold)
169  {
170  indices.push_back(i);
171  }
172  }
173  }
174 
175  int32_t Size() const { return data_.rows; }
176  virtual std::string GetModelString(M& model) const { return ""; }
177 
178  static void CopyTo(const M& src, M& dst)
179  {
180  src.copyTo(dst);
181  }
182 
183  protected:
184  virtual void CalculateNorms(const M& model, cv::Mat& norms) = 0;
185 
186  const T& data_;
187 
188  // Buffer matrices to avoid repeated memory allocations.
189  cv::Mat norms__;
190  cv::Mat delta__;
191  cv::Mat thresholded__;
192  };
193 
194  struct PlaneModel
195  {
196  PlaneModel() : x(0), y(0), z(0), i(0), j(0), k(0) {}
197  void copyTo(PlaneModel& dst) const
198  {
199  dst = *this;
200  }
201 
202  float x, y, z, i, j, k;
203  };
204 
205  class PlaneFit : public Fit3d<PlaneModel>
206  {
207  public:
208  enum { MIN_SIZE = 3 };
209 
210  PlaneFit(const T& data, float min_angle = 0.2) :
211  Fit3d<PlaneModel>(data),
212  min_angle_(min_angle) {}
213  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
214  bool ValidData() const
215  {
216  return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
217  }
218 
219  protected:
220  virtual void CalculateNorms(const M& model, cv::Mat& norms);
221 
222  float min_angle_;
223  };
224 
226  {
227  public:
228  enum { MIN_SIZE = 2 };
229 
231  const cv::Vec3f& point_on_plane = cv::Vec3f(0,0,0),
232  const cv::Vec3f& perp_axis = cv::Vec3f(0,0,1),
233  float max_axis_angle = 0.5,
234  float min_angle = 0.2) :
235  PlaneFit(data, min_angle),
236  point_(point_on_plane),
237  perp_axis_(perp_axis),
238  max_axis_angle_(max_axis_angle)
239  {}
240 
241  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
242 
243  protected:
244 
245  cv::Vec3f point_;
246  cv::Vec3f perp_axis_;
248  };
249 
250  struct LineModel3d
251  {
252  LineModel3d() : x(0), y(0), z(0), i(0), j(0), k(0) {}
253  void copyTo(LineModel3d& dst) const
254  {
255  dst = *this;
256  }
257 
258  float x, y, z, i, j, k;
259  };
260 
261  class LineFit3d : public Fit3d<LineModel3d>
262  {
263  public:
264  enum { MIN_SIZE = 2 };
265 
266  LineFit3d(const T& data) : Fit3d<LineModel3d>(data) {}
267  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
268  bool ValidData() const
269  {
270  return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
271  }
272 
273  protected:
274  virtual void CalculateNorms(const M& model, cv::Mat& norms);
275 
276  cv::Mat temp1__;
277  cv::Mat temp2__;
278  cv::Mat x0_p_dot_n__;
279  cv::Mat x0_p__;
280  };
281 
282  class OrthoLineFit3d : public LineFit3d
283  {
284  public:
285  OrthoLineFit3d(const T& data, const LineModel3d& ortho, float angle_tolerance = 0.09) :
286  LineFit3d(data), ortho_(ortho), angle_tolerance_(angle_tolerance) {}
287  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
288 
289  protected:
292  };
293 
295  {
296  CrossModel3d() : x(0), y(0), z(0), i1(0), j1(0), k1(0), i2(0), j2(0), k2(0) {}
297  void copyTo(CrossModel3d& dst) const
298  {
299  dst = *this;
300  }
301 
302  float x, y, z, i1, j1, k1, i2, j2, k2;
303  };
304 
305  class CrossFit3d : public Fit3d<CrossModel3d>
306  {
307  public:
308  enum { MIN_SIZE = 3 };
309 
310  CrossFit3d(const T& data, float min_angle = 0.2) :
311  Fit3d<CrossModel3d>(data),
312  min_angle_(min_angle) {}
313  virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
314  bool ValidData() const
315  {
316  return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
317  }
318 
319  protected:
320  virtual void CalculateNorms(const M& model, cv::Mat& norms);
321 
322  float min_angle_;
323  cv::Mat temp1__;
324  cv::Mat temp2__;
325  cv::Mat temp3__;
326  cv::Mat x0_p_dot_n__;
327  cv::Mat x0_p__;
328  };
329 
330 }
331 
332 #endif // OPENCV_UTIL_MODELS_H_
bool Valid2dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
Definition: models.cpp:265
void copyTo(PlaneModel &dst) const
Definition: models.h:197
void GetInliers(const M &model, double max_error, std::vector< uint32_t > &indices)
Definition: models.cpp:46
bool ValidData() const
Definition: models.h:268
Homography(const T &data)
Definition: models.h:77
virtual std::string GetModelString(M &model) const
Definition: models.h:176
bool Valid3dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
Definition: models.cpp:292
bool ValidData() const
Definition: models.h:79
OrthoLineFit3d(const T &data, const LineModel3d &ortho, float angle_tolerance=0.09)
Definition: models.h:285
LineFit3d(const T &data)
Definition: models.h:266
bool ValidData() const
Definition: models.h:214
Correspondence2d(const T &data)
Definition: models.h:46
bool ValidData() const
Definition: models.h:314
AffineTransform2d(const T &data)
Definition: models.h:93
static void CopyTo(const M &src, M &dst)
Definition: models.h:178
void GetInliers(const M &model, double max_error, std::vector< uint32_t > &indices)
Definition: models.h:159
Fit3d(const T &data)
Definition: models.h:147
PerpendicularPlaneWithPointFit(const T &data, const cv::Vec3f &point_on_plane=cv::Vec3f(0, 0, 0), const cv::Vec3f &perp_axis=cv::Vec3f(0, 0, 1), float max_axis_angle=0.5, float min_angle=0.2)
Definition: models.h:230
int32_t Size() const
Definition: models.h:175
Translation2d(const T &data)
Definition: models.h:119
PlaneFit(const T &data, float min_angle=0.2)
Definition: models.h:210
void copyTo(CrossModel3d &dst) const
Definition: models.h:297
static void CopyTo(const M &src, M &dst)
Definition: models.h:54
virtual std::string GetModelString(M &model) const
Definition: models.h:52
RigidTransform2d(const T &data)
Definition: models.h:106
int32_t GetInlierCount(const M &model, double max_error)
Definition: models.cpp:37
int32_t GetInlierCount(const M &model, double max_error)
Definition: models.h:150
bool ZipCorrespondences(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences)
Definition: models.cpp:319
void copyTo(LineModel3d &dst) const
Definition: models.h:253
CrossFit3d(const T &data, float min_angle=0.2)
Definition: models.h:310
virtual void CalculateNorms(const M &model, cv::Mat &norms)
Definition: models.cpp:62
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const =0


swri_opencv_util
Author(s): Marc Alban
autogenerated on Sat Jan 21 2023 03:13:14