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 #ifndef OPENCV_UTIL_MODEL_FIT_H_
00031 #define OPENCV_UTIL_MODEL_FIT_H_
00032
00033 #include <vector>
00034
00035 #include <opencv2/core/core.hpp>
00036
00037 #include <swri_math_util/random.h>
00038 #include <swri_math_util/ransac.h>
00039
00040 #include <swri_opencv_util/models.h>
00041
00042 namespace swri_opencv_util
00043 {
00044 template <class Model>
00045 cv::Mat FindModel2d(
00046 const cv::Mat& points1,
00047 const cv::Mat& points2,
00048 cv::Mat& inliers1,
00049 cv::Mat& inliers2,
00050 std::vector<uint32_t> &good_points,
00051 int32_t& iterations,
00052 double max_error = 1.0,
00053 double confidence = 0.9,
00054 int32_t max_iterations = 1000,
00055 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr())
00056 {
00057 cv::Mat model;
00058
00059
00060 cv::Mat correspondences;
00061 if (!ZipCorrespondences(points1, points2, correspondences))
00062 {
00063 return model;
00064 }
00065
00066
00067
00068 swri_math_util::Ransac<Model> ransac(rng);
00069
00070 Model fit_model(correspondences);
00071 model = ransac.FitModel(
00072 fit_model, max_error, confidence, 1, max_iterations, good_points, iterations);
00073
00074 if (good_points.empty())
00075 {
00076 return model;
00077 }
00078
00079
00080 bool row_order = points1.rows > 1;
00081 if (row_order)
00082 {
00083 inliers1 = cv::Mat(good_points.size(), 1, CV_32FC2);
00084 inliers2 = cv::Mat(good_points.size(), 1, CV_32FC2);
00085 for (size_t i = 0; i < good_points.size(); ++i)
00086 {
00087 inliers1.at<cv::Vec2f>(i, 0) = points1.at<cv::Vec2f>(good_points[i], 0);
00088 inliers2.at<cv::Vec2f>(i, 0) = points2.at<cv::Vec2f>(good_points[i], 0);
00089 }
00090 }
00091 else
00092 {
00093 inliers1 = cv::Mat(1, good_points.size(), CV_32FC2);
00094 inliers2 = cv::Mat(1, good_points.size(), CV_32FC2);
00095 for (size_t i = 0; i < good_points.size(); ++i)
00096 {
00097 inliers1.at<cv::Vec2f>(0, i) = points1.at<cv::Vec2f>(0, good_points[i]);
00098 inliers2.at<cv::Vec2f>(0, i) = points2.at<cv::Vec2f>(0, good_points[i]);
00099 }
00100 }
00101
00102 return model;
00103 }
00104
00105 cv::Mat FindTranslation2d(
00106 const cv::Mat& points1,
00107 const cv::Mat& points2,
00108 cv::Mat& inliers1,
00109 cv::Mat& inliers2,
00110 std::vector<uint32_t> &good_points,
00111 int32_t& iterations,
00112 double max_error = 1.0,
00113 double confidence = 0.9,
00114 int32_t max_iterations = 1000,
00115 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00116
00117 cv::Mat FindRigidTransform2d(
00118 const cv::Mat& points1,
00119 const cv::Mat& points2,
00120 cv::Mat& inliers1,
00121 cv::Mat& inliers2,
00122 std::vector<uint32_t> &good_points,
00123 int32_t& iterations,
00124 double max_error = 1.0,
00125 double confidence = 0.9,
00126 int32_t max_iterations = 1000,
00127 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00128
00129
00130
00131 cv::Mat FitRigidTransform2d(const cv::Mat& points1, const cv::Mat& points2);
00132
00133
00134
00135 cv::Mat FitRotation3d(const cv::Mat& points1, const cv::Mat& points2);
00136
00137 cv::Mat FindAffineTransform2d(
00138 const cv::Mat& points1,
00139 const cv::Mat& points2,
00140 cv::Mat& inliers1,
00141 cv::Mat& inliers2,
00142 std::vector<uint32_t> &good_points,
00143 int32_t& iterations,
00144 double max_error = 1.0,
00145 double confidence = 0.9,
00146 int32_t max_iterations = 1000,
00147 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00148
00149 cv::Mat FitAffineTransform2d(const cv::Mat& points1, const cv::Mat& points2);
00150
00151 cv::Mat FindHomography(
00152 const cv::Mat& points1,
00153 const cv::Mat& points2,
00154 cv::Mat& inliers1,
00155 cv::Mat& inliers2,
00156 std::vector<uint32_t> &good_points,
00157 int32_t& iterations,
00158 double max_error = 1.0,
00159 double confidence = 0.9,
00160 int32_t max_iterations = 1000,
00161 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00162
00163 PlaneModel FindPerpendicularPlaneWithPoint(
00164 const cv::Vec3f& point_on_plane,
00165 const cv::Vec3f& perp_axis,
00166 double max_angle_from_perp,
00167 const cv::Mat& points,
00168 cv::Mat& inliers,
00169 std::vector<uint32_t> &good_points,
00170 int32_t& iterations,
00171 double max_error,
00172 double confidence,
00173 int32_t min_iterations,
00174 int32_t max_iterations,
00175 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00176
00177 PlaneModel FindPlane(
00178 const cv::Mat& points,
00179 cv::Mat& inliers,
00180 std::vector<uint32_t> &good_points,
00181 int32_t& iterations,
00182 double max_error = 1.0,
00183 double confidence = 0.9,
00184 int32_t min_iterations = 1,
00185 int32_t max_iterations = 1000,
00186 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00187
00188 PlaneModel FitPlane(const cv::Mat& points);
00189
00190 LineModel3d FindLine3d(
00191 const cv::Mat& points,
00192 cv::Mat& inliers,
00193 std::vector<uint32_t> &good_points,
00194 int32_t& iterations,
00195 double max_error = 1.0,
00196 double confidence = 0.9,
00197 int32_t min_iterations = 1,
00198 int32_t max_iterations = 1000,
00199 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00200
00201 LineModel3d FindOrthoLine3d(
00202 const cv::Mat& points,
00203 const LineModel3d& ortho,
00204 cv::Mat& inliers,
00205 std::vector<uint32_t> &good_points,
00206 int32_t& iterations,
00207 double max_error = 1.0,
00208 double confidence = 0.9,
00209 int32_t min_iterations = 1,
00210 int32_t max_iterations = 1000,
00211 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00212
00213 LineModel3d FitLine3d(const cv::Mat& points);
00214
00215 CrossModel3d FindCross3d(
00216 const cv::Mat& points,
00217 cv::Mat& inliers,
00218 std::vector<uint32_t> &good_points,
00219 int32_t& iterations,
00220 double max_error = 1.0,
00221 double confidence = 0.9,
00222 int32_t min_iterations = 1,
00223 int32_t max_iterations = 1000,
00224 swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00225 }
00226
00227 #endif // OPENCV_UTIL_MODEL_FIT_H_