Go to the documentation of this file.
30 #ifndef OPENCV_UTIL_MODEL_FIT_H_
31 #define OPENCV_UTIL_MODEL_FIT_H_
35 #include <opencv2/core/core.hpp>
44 template <
class Model>
46 const cv::Mat& points1,
47 const cv::Mat& points2,
50 std::vector<uint32_t> &good_points,
52 double max_error = 1.0,
53 double confidence = 0.9,
54 int32_t max_iterations = 1000,
60 cv::Mat correspondences;
70 Model fit_model(correspondences);
72 fit_model, max_error, confidence, 1, max_iterations, good_points, iterations);
74 if (good_points.empty())
80 bool row_order = points1.rows > 1;
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)
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);
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)
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]);
106 const cv::Mat& points1,
107 const cv::Mat& points2,
110 std::vector<uint32_t> &good_points,
112 double max_error = 1.0,
113 double confidence = 0.9,
114 int32_t max_iterations = 1000,
118 const cv::Mat& points1,
119 const cv::Mat& points2,
122 std::vector<uint32_t> &good_points,
124 double max_error = 1.0,
125 double confidence = 0.9,
126 int32_t max_iterations = 1000,
135 cv::Mat
FitRotation3d(
const cv::Mat& points1,
const cv::Mat& points2);
138 const cv::Mat& points1,
139 const cv::Mat& points2,
142 std::vector<uint32_t> &good_points,
144 double max_error = 1.0,
145 double confidence = 0.9,
146 int32_t max_iterations = 1000,
152 const cv::Mat& points1,
153 const cv::Mat& points2,
156 std::vector<uint32_t> &good_points,
158 double max_error = 1.0,
159 double confidence = 0.9,
160 int32_t max_iterations = 1000,
164 const cv::Vec3f& point_on_plane,
165 const cv::Vec3f& perp_axis,
166 double max_angle_from_perp,
167 const cv::Mat& points,
169 std::vector<uint32_t> &good_points,
173 int32_t min_iterations,
174 int32_t max_iterations,
178 const cv::Mat& points,
180 std::vector<uint32_t> &good_points,
182 double max_error = 1.0,
183 double confidence = 0.9,
184 int32_t min_iterations = 1,
185 int32_t max_iterations = 1000,
188 PlaneModel
FitPlane(
const cv::Mat& points);
191 const cv::Mat& points,
193 std::vector<uint32_t> &good_points,
195 double max_error = 1.0,
196 double confidence = 0.9,
197 int32_t min_iterations = 1,
198 int32_t max_iterations = 1000,
202 const cv::Mat& points,
203 const LineModel3d& ortho,
205 std::vector<uint32_t> &good_points,
207 double max_error = 1.0,
208 double confidence = 0.9,
209 int32_t min_iterations = 1,
210 int32_t max_iterations = 1000,
213 LineModel3d
FitLine3d(
const cv::Mat& points);
216 const cv::Mat& points,
218 std::vector<uint32_t> &good_points,
220 double max_error = 1.0,
221 double confidence = 0.9,
222 int32_t min_iterations = 1,
223 int32_t max_iterations = 1000,
227 #endif // OPENCV_UTIL_MODEL_FIT_H_
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())
cv::Mat FitAffineTransform2d(const cv::Mat &points1, const cv::Mat &points2)
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())
bool ZipCorrespondences(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences)
cv::Mat FitRigidTransform2d(const cv::Mat &points1, const cv::Mat &points2)
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())
PlaneModel FitPlane(const cv::Mat &points)
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())
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())
cv::Mat FitRotation3d(const cv::Mat &points1, const cv::Mat &points2)
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())
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())
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)
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())
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())
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())
LineModel3d FitLine3d(const cv::Mat &points)