model_fit.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_MODEL_FIT_H_
31 #define OPENCV_UTIL_MODEL_FIT_H_
32 
33 #include <vector>
34 
35 #include <opencv2/core/core.hpp>
36 
37 #include <swri_math_util/random.h>
38 #include <swri_math_util/ransac.h>
39 
41 
42 namespace swri_opencv_util
43 {
44  template <class Model>
45  cv::Mat FindModel2d(
46  const cv::Mat& points1,
47  const cv::Mat& points2,
48  cv::Mat& inliers1,
49  cv::Mat& inliers2,
50  std::vector<uint32_t> &good_points,
51  int32_t& iterations,
52  double max_error = 1.0,
53  double confidence = 0.9,
54  int32_t max_iterations = 1000,
56  {
57  cv::Mat model;
58 
59  // Put data into the expected format.
60  cv::Mat correspondences;
61  if (!ZipCorrespondences(points1, points2, correspondences))
62  {
63  return model;
64  }
65 
66  // Run RANSAC to robustly fit a rigid transform model to the set of
67  // corresponding points.
69 
70  Model fit_model(correspondences);
71  model = ransac.FitModel(
72  fit_model, max_error, confidence, 1, max_iterations, good_points, iterations);
73 
74  if (good_points.empty())
75  {
76  return model;
77  }
78 
79  // Populate output data.
80  bool row_order = points1.rows > 1;
81  if (row_order)
82  {
83  inliers1 = cv::Mat(good_points.size(), 1, CV_32FC2);
84  inliers2 = cv::Mat(good_points.size(), 1, CV_32FC2);
85  for (size_t i = 0; i < good_points.size(); ++i)
86  {
87  inliers1.at<cv::Vec2f>(i, 0) = points1.at<cv::Vec2f>(good_points[i], 0);
88  inliers2.at<cv::Vec2f>(i, 0) = points2.at<cv::Vec2f>(good_points[i], 0);
89  }
90  }
91  else
92  {
93  inliers1 = cv::Mat(1, good_points.size(), CV_32FC2);
94  inliers2 = cv::Mat(1, good_points.size(), CV_32FC2);
95  for (size_t i = 0; i < good_points.size(); ++i)
96  {
97  inliers1.at<cv::Vec2f>(0, i) = points1.at<cv::Vec2f>(0, good_points[i]);
98  inliers2.at<cv::Vec2f>(0, i) = points2.at<cv::Vec2f>(0, good_points[i]);
99  }
100  }
101 
102  return model;
103  }
104 
105  cv::Mat FindTranslation2d(
106  const cv::Mat& points1,
107  const cv::Mat& points2,
108  cv::Mat& inliers1,
109  cv::Mat& inliers2,
110  std::vector<uint32_t> &good_points,
111  int32_t& iterations,
112  double max_error = 1.0,
113  double confidence = 0.9,
114  int32_t max_iterations = 1000,
116 
117  cv::Mat FindRigidTransform2d(
118  const cv::Mat& points1,
119  const cv::Mat& points2,
120  cv::Mat& inliers1,
121  cv::Mat& inliers2,
122  std::vector<uint32_t> &good_points,
123  int32_t& iterations,
124  double max_error = 1.0,
125  double confidence = 0.9,
126  int32_t max_iterations = 1000,
128 
129  // Returns a 2x3 transform that can be applied to points1 to align them to
130  // points2.
131  cv::Mat FitRigidTransform2d(const cv::Mat& points1, const cv::Mat& points2);
132 
133  // Calculate 3x3 rotation matrix that can be applied to points1 to align them
134  // to points2.
135  cv::Mat FitRotation3d(const cv::Mat& points1, const cv::Mat& points2);
136 
137  cv::Mat FindAffineTransform2d(
138  const cv::Mat& points1,
139  const cv::Mat& points2,
140  cv::Mat& inliers1,
141  cv::Mat& inliers2,
142  std::vector<uint32_t> &good_points,
143  int32_t& iterations,
144  double max_error = 1.0,
145  double confidence = 0.9,
146  int32_t max_iterations = 1000,
148 
149  cv::Mat FitAffineTransform2d(const cv::Mat& points1, const cv::Mat& points2);
150 
151  cv::Mat FindHomography(
152  const cv::Mat& points1,
153  const cv::Mat& points2,
154  cv::Mat& inliers1,
155  cv::Mat& inliers2,
156  std::vector<uint32_t> &good_points,
157  int32_t& iterations,
158  double max_error = 1.0,
159  double confidence = 0.9,
160  int32_t max_iterations = 1000,
162 
164  const cv::Vec3f& point_on_plane,
165  const cv::Vec3f& perp_axis,
166  double max_angle_from_perp,
167  const cv::Mat& points,
168  cv::Mat& inliers,
169  std::vector<uint32_t> &good_points,
170  int32_t& iterations,
171  double max_error,
172  double confidence,
173  int32_t min_iterations,
174  int32_t max_iterations,
176 
178  const cv::Mat& points,
179  cv::Mat& inliers,
180  std::vector<uint32_t> &good_points,
181  int32_t& iterations,
182  double max_error = 1.0,
183  double confidence = 0.9,
184  int32_t min_iterations = 1,
185  int32_t max_iterations = 1000,
187 
188  PlaneModel FitPlane(const cv::Mat& points);
189 
191  const cv::Mat& points,
192  cv::Mat& inliers,
193  std::vector<uint32_t> &good_points,
194  int32_t& iterations,
195  double max_error = 1.0,
196  double confidence = 0.9,
197  int32_t min_iterations = 1,
198  int32_t max_iterations = 1000,
200 
202  const cv::Mat& points,
203  const LineModel3d& ortho,
204  cv::Mat& inliers,
205  std::vector<uint32_t> &good_points,
206  int32_t& iterations,
207  double max_error = 1.0,
208  double confidence = 0.9,
209  int32_t min_iterations = 1,
210  int32_t max_iterations = 1000,
212 
213  LineModel3d FitLine3d(const cv::Mat& points);
214 
216  const cv::Mat& points,
217  cv::Mat& inliers,
218  std::vector<uint32_t> &good_points,
219  int32_t& iterations,
220  double max_error = 1.0,
221  double confidence = 0.9,
222  int32_t min_iterations = 1,
223  int32_t max_iterations = 1000,
225 }
226 
227 #endif // OPENCV_UTIL_MODEL_FIT_H_
CrossModel3d FindCross3d(const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:450
PlaneModel FindPlane(const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:285
cv::Mat FindModel2d(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.h:45
PlaneModel FitPlane(const cv::Mat &points)
Definition: model_fit.cpp:317
LineModel3d FindOrthoLine3d(const cv::Mat &points, const LineModel3d &ortho, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:383
cv::Mat FitAffineTransform2d(const cv::Mat &points1, const cv::Mat &points2)
Definition: model_fit.cpp:193
ModelType FitModel(Model &model, double max_error, double confidence, int32_t min_iterations, int32_t max_iterations, std::vector< uint32_t > &inliers, int32_t &iterations)
cv::Mat FindHomography(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:176
cv::Mat FindRigidTransform2d(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:55
cv::Mat FitRigidTransform2d(const cv::Mat &points1, const cv::Mat &points2)
Definition: model_fit.cpp:72
PlaneModel FindPerpendicularPlaneWithPoint(const cv::Vec3f &point_on_plane, const cv::Vec3f &perp_axis, double max_angle_from_perp, const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error, double confidence, int32_t min_iterations, int32_t max_iterations, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:249
cv::Mat FindTranslation2d(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:38
cv::Mat FindAffineTransform2d(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:159
bool ZipCorrespondences(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences)
Definition: models.cpp:319
LineModel3d FindLine3d(const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr())
Definition: model_fit.cpp:351
cv::Mat FitRotation3d(const cv::Mat &points1, const cv::Mat &points2)
Definition: model_fit.cpp:127
LineModel3d FitLine3d(const cv::Mat &points)
Definition: model_fit.cpp:416


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