00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <swri_opencv_util/model_fit.h>
00031
00032 #include <ros/ros.h>
00033
00034 #include <opencv2/imgproc/imgproc.hpp>
00035
00036 namespace swri_opencv_util
00037 {
00038 cv::Mat FindTranslation2d(
00039 const cv::Mat& points1,
00040 const cv::Mat& points2,
00041 cv::Mat& inliers1,
00042 cv::Mat& inliers2,
00043 std::vector<uint32_t> &good_points,
00044 int32_t& iterations,
00045 double max_error,
00046 double confidence,
00047 int32_t max_iterations,
00048 swri_math_util::RandomGeneratorPtr rng)
00049 {
00050 return FindModel2d<Translation2d>(
00051 points1, points2, inliers1, inliers2, good_points, iterations, max_error,
00052 confidence, max_iterations, rng);
00053 }
00054
00055 cv::Mat FindRigidTransform2d(
00056 const cv::Mat& points1,
00057 const cv::Mat& points2,
00058 cv::Mat& inliers1,
00059 cv::Mat& inliers2,
00060 std::vector<uint32_t> &good_points,
00061 int32_t& iterations,
00062 double max_error,
00063 double confidence,
00064 int32_t max_iterations,
00065 swri_math_util::RandomGeneratorPtr rng)
00066 {
00067 return FindModel2d<RigidTransform2d>(
00068 points1, points2, inliers1, inliers2, good_points, iterations, max_error,
00069 confidence, max_iterations, rng);
00070 }
00071
00072 cv::Mat FitRigidTransform2d(const cv::Mat& points1, const cv::Mat& points2)
00073 {
00074 cv::Mat transform;
00075
00076 if (!Valid2dPointCorrespondences(points1, points2))
00077 {
00078 return transform;
00079 }
00080
00081
00082
00083
00084
00085
00086 cv::Scalar centroid1 = cv::mean(points1);
00087 cv::Scalar centroid2 = cv::mean(points2);
00088
00089
00090 cv::Mat points1_centered = (points1 - centroid1);
00091 cv::Mat points2_centered = (points2 - centroid2);
00092
00093
00094 points1_centered = points1_centered.reshape(1, points1.rows);
00095 points2_centered = points2_centered.reshape(1, points1.rows);
00096
00097
00098 cv::Mat cov = points1_centered.t() * points2_centered;
00099
00100
00101 cv::Mat W, U, Vt;
00102 cv::SVD::compute(cov, W, U, Vt);
00103 double d = cv::determinant(Vt.t() * U.t()) > 0 ? 1.0 : -1.0;
00104 cv::Mat I = cv::Mat::eye(2, 2, CV_32F);
00105 I.at<float>(1, 1) = d;
00106 cv::Mat rotation = Vt.t() * I * U.t();
00107
00108
00109 cv::Mat c1_r(2, 1, CV_32F);
00110 c1_r.at<float>(0, 0) = centroid1[0];
00111 c1_r.at<float>(1, 0) = centroid1[1];
00112 c1_r = rotation * c1_r;
00113 float t_x = centroid2[0] - c1_r.at<float>(0, 0);
00114 float t_y = centroid2[1] - c1_r.at<float>(1, 0);
00115
00116 transform.create(2, 3, CV_32F);
00117 transform.at<float>(0, 0) = rotation.at<float>(0, 0);
00118 transform.at<float>(0, 1) = rotation.at<float>(0, 1);
00119 transform.at<float>(1, 0) = rotation.at<float>(1, 0);
00120 transform.at<float>(1, 1) = rotation.at<float>(1, 1);
00121 transform.at<float>(0, 2) = t_x;
00122 transform.at<float>(1, 2) = t_y;
00123
00124 return transform;
00125 }
00126
00127 cv::Mat FitRotation3d(const cv::Mat& points1, const cv::Mat& points2)
00128 {
00129 cv::Mat matrix;
00130
00131 if (!Valid3dPointCorrespondences(points1, points2))
00132 {
00133 return matrix;
00134 }
00135
00136
00137
00138
00139
00140
00141 cv::Mat src = points1.reshape(1, points1.rows);
00142 cv::Mat dst = points2.reshape(1, points1.rows);
00143
00144 cv::Mat cov = src.t() * dst;
00145
00146
00147 cv::Mat W, U, Vt;
00148 cv::SVD::compute(cov, W, U, Vt);
00149 cv::Mat V = Vt.t();
00150 double d = cv::determinant(V * U.t()) > 0 ? 1.0 : -1.0;
00151 cv::Mat I = cv::Mat::eye(3, 3, CV_32F);
00152 I.at<float>(2, 2) = d;
00153 matrix = V * I * U.t();
00154
00155 return matrix;
00156 }
00157
00158
00159 cv::Mat FindAffineTransform2d(
00160 const cv::Mat& points1,
00161 const cv::Mat& points2,
00162 cv::Mat& inliers1,
00163 cv::Mat& inliers2,
00164 std::vector<uint32_t> &good_points,
00165 int32_t& iterations,
00166 double max_error,
00167 double confidence,
00168 int32_t max_iterations,
00169 swri_math_util::RandomGeneratorPtr rng)
00170 {
00171 return FindModel2d<AffineTransform2d>(
00172 points1, points2, inliers1, inliers2, good_points, iterations, max_error,
00173 confidence, max_iterations, rng);
00174 }
00175
00176 cv::Mat FindHomography(
00177 const cv::Mat& points1,
00178 const cv::Mat& points2,
00179 cv::Mat& inliers1,
00180 cv::Mat& inliers2,
00181 std::vector<uint32_t> &good_points,
00182 int32_t& iterations,
00183 double max_error,
00184 double confidence,
00185 int32_t max_iterations,
00186 swri_math_util::RandomGeneratorPtr rng)
00187 {
00188 return FindModel2d<Homography>(
00189 points1, points2, inliers1, inliers2, good_points, iterations, max_error,
00190 confidence, max_iterations, rng);
00191 }
00192
00193 cv::Mat FitAffineTransform2d(const cv::Mat& points1, const cv::Mat& points2)
00194 {
00195 cv::Mat transform;
00196
00197 if (!Valid2dPointCorrespondences(points1, points2))
00198 {
00199 return transform;
00200 }
00201
00202 bool row_order = points1.rows > 1;
00203 int32_t size = row_order ? points1.rows : points1.cols;
00204
00205
00206
00207
00208
00209
00210
00211
00212 cv::Mat A(size, 3, CV_32F);
00213 cv::Mat B = points2.reshape(1, 2);
00214 if (row_order)
00215 {
00216 for (int32_t i = 0; i < size; ++i)
00217 {
00218 const cv::Vec2f& point = points1.at<cv::Vec2f>(i, 0);
00219 cv::Vec3f& A_i = A.at<cv::Vec3f>(i, 0);
00220 A_i[0] = point[0];
00221 A_i[1] = point[1];
00222 A_i[2] = 1.0;
00223 }
00224 }
00225 else
00226 {
00227 B = points2.t();
00228 B = B.reshape(1, 2);
00229
00230 for (int32_t i = 0; i < size; ++i)
00231 {
00232 const cv::Vec2f& point = points1.at<cv::Vec2f>(0, i);
00233 cv::Vec3f& A_i = A.at<cv::Vec3f>(i, 0);
00234 A_i[0] = point[0];
00235 A_i[1] = point[1];
00236 A_i[2] = 1.0;
00237 }
00238 }
00239
00240 cv::Mat x;
00241 if (cv::solve(A, B, x))
00242 {
00243 transform = x;
00244 }
00245
00246 return transform;
00247 }
00248
00249 PlaneModel FindPerpendicularPlaneWithPoint(
00250 const cv::Vec3f& point_on_plane,
00251 const cv::Vec3f& perp_axis,
00252 double max_angle_from_perp,
00253 const cv::Mat& points,
00254 cv::Mat& inliers,
00255 std::vector<uint32_t> &good_points,
00256 int32_t& iterations,
00257 double max_error,
00258 double confidence,
00259 int32_t min_iterations,
00260 int32_t max_iterations,
00261 swri_math_util::RandomGeneratorPtr rng)
00262 {
00263 swri_math_util::Ransac<PerpendicularPlaneWithPointFit> ransac(rng);
00264
00265 cv::Mat reshaped = points.reshape(3);
00266 PerpendicularPlaneWithPointFit fit_model(reshaped, point_on_plane, perp_axis, max_angle_from_perp);
00267 PlaneModel model = ransac.FitModel(
00268 fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
00269
00270 if (good_points.empty())
00271 {
00272 return model;
00273 }
00274
00275 inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
00276 for (size_t i = 0; i < good_points.size(); ++i)
00277 {
00278 inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
00279 }
00280 inliers.reshape(points.channels());
00281 return model;
00282 }
00283
00284
00285 PlaneModel FindPlane(
00286 const cv::Mat& points,
00287 cv::Mat& inliers,
00288 std::vector<uint32_t> &good_points,
00289 int32_t& iterations,
00290 double max_error,
00291 double confidence,
00292 int32_t min_iterations,
00293 int32_t max_iterations,
00294 swri_math_util::RandomGeneratorPtr rng)
00295 {
00296 swri_math_util::Ransac<PlaneFit> ransac(rng);
00297
00298 cv::Mat reshaped = points.reshape(3);
00299 PlaneFit fit_model(reshaped);
00300 PlaneModel model = ransac.FitModel(
00301 fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
00302
00303 if (good_points.empty())
00304 {
00305 return model;
00306 }
00307
00308 inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
00309 for (size_t i = 0; i < good_points.size(); ++i)
00310 {
00311 inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
00312 }
00313 inliers.reshape(points.channels());
00314 return model;
00315 }
00316
00317 PlaneModel FitPlane(const cv::Mat& points)
00318 {
00319 PlaneModel model;
00320 if (points.rows < 3)
00321 {
00322 return model;
00323 }
00324 cv::Mat centroid;
00325 cv::reduce(points.reshape(3), centroid, 0, CV_REDUCE_AVG);
00326
00327 cv::Scalar c(centroid.at<float>(0, 0), centroid.at<float>(0, 1), centroid.at<float>(0, 2));
00328
00329 cv::Mat A;
00330 cv::subtract(points, c, A);
00331
00332 cv::SVD svd;
00333 cv::Mat w, u, vt;
00334 cv::Mat At;
00335 cv::transpose(A.reshape(1), At);
00336 svd.compute(At, w, u, vt);
00337
00338 cv::Point min_w_loc;
00339 cv::minMaxLoc(w, NULL, NULL, &min_w_loc);
00340
00341 model.x = centroid.at<float>(0, 0);
00342 model.y = centroid.at<float>(0, 1);
00343 model.z = centroid.at<float>(0, 2);
00344 model.i = u.at<float>(0, min_w_loc.y);
00345 model.j = u.at<float>(1, min_w_loc.y);
00346 model.k = u.at<float>(2, min_w_loc.y);
00347
00348 return model;
00349 }
00350
00351 LineModel3d FindLine3d(
00352 const cv::Mat& points,
00353 cv::Mat& inliers,
00354 std::vector<uint32_t> &good_points,
00355 int32_t& iterations,
00356 double max_error,
00357 double confidence,
00358 int32_t min_iterations,
00359 int32_t max_iterations,
00360 swri_math_util::RandomGeneratorPtr rng)
00361 {
00362 swri_math_util::Ransac<LineFit3d> ransac(rng);
00363
00364 cv::Mat reshaped = points.reshape(3);
00365 LineFit3d fit_model(reshaped);
00366 LineModel3d model = ransac.FitModel(
00367 fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
00368
00369 if (good_points.empty())
00370 {
00371 return model;
00372 }
00373
00374 inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
00375 for (size_t i = 0; i < good_points.size(); ++i)
00376 {
00377 inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
00378 }
00379 inliers.reshape(points.channels());
00380 return model;
00381 }
00382
00383 LineModel3d FindOrthoLine3d(
00384 const cv::Mat& points,
00385 const LineModel3d& ortho,
00386 cv::Mat& inliers,
00387 std::vector<uint32_t> &good_points,
00388 int32_t& iterations,
00389 double max_error,
00390 double confidence,
00391 int32_t min_iterations,
00392 int32_t max_iterations,
00393 swri_math_util::RandomGeneratorPtr rng)
00394 {
00395 swri_math_util::Ransac<LineFit3d> ransac(rng);
00396
00397 cv::Mat reshaped = points.reshape(3);
00398 OrthoLineFit3d fit_model(reshaped, ortho);
00399 LineModel3d model = ransac.FitModel(
00400 fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
00401
00402 if (good_points.empty())
00403 {
00404 return model;
00405 }
00406
00407 inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
00408 for (size_t i = 0; i < good_points.size(); ++i)
00409 {
00410 inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
00411 }
00412 inliers.reshape(points.channels());
00413 return model;
00414 }
00415
00416 LineModel3d FitLine3d(const cv::Mat& points)
00417 {
00418 LineModel3d model;
00419 if (points.rows < 2)
00420 {
00421 return model;
00422 }
00423 cv::Mat centroid;
00424 cv::reduce(points.reshape(3), centroid, 0, CV_REDUCE_AVG);
00425
00426 cv::Scalar c(centroid.at<float>(0, 0), centroid.at<float>(0, 1), centroid.at<float>(0, 2));
00427
00428 cv::Mat A;
00429 cv::subtract(points, c, A);
00430
00431 cv::SVD svd;
00432 cv::Mat w, u, vt;
00433 cv::Mat At;
00434 cv::transpose(A.reshape(1), At);
00435 svd.compute(At, w, u, vt);
00436
00437 cv::Point max_w_loc;
00438 cv::minMaxLoc(w, NULL, NULL, NULL, &max_w_loc);
00439
00440 model.x = centroid.at<float>(0, 0);
00441 model.y = centroid.at<float>(0, 1);
00442 model.z = centroid.at<float>(0, 2);
00443 model.i = u.at<float>(0, max_w_loc.y);
00444 model.j = u.at<float>(1, max_w_loc.y);
00445 model.k = u.at<float>(2, max_w_loc.y);
00446
00447 return model;
00448 }
00449
00450 CrossModel3d FindCross3d(
00451 const cv::Mat& points,
00452 cv::Mat& inliers,
00453 std::vector<uint32_t> &good_points,
00454 int32_t& iterations,
00455 double max_error,
00456 double confidence,
00457 int32_t min_iterations,
00458 int32_t max_iterations,
00459 swri_math_util::RandomGeneratorPtr rng)
00460 {
00461 swri_math_util::Ransac<CrossFit3d> ransac(rng);
00462
00463 cv::Mat reshaped = points.reshape(3);
00464 CrossFit3d fit_model(reshaped);
00465 CrossModel3d model = ransac.FitModel(
00466 fit_model, max_error, confidence, min_iterations, max_iterations, good_points, iterations);
00467
00468 if (good_points.empty())
00469 {
00470 return model;
00471 }
00472
00473 inliers = cv::Mat(good_points.size(), reshaped.cols, reshaped.type());
00474 for (size_t i = 0; i < good_points.size(); ++i)
00475 {
00476 inliers.at<cv::Vec3f>(i, 0) = reshaped.at<cv::Vec3f>(good_points[i], 0);
00477 }
00478 inliers.reshape(points.channels());
00479 return model;
00480 }
00481 }