Go to the documentation of this file.
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);
78 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
94 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
107 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
120 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
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);
213 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
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) :
241 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
267 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
287 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
313 virtual bool GetModel(
const std::vector<int32_t>& indices,
M& model,
double max_error)
const;
332 #endif // OPENCV_UTIL_MODELS_H_
bool Valid3dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
virtual void CalculateNorms(const M &model, cv::Mat &norms)
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)
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
CrossFit3d(const T &data, float min_angle=0.2)
Correspondence2d(const T &data)
static void CopyTo(const M &src, M &dst)
bool Valid2dPointCorrespondences(const cv::Mat &points1, const cv::Mat &points2)
void copyTo(PlaneModel &dst) const
virtual void CalculateNorms(const M &model, cv::Mat &norms)
void GetInliers(const M &model, double max_error, std::vector< uint32_t > &indices)
void copyTo(CrossModel3d &dst) const
PlaneFit(const T &data, float min_angle=0.2)
bool ZipCorrespondences(const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const =0
int32_t GetInlierCount(const M &model, double max_error)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const
virtual void CalculateNorms(const M &model, cv::Mat &norms)=0
virtual std::string GetModelString(M &model) const
Homography(const T &data)
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 void CalculateNorms(const M &model, cv::Mat &norms)
OrthoLineFit3d(const T &data, const LineModel3d &ortho, float angle_tolerance=0.09)
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
void copyTo(LineModel3d &dst) const
Translation2d(const T &data)
virtual std::string GetModelString(M &model) const
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const =0
int32_t GetInlierCount(const M &model, double max_error)
virtual bool GetModel(const std::vector< int32_t > &indices, M &model, double max_error) const
virtual void CalculateNorms(const M &model, cv::Mat &norms)