32 #include <opencv2/imgproc/imgproc.hpp>    52     double threshold = max_error * max_error;
    53     for (
int i = 0; i < 
norms__.rows; i++)
    55       if (
norms__.at<
float>(i) < threshold)
    64     cv::Mat src = 
data_(cv::Rect(0, 0, 2, 
data_.rows)).reshape(2);
    66     cv::Mat measured = 
data_(cv::Rect(2, 0, 2, 
data_.rows));
    77     if (indices.size() != MIN_SIZE)
    82     cv::Mat src(MIN_SIZE, 1, CV_32FC2);
    83     cv::Mat dst(MIN_SIZE, 1, CV_32FC2);
    85     for (int32_t i = 0; i < MIN_SIZE; i++)
    87       const float* sample = 
data_.ptr<
float>(indices[i]);
    88       src.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[0], sample[1]);
    89       dst.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[2], sample[3]);
    92     model = cv::getPerspectiveTransform(src, dst);
    96     cv::perspectiveTransform(src, predicted, model);
    97     cv::Mat delta, delta_squared, norms;
    98     cv::subtract(predicted.reshape(1), dst.reshape(1), delta);
    99     cv::multiply(delta, delta, delta_squared);
   101       delta_squared(cv::Rect(0, 0, 1, delta.rows)),
   102       delta_squared(cv::Rect(1, 0, 1, delta.rows)),
   106     cv::minMaxLoc(norms, &min, &max);
   108     return max < max_error * max_error;
   113     cv::Mat src = 
data_(cv::Rect(0, 0, 2, 
data_.rows)).reshape(2);
   115     cv::Mat measured = 
data_(cv::Rect(2, 0, 2, 
data_.rows));
   126     if (indices.size() != MIN_SIZE)
   131     cv::Mat src(MIN_SIZE, 1, CV_32FC2);
   132     cv::Mat dst(MIN_SIZE, 1, CV_32FC2);
   134     for (int32_t i = 0; i < MIN_SIZE; i++)
   136       const float* sample = 
data_.ptr<
float>(indices[i]);
   137       src.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[0], sample[1]);
   138       dst.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[2], sample[3]);
   141     model = cv::getAffineTransform(src, dst);
   145     cv::transform(src, predicted, model);
   146     cv::Mat delta, delta_squared, norms;
   147     cv::subtract(predicted.reshape(1), dst.reshape(1), delta);
   148     cv::multiply(delta, delta, delta_squared);
   150       delta_squared(cv::Rect(0, 0, 1, delta.rows)),
   151       delta_squared(cv::Rect(1, 0, 1, delta.rows)),
   155     cv::minMaxLoc(norms, &min, &max);
   157     return max < max_error * max_error;
   162     if (indices.size() != MIN_SIZE)
   167     cv::Point2f src[MIN_SIZE];
   168     cv::Point2f dst[MIN_SIZE];
   170     for (int32_t i = 0; i < MIN_SIZE; i++)
   172       const float* sample = 
data_.ptr<
float>(indices[i]);
   173       src[i].x = sample[0];
   174       src[i].y = sample[1];
   175       dst[i].x = sample[2];
   176       dst[i].y = sample[3];
   179     double len_src = cv::norm(src[1] - src[0]);
   180     double len_dst = cv::norm(dst[1] - dst[0]);
   181     if (std::fabs(len_src - len_dst) >= max_error)
   187     cv::Point2f src_x = (src[1] - src[0]) * (1.0 / len_src);
   188     cv::Point2f dst_x = (dst[1] - dst[0]) * (1.0 / len_dst);
   191     cv::Point2f src_y(src_x.y, -src_x.x);
   192     src_y *= 1.0 / cv::norm(src_y);
   194     cv::Point2f dst_y(dst_x.y, -dst_x.x);
   195     dst_y *= 1.0 / cv::norm(dst_y);
   198     cv::Mat src_r(2, 2, CV_32F);
   199     src_r.at<
float>(0, 0) = src_x.x;
   200     src_r.at<
float>(1, 0) = src_x.y;
   201     src_r.at<
float>(0, 1) = src_y.x;
   202     src_r.at<
float>(1, 1) = src_y.y;
   204     cv::Mat dst_r(2, 2, CV_32F);
   205     dst_r.at<
float>(0, 0) = dst_x.x;
   206     dst_r.at<
float>(1, 0) = dst_x.y;
   207     dst_r.at<
float>(0, 1) = dst_y.x;
   208     dst_r.at<
float>(1, 1) = dst_y.y;
   213     cv::Mat rotation = dst_r * src_r.t();
   216     cv::Mat src0_rotated(2, 1, CV_32F);
   217     src0_rotated.at<
float>(0, 0) = src[0].x;
   218     src0_rotated.at<
float>(1, 0) = src[0].y;
   219     src0_rotated = rotation * src0_rotated;
   220     float t_x = dst[0].x - src0_rotated.at<
float>(0, 0);
   221     float t_y = dst[0].y - src0_rotated.at<
float>(1, 0);
   223     model.create(2, 3, CV_32F);
   224     model.at<
float>(0, 0) = rotation.at<
float>(0, 0);
   225     model.at<
float>(0, 1) = rotation.at<
float>(0, 1);
   226     model.at<
float>(1, 0) = rotation.at<
float>(1, 0);
   227     model.at<
float>(1, 1) = rotation.at<
float>(1, 1);
   228     model.at<
float>(0, 2) = t_x;
   229     model.at<
float>(1, 2) = t_y;
   236     if (indices.size() != MIN_SIZE)
   244     const float* sample = 
data_.ptr<
float>(indices[0]);
   251     float t_x = dst.x - src.x;
   252     float t_y = dst.y - src.y;
   254     model.create(2, 3, CV_32F);
   255     model.at<
float>(0, 0) = 1.0
f;
   256     model.at<
float>(0, 1) = 0.0
f;
   257     model.at<
float>(1, 0) = 0.0
f;
   258     model.at<
float>(1, 1) = 1.0
f;
   259     model.at<
float>(0, 2) = t_x;
   260     model.at<
float>(1, 2) = t_y;
   266     const cv::Mat& points1,
   267     const cv::Mat& points2)
   269     if (points1.type() != points2.type())
   274     if (points1.type() != CV_32FC2)
   279     if (points1.cols != points2.cols  || points1.rows  != points2.rows)
   284     if (points1.cols != 1 && points1.rows != 1)
   293     const cv::Mat& points1,
   294     const cv::Mat& points2)
   296     if (points1.type() != points2.type())
   301     if (points1.type() != CV_32FC3)
   306     if (points1.cols != points2.cols  || points1.rows  != points2.rows)
   311     if (points1.cols != 1)
   320     const cv::Mat& points1,
   321     const cv::Mat& points2,
   322     cv::Mat& correspondeces)
   329     size_t num_points = points1.cols;
   330     bool row_order = 
false;
   331     if (points1.rows > 1)
   334       num_points = points1.rows;
   340       cv::hconcat(points1.reshape(1), points2.reshape(1), correspondeces);
   345         points1.reshape(0, num_points).reshape(1),
   346         points2.reshape(0, num_points).reshape(1),
   355                                                 double max_error)
 const   357     if (indices.size() != MIN_SIZE)
   364     cv::Mat points = 
data_.reshape(3);
   366     cv::Vec3f p1 = points.at<cv::Vec3f>(indices[0], 0);
   367     cv::Vec3f p2 = points.at<cv::Vec3f>(indices[1], 0);
   368     cv::Vec3f p3 = point_;
   370     cv::Point3f v12 = p2 - p1;
   371     cv::Point3f v13 = p3 - p1;
   372     float d12 = cv::norm(v12);
   373     float d13 = cv::norm(v13);
   374     float d = std::fabs(d12 * d13);
   380     float angle = std::acos(v12.dot(v13) / d);
   381     if (angle < min_angle_ || angle + min_angle_ > M_PI)
   388     cv::Vec3f normal = v12.cross(v13);
   389     normal = normal / cv::norm(normal);
   391     if (std::acos(normal.dot(perp_axis_)) > max_axis_angle_)
   408     if (indices.size() != MIN_SIZE)
   415     cv::Mat points = 
data_.reshape(3);
   417     cv::Vec3f p1 = points.at<cv::Vec3f>(indices[0], 0);
   418     cv::Vec3f p2 = points.at<cv::Vec3f>(indices[1], 0);
   419     cv::Vec3f p3 = points.at<cv::Vec3f>(indices[2], 0);
   421     cv::Point3f v12 = p2 - p1;
   422     cv::Point3f v13 = p3 - p1;
   423     float d12 = cv::norm(v12);
   424     float d13 = cv::norm(v13);
   425     float d = std::fabs(d12 * d13);
   431     float angle = std::acos(v12.dot(v13) / d);
   432     if (angle < min_angle_ || angle + min_angle_ > M_PI)
   439     cv::Vec3f normal = v12.cross(v13);
   440     normal = normal / cv::norm(normal);
   455     cv::Mat single_column = 
data_.reshape(3);
   456     cv::subtract(single_column, cv::Scalar(model.
x, model.
y, model.
z), 
delta__);
   460     cv::Mat split_columns = 
delta__.reshape(1);
   461     cv::Mat x = split_columns(cv::Rect(0, 0, 1, split_columns.rows));
   462     cv::Mat y = split_columns(cv::Rect(1, 0, 1, split_columns.rows));
   463     cv::Mat z = split_columns(cv::Rect(2, 0, 1, split_columns.rows));
   467     cv::add(x, y, norms);
   468     cv::add(norms, z, norms);
   469     norms = cv::abs(norms);
   474     if (indices.size() != MIN_SIZE)
   479     cv::Mat points = 
data_.reshape(3);
   481     cv::Point3f p1(points.at<cv::Vec3f>(indices[0], 0));
   482     cv::Point3f p2(points.at<cv::Vec3f>(indices[1], 0));
   484     cv::Point3f v12 = p2 - p1;
   485     v12 = cv::Vec3f(v12) / cv::norm(v12);
   501     cv::Scalar x0(model.
x, model.
y, model.
z);
   502     cv::Scalar n(model.
i, model.
j, model.
k);
   503     cv::Mat p = 
data_.reshape(3);
   505     if (temp1__.size != p.size)
   507       temp1__ = cv::Mat(p.rows, p.cols, p.type());
   510     cv::Mat n_columns = temp1__.reshape(1);
   511     cv::Mat n_x = n_columns(cv::Rect(0, 0, 1, n_columns.rows));
   512     cv::Mat n_y = n_columns(cv::Rect(1, 0, 1, n_columns.rows));
   513     cv::Mat n_z = n_columns(cv::Rect(2, 0, 1, n_columns.rows));
   516     cv::subtract(p, x0, x0_p__);
   519     cv::multiply(x0_p__, temp1__, temp2__);
   520     cv::reduce(temp2__.reshape(1), x0_p_dot_n__, 1, CV_REDUCE_SUM);
   523     cv::multiply(n_x, x0_p_dot_n__, n_x);
   524     cv::multiply(n_y, x0_p_dot_n__, n_y);
   525     cv::multiply(n_z, x0_p_dot_n__, n_z);
   528     cv::subtract(x0_p__, temp1__, temp1__);
   531     cv::multiply(n_x, n_x, n_x);
   532     cv::multiply(n_y, n_y, n_y);
   533     cv::multiply(n_z, n_z, n_z);
   534     cv::reduce(temp1__.reshape(1), norms, 1, CV_REDUCE_SUM);
   535     cv::sqrt(norms, norms);
   540     if (indices.size() != MIN_SIZE)
   545     cv::Mat points = 
data_.reshape(3);
   547     cv::Point3f p1(points.at<cv::Vec3f>(indices[0], 0));
   548     cv::Point3f p2(points.at<cv::Vec3f>(indices[1], 0));
   550     cv::Point3f v12 = p2 - p1;
   551     v12 = cv::Vec3f(v12) / cv::norm(v12);
   554     cv::Point3f ortho(ortho_.i, ortho_.j, ortho_.k);
   555     ortho = cv::Vec3f(ortho) / cv::norm(ortho);
   557     float angle = std::acos(v12.dot(ortho));
   558     float error = std::fabs(M_PI * 0.5 - angle);
   559     if (error > angle_tolerance_)
   576     if (indices.size() != MIN_SIZE)
   583     cv::Mat points = 
data_.reshape(3);
   585     cv::Point3f p1(points.at<cv::Vec3f>(indices[0], 0));
   586     cv::Point3f p2(points.at<cv::Vec3f>(indices[1], 0));
   587     cv::Point3f p3(points.at<cv::Vec3f>(indices[2], 0));
   589     cv::Point3f v12 = p2 - p1;
   590     cv::Point3f v13 = p3 - p1;
   591     float d12 = cv::norm(v12);
   592     float d13 = cv::norm(v13);
   593     float d = std::fabs(d12 * d13);
   599     float angle = std::acos(v12.dot(v13) / d);
   600     if (angle < min_angle_ || angle + min_angle_ > M_PI)
   610     cv::Point3f p4 = p1 + (v13.dot(v12) / v12.dot(v12)) * v12;
   611     cv::Point3f v34 = p4 - p3;
   614     v12 = cv::Vec3f(v12) / cv::norm(v12);
   615     v34 = cv::Vec3f(v34) / cv::norm(v34);
   638     cv::Scalar x0(model.
x, model.
y, model.
z);
   639     cv::Scalar n(model.
i1, model.
j1, model.
k1);
   640     cv::Mat p = 
data_.reshape(3);
   642     if (temp1__.size != p.size)
   644       temp1__ = cv::Mat(p.rows, p.cols, p.type());
   647     cv::Mat n_columns = temp1__.reshape(1);
   648     cv::Mat n_x = n_columns(cv::Rect(0, 0, 1, n_columns.rows));
   649     cv::Mat n_y = n_columns(cv::Rect(1, 0, 1, n_columns.rows));
   650     cv::Mat n_z = n_columns(cv::Rect(2, 0, 1, n_columns.rows));
   653     cv::subtract(p, x0, x0_p__);
   656     cv::multiply(x0_p__, temp1__, temp2__);
   657     cv::reduce(temp2__.reshape(1), x0_p_dot_n__, 1, CV_REDUCE_SUM);
   660     cv::multiply(n_x, x0_p_dot_n__, n_x);
   661     cv::multiply(n_y, x0_p_dot_n__, n_y);
   662     cv::multiply(n_z, x0_p_dot_n__, n_z);
   665     cv::subtract(x0_p__, temp1__, temp1__);
   668     cv::multiply(n_x, n_x, n_x);
   669     cv::multiply(n_y, n_y, n_y);
   670     cv::multiply(n_z, n_z, n_z);
   671     cv::reduce(temp1__.reshape(1), temp3__, 1, CV_REDUCE_SUM);
   672     cv::sqrt(temp3__, temp3__);
   681     n = cv::Scalar(model.
i2, model.
j2, model.
k2);
   685     cv::subtract(p, x0, x0_p__);
   688     cv::multiply(x0_p__, temp1__, temp2__);
   689     cv::reduce(temp2__.reshape(1), x0_p_dot_n__, 1, CV_REDUCE_SUM);
   692     cv::multiply(n_x, x0_p_dot_n__, n_x);
   693     cv::multiply(n_y, x0_p_dot_n__, n_y);
   694     cv::multiply(n_z, x0_p_dot_n__, n_z);
   697     cv::subtract(x0_p__, temp1__, temp1__);
   700     cv::multiply(n_x, n_x, n_x);
   701     cv::multiply(n_y, n_y, n_y);
   702     cv::multiply(n_z, n_z, n_z);
   703     cv::reduce(temp1__.reshape(1), norms, 1, CV_REDUCE_SUM);
   704     cv::sqrt(norms, norms);
   707     norms = cv::min(norms, temp3__);
 
bool Valid2dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
void GetInliers(const M &model, double max_error, std::vector< uint32_t > &indices)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
bool Valid3dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
virtual void CalculateNorms(const M &model, cv::Mat &norms)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
int32_t GetInlierCount(const M &model, double max_error)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
bool ZipCorrespondences(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences)
virtual void CalculateNorms(const M &model, cv::Mat &norms)
virtual void CalculateNorms(const M &model, cv::Mat &norms)
virtual void CalculateNorms(const M &model, cv::Mat &norms)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const 
virtual void CalculateNorms(const M &model, cv::Mat &norms)