Classes | |
class | AffineTransform2d |
class | Correspondence2d |
class | CrossFit3d |
struct | CrossModel3d |
class | CvWindows |
class | Fit3d |
class | Homography |
class | LineFit3d |
struct | LineModel3d |
class | OrthoLineFit3d |
class | PerpendicularPlaneWithPointFit |
class | PlaneFit |
struct | PlaneModel |
class | RigidTransform2d |
class | Translation2d |
Typedefs | |
typedef boost::serialization::singleton< CvWindows > | CvWindowsSingleton |
Functions | |
cv::Mat | blend (const cv::Mat &overlay, const cv::Mat &base, double aplha) |
cv::Mat | blend (const cv::Mat &src1, const cv::Mat &alpha1, const cv::Mat &src2, const cv::Mat &alpha2) |
cv::Mat | FindAffineTransform2d (const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
CrossModel3d | FindCross3d (const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
cv::Mat | FindHomography (const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
LineModel3d | FindLine3d (const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
template<class Model > | |
cv::Mat | FindModel2d (const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
LineModel3d | FindOrthoLine3d (const cv::Mat &points, const LineModel3d &ortho, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
PlaneModel | FindPerpendicularPlaneWithPoint (const cv::Vec3f &point_on_plane, const cv::Vec3f &perp_axis, double max_angle_from_perp, const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error, double confidence, int32_t min_iterations, int32_t max_iterations, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
PlaneModel | FindPlane (const cv::Mat &points, cv::Mat &inliers, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t min_iterations=1, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
cv::Mat | FindRigidTransform2d (const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
cv::Mat | FindTranslation2d (const cv::Mat &points1, const cv::Mat &points2, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &good_points, int32_t &iterations, double max_error=1.0, double confidence=0.9, int32_t max_iterations=1000, swri_math_util::RandomGeneratorPtr rng=swri_math_util::RandomGeneratorPtr()) |
cv::Mat | FitAffineTransform2d (const cv::Mat &points1, const cv::Mat &points2) |
LineModel3d | FitLine3d (const cv::Mat &points) |
PlaneModel | FitPlane (const cv::Mat &points) |
cv::Mat | FitRigidTransform2d (const cv::Mat &points1, const cv::Mat &points2) |
cv::Mat | FitRotation3d (const cv::Mat &points1, const cv::Mat &points2) |
cv::Mat | overlayColor (const cv::Mat &src, const cv::Mat &mask, const cv::Scalar &color, double alpha) |
void | SetAlpha (cv::Mat &mat, uint8_t alpha) |
void | ShowScaled (const std::string &name, const cv::Mat &mat, const cv::Mat &mask=cv::Mat(), double a=-1.0, double b=0.0) |
cv::Mat | ToBgra8 (const cv::Mat &mat, const cv::Mat &mask=cv::Mat(), bool is_rgb=false, double a=0.0, double b=0.0) |
bool | Valid2dPointCorrespondences (const cv::Mat &points1, const cv::Mat &points2) |
bool | Valid3dPointCorrespondences (const cv::Mat &points1, const cv::Mat &points2) |
bool | ZipCorrespondences (const cv::Mat &points1, const cv::Mat &points2, cv::Mat &correspondences) |
typedef boost::serialization::singleton<CvWindows> swri_opencv_util::CvWindowsSingleton |
cv::Mat swri_opencv_util::blend | ( | const cv::Mat & | overlay, |
const cv::Mat & | base, | ||
double | aplha | ||
) |
cv::Mat swri_opencv_util::blend | ( | const cv::Mat & | src1, |
const cv::Mat & | alpha1, | ||
const cv::Mat & | src2, | ||
const cv::Mat & | alpha2 | ||
) |
cv::Mat swri_opencv_util::FindAffineTransform2d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2, | ||
cv::Mat & | inliers1, | ||
cv::Mat & | inliers2, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 159 of file model_fit.cpp.
CrossModel3d swri_opencv_util::FindCross3d | ( | const cv::Mat & | points, |
cv::Mat & | inliers, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | min_iterations = 1 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 450 of file model_fit.cpp.
cv::Mat swri_opencv_util::FindHomography | ( | const cv::Mat & | points1, |
const cv::Mat & | points2, | ||
cv::Mat & | inliers1, | ||
cv::Mat & | inliers2, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 176 of file model_fit.cpp.
LineModel3d swri_opencv_util::FindLine3d | ( | const cv::Mat & | points, |
cv::Mat & | inliers, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | min_iterations = 1 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 351 of file model_fit.cpp.
cv::Mat swri_opencv_util::FindModel2d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2, | ||
cv::Mat & | inliers1, | ||
cv::Mat & | inliers2, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 45 of file model_fit.h.
LineModel3d swri_opencv_util::FindOrthoLine3d | ( | const cv::Mat & | points, |
const LineModel3d & | ortho, | ||
cv::Mat & | inliers, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | min_iterations = 1 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 383 of file model_fit.cpp.
PlaneModel swri_opencv_util::FindPerpendicularPlaneWithPoint | ( | const cv::Vec3f & | point_on_plane, |
const cv::Vec3f & | perp_axis, | ||
double | max_angle_from_perp, | ||
const cv::Mat & | points, | ||
cv::Mat & | inliers, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error, | ||
double | confidence, | ||
int32_t | min_iterations, | ||
int32_t | max_iterations, | ||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 249 of file model_fit.cpp.
PlaneModel swri_opencv_util::FindPlane | ( | const cv::Mat & | points, |
cv::Mat & | inliers, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | min_iterations = 1 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 285 of file model_fit.cpp.
cv::Mat swri_opencv_util::FindRigidTransform2d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2, | ||
cv::Mat & | inliers1, | ||
cv::Mat & | inliers2, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 55 of file model_fit.cpp.
cv::Mat swri_opencv_util::FindTranslation2d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2, | ||
cv::Mat & | inliers1, | ||
cv::Mat & | inliers2, | ||
std::vector< uint32_t > & | good_points, | ||
int32_t & | iterations, | ||
double | max_error = 1.0 , |
||
double | confidence = 0.9 , |
||
int32_t | max_iterations = 1000 , |
||
swri_math_util::RandomGeneratorPtr | rng = swri_math_util::RandomGeneratorPtr() |
||
) |
Definition at line 38 of file model_fit.cpp.
cv::Mat swri_opencv_util::FitAffineTransform2d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2 | ||
) |
Definition at line 193 of file model_fit.cpp.
LineModel3d swri_opencv_util::FitLine3d | ( | const cv::Mat & | points | ) |
Definition at line 416 of file model_fit.cpp.
PlaneModel swri_opencv_util::FitPlane | ( | const cv::Mat & | points | ) |
Definition at line 317 of file model_fit.cpp.
cv::Mat swri_opencv_util::FitRigidTransform2d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2 | ||
) |
Definition at line 72 of file model_fit.cpp.
cv::Mat swri_opencv_util::FitRotation3d | ( | const cv::Mat & | points1, |
const cv::Mat & | points2 | ||
) |
Definition at line 127 of file model_fit.cpp.
cv::Mat swri_opencv_util::overlayColor | ( | const cv::Mat & | src, |
const cv::Mat & | mask, | ||
const cv::Scalar & | color, | ||
double | alpha | ||
) |
void swri_opencv_util::SetAlpha | ( | cv::Mat & | mat, |
uint8_t | alpha | ||
) |
Definition at line 203 of file convert.cpp.
void swri_opencv_util::ShowScaled | ( | const std::string & | name, |
const cv::Mat & | mat, | ||
const cv::Mat & | mask = cv::Mat() , |
||
double | a = -1.0 , |
||
double | b = 0.0 |
||
) |
cv::Mat swri_opencv_util::ToBgra8 | ( | const cv::Mat & | mat, |
const cv::Mat & | mask = cv::Mat() , |
||
bool | is_rgb = false , |
||
double | a = 0.0 , |
||
double | b = 0.0 |
||
) |
Definition at line 38 of file convert.cpp.
bool swri_opencv_util::Valid2dPointCorrespondences | ( | const cv::Mat & | points1, |
const cv::Mat & | points2 | ||
) |
Definition at line 265 of file models.cpp.
bool swri_opencv_util::Valid3dPointCorrespondences | ( | const cv::Mat & | points1, |
const cv::Mat & | points2 | ||
) |
Definition at line 292 of file models.cpp.
bool swri_opencv_util::ZipCorrespondences | ( | const cv::Mat & | points1, |
const cv::Mat & | points2, | ||
cv::Mat & | correspondences | ||
) |
Definition at line 319 of file models.cpp.