30 #ifndef OPENCV_UTIL_MODELS_H_ 31 #define OPENCV_UTIL_MODELS_H_ 35 #include <opencv2/core/core.hpp> 48 virtual bool GetModel(
const std::vector<int32_t>& indices, M& model,
double max_error)
const = 0;
50 void GetInliers(
const M& model,
double max_error, std::vector<uint32_t>& indices);
54 static void CopyTo(
const M& src, M& dst)
75 enum { MIN_SIZE = 4 };
78 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
81 return data_.cols == 4 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32F;
91 enum { MIN_SIZE = 3 };
94 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
97 return data_.cols == 4 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32F;
104 enum { MIN_SIZE = 2 };
107 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
110 return data_.cols == 4 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32F;
117 enum { MIN_SIZE = 1 };
120 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
123 return data_.cols == 4 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32F;
128 const cv::Mat& points1,
129 const cv::Mat& points2);
132 const cv::Mat& points1,
133 const cv::Mat& points2);
136 const cv::Mat& points1,
137 const cv::Mat& points2,
138 cv::Mat& correspondences);
140 template <
class Model>
149 virtual bool GetModel(
const std::vector<int32_t>& indices, M& model,
double max_error)
const = 0;
159 void GetInliers(
const M& model,
double max_error, std::vector<uint32_t>& indices)
165 double threshold = max_error;
166 for (
int i = 0; i <
norms__.rows; i++)
168 if (
norms__.at<
float>(i) < threshold)
170 indices.push_back(i);
202 float x, y,
z, i, j, k;
208 enum { MIN_SIZE = 3 };
212 min_angle_(min_angle) {}
213 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
216 return data_.cols == 1 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32FC3;
228 enum { MIN_SIZE = 2 };
231 const cv::Vec3f& point_on_plane = cv::Vec3f(0,0,0),
232 const cv::Vec3f& perp_axis = cv::Vec3f(0,0,1),
233 float max_axis_angle = 0.5,
234 float min_angle = 0.2) :
236 point_(point_on_plane),
237 perp_axis_(perp_axis),
238 max_axis_angle_(max_axis_angle)
241 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
258 float x, y,
z, i, j, k;
264 enum { MIN_SIZE = 2 };
267 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
270 return data_.cols == 1 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32FC3;
286 LineFit3d(data), ortho_(ortho), angle_tolerance_(angle_tolerance) {}
287 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
296 CrossModel3d() : x(0), y(0), z(0), i1(0), j1(0), k1(0), i2(0), j2(0), k2(0) {}
302 float x, y,
z, i1, j1, k1, i2, j2, k2;
308 enum { MIN_SIZE = 3 };
312 min_angle_(min_angle) {}
313 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
316 return data_.cols == 1 &&
data_.rows >= MIN_SIZE &&
data_.type() == CV_32FC3;
332 #endif // OPENCV_UTIL_MODELS_H_ bool Valid2dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
void GetInliers(const M &model, double max_error, std::vector< uint32_t > &indices)
Homography(const T &data)
bool Valid3dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
OrthoLineFit3d(const T &data, const LineModel3d &ortho, float angle_tolerance=0.09)
Correspondence2d(const T &data)
void copyTo(CrossModel3d &dst) const
static void CopyTo(const M &src, M &dst)
void GetInliers(const M &model, double max_error, std::vector< uint32_t > &indices)
PerpendicularPlaneWithPointFit(const T &data, const cv::Vec3f &point_on_plane=cv::Vec3f(0, 0, 0), const cv::Vec3f &perp_axis=cv::Vec3f(0, 0, 1), float max_axis_angle=0.5, float min_angle=0.2)
void copyTo(PlaneModel &dst) const
Translation2d(const T &data)
PlaneFit(const T &data, float min_angle=0.2)
static void CopyTo(const M &src, M &dst)
virtual std::string GetModelString(M &model) const
virtual std::string GetModelString(M &model) const
void copyTo(LineModel3d &dst) const
int32_t GetInlierCount(const M &model, double max_error)
int32_t GetInlierCount(const M &model, double max_error)
bool ZipCorrespondences(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences)
CrossFit3d(const T &data, float min_angle=0.2)
virtual void CalculateNorms(const M &model, cv::Mat &norms)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const =0