34 #include <opencv2/imgproc/imgproc.hpp>    39     const cv::Mat& points1,
    40     const cv::Mat& points2,
    43     std::vector<uint32_t> &good_points,
    47     int32_t max_iterations,
    50     return FindModel2d<Translation2d>(
    51       points1, points2, inliers1, inliers2, good_points, iterations, max_error,
    52       confidence, max_iterations, rng);
    56     const cv::Mat& points1,
    57     const cv::Mat& points2,
    60     std::vector<uint32_t> &good_points,
    64     int32_t max_iterations,
    67     return FindModel2d<RigidTransform2d>(
    68       points1, points2, inliers1, inliers2, good_points, iterations, max_error,
    69       confidence, max_iterations, rng);
    86     cv::Scalar centroid1 = cv::mean(points1);
    87     cv::Scalar centroid2 = cv::mean(points2);
    90     cv::Mat points1_centered = (points1 - centroid1);
    91     cv::Mat points2_centered = (points2 - centroid2);
    94     points1_centered = points1_centered.reshape(1, points1.rows);
    95     points2_centered = points2_centered.reshape(1, points1.rows);
    98     cv::Mat cov = points1_centered.t() * points2_centered;
   102     cv::SVD::compute(cov, W, U, Vt);
   103     double d = cv::determinant(Vt.t() * U.t()) > 0 ? 1.0 : -1.0;
   104     cv::Mat I = cv::Mat::eye(2, 2, CV_32F);
   105     I.at<
float>(1, 1) = d;
   106     cv::Mat rotation = Vt.t() * I * U.t();
   109     cv::Mat c1_r(2, 1, CV_32F);
   110     c1_r.at<
float>(0, 0) = centroid1[0];
   111     c1_r.at<
float>(1, 0) = centroid1[1];
   112     c1_r = rotation * c1_r;
   113     float t_x = centroid2[0] - c1_r.at<
float>(0, 0);
   114     float t_y = centroid2[1] - c1_r.at<
float>(1, 0);
   116     transform.create(2, 3, CV_32F);
   117     transform.at<
float>(0, 0) = rotation.at<
float>(0, 0);
   118     transform.at<
float>(0, 1) = rotation.at<
float>(0, 1);
   119     transform.at<
float>(1, 0) = rotation.at<
float>(1, 0);
   120     transform.at<
float>(1, 1) = rotation.at<
float>(1, 1);
   121     transform.at<
float>(0, 2) = t_x;
   122     transform.at<
float>(1, 2) = t_y;
   141     cv::Mat src = points1.reshape(1, points1.rows);
   142     cv::Mat dst = points2.reshape(1, points1.rows);
   144     cv::Mat cov = src.t() * dst;
   148     cv::SVD::compute(cov, W, U, Vt);
   150     double d = cv::determinant(V * U.t()) > 0 ? 1.0 : -1.0;
   151     cv::Mat I = cv::Mat::eye(3, 3, CV_32F);
   152     I.at<
float>(2, 2) = d;
   153     matrix = V * I * U.t();
   160     const cv::Mat& points1,
   161     const cv::Mat& points2,
   164     std::vector<uint32_t> &good_points,
   168     int32_t max_iterations,
   171     return FindModel2d<AffineTransform2d>(
   172       points1, points2, inliers1, inliers2, good_points, iterations, max_error,
   173       confidence, max_iterations, rng);
   177     const cv::Mat& points1,
   178     const cv::Mat& points2,
   181     std::vector<uint32_t> &good_points,
   185     int32_t max_iterations,
   188     return FindModel2d<Homography>(
   189       points1, points2, inliers1, inliers2, good_points, iterations, max_error,
   190       confidence, max_iterations, rng);
   202     bool row_order = points1.rows > 1;
   203     int32_t size = row_order ? points1.rows : points1.cols;
   212     cv::Mat A(size, 3, CV_32F);
   213     cv::Mat B = points2.reshape(1, 2);
   216       for (int32_t i = 0; i < size; ++i)
   218         const cv::Vec2f& point = points1.at<cv::Vec2f>(i, 0);
   219         cv::Vec3f& A_i = A.at<cv::Vec3f>(i, 0);
   230       for (int32_t i = 0; i < size; ++i)
   232         const cv::Vec2f& point = points1.at<cv::Vec2f>(0, i);
   233         cv::Vec3f& A_i = A.at<cv::Vec3f>(i, 0);
   241     if (cv::solve(A, B, x))
   250     const cv::Vec3f& point_on_plane,
   251     const cv::Vec3f& perp_axis,
   252     double max_angle_from_perp,
   253     const cv::Mat& points,
   255     std::vector<uint32_t> &good_points,
   259     int32_t min_iterations,
   260     int32_t max_iterations,
   265     cv::Mat reshaped = points.reshape(3);
   268       fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
   270     if (good_points.empty())
   275     inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
   276     for (
size_t i = 0; i < good_points.size(); ++i)
   278       inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
   280     inliers.reshape(points.channels());
   286     const cv::Mat& points,
   288     std::vector<uint32_t> &good_points,
   292     int32_t min_iterations,
   293     int32_t max_iterations,
   298     cv::Mat reshaped = points.reshape(3);
   301       fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
   303     if (good_points.empty())
   308     inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
   309     for (
size_t i = 0; i < good_points.size(); ++i)
   311       inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
   313     inliers.reshape(points.channels());
   325     cv::reduce(points.reshape(3), centroid, 0, CV_REDUCE_AVG);
   327     cv::Scalar c(centroid.at<
float>(0, 0), centroid.at<
float>(0, 1), centroid.at<
float>(0, 2));
   330     cv::subtract(points, c, A);
   335     cv::transpose(A.reshape(1), At);
   336     svd.compute(At, w, u, vt);
   339     cv::minMaxLoc(w, 
NULL, 
NULL, &min_w_loc);
   341     model.
x = centroid.at<
float>(0, 0);
   342     model.
y = centroid.at<
float>(0, 1);
   343     model.
z = centroid.at<
float>(0, 2);
   344     model.
i = u.at<
float>(0, min_w_loc.y);
   345     model.
j = u.at<
float>(1, min_w_loc.y);
   346     model.
k = u.at<
float>(2, min_w_loc.y);
   352     const cv::Mat& points,
   354     std::vector<uint32_t> &good_points,
   358     int32_t min_iterations,
   359     int32_t max_iterations,
   364     cv::Mat reshaped = points.reshape(3);
   367       fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
   369     if (good_points.empty())
   374     inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
   375     for (
size_t i = 0; i < good_points.size(); ++i)
   377       inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
   379     inliers.reshape(points.channels());
   384     const cv::Mat& points,
   387     std::vector<uint32_t> &good_points,
   391     int32_t min_iterations,
   392     int32_t max_iterations,
   397     cv::Mat reshaped = points.reshape(3);
   400       fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
   402     if (good_points.empty())
   407     inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
   408     for (
size_t i = 0; i < good_points.size(); ++i)
   410       inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
   412     inliers.reshape(points.channels());
   424     cv::reduce(points.reshape(3), centroid, 0, CV_REDUCE_AVG);
   426     cv::Scalar c(centroid.at<
float>(0, 0), centroid.at<
float>(0, 1), centroid.at<
float>(0, 2));
   429     cv::subtract(points, c, A);
   434     cv::transpose(A.reshape(1), At);
   435     svd.compute(At, w, u, vt);
   440     model.
x = centroid.at<
float>(0, 0);
   441     model.
y = centroid.at<
float>(0, 1);
   442     model.
z = centroid.at<
float>(0, 2);
   443     model.
i = u.at<
float>(0, max_w_loc.y);
   444     model.
j = u.at<
float>(1, max_w_loc.y);
   445     model.
k = u.at<
float>(2, max_w_loc.y);
   451     const cv::Mat& points,
   453     std::vector<uint32_t> &good_points,
   457     int32_t min_iterations,
   458     int32_t max_iterations,
   463     cv::Mat reshaped = points.reshape(3);
   466       fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
   468     if (good_points.empty())
   473     inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
   474     for (
size_t i = 0; i < good_points.size(); ++i)
   476       inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
   478     inliers.reshape(points.channels());
 
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())
bool Valid2dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
bool Valid3dPointCorrespondences(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())
PlaneModel FitPlane(const cv::Mat &points)
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)
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())
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 FitRigidTransform2d(const cv::Mat &points1, const cv::Mat &points2)
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())
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 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 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())
cv::Mat FitRotation3d(const cv::Mat &points1, const cv::Mat &points2)
LineModel3d FitLine3d(const cv::Mat &points)