#include <stdio.h>
#include <opencv2/core/core.hpp>
Go to the source code of this file.
Functions | |
void | cvDistort (const double *pIntrinsicDistort, const double *pDistortion, const double *pSrc, double *pDes) |
Distorts a point. | |
void | cvDistort (const CvMat *pIntrinsicDistort, const CvMat *pDistortion, const CvPoint2D64f *pSrc, CvPoint2D64f *pDes) |
Distorts a point. | |
void | cvDistort (const CvMat *pIntrinsicDistort, const CvMat *pDistortion, const CvPoint *pSrc, CvPoint *pDes) |
Distorts a point. | |
void | cvInitUndistortMapExact (const CvMat *pIntrinsicDistort, const CvMat *pDistortion, CvMat *pMapX, CvMat *pMapY) |
Undistort a image by using the equations x = dx*(1 + k1r^2 + k2r^4) + 2*p1*dx*dy + p2(r^2+2*dx^2) y = dy*(1 + k1r^2 + k2r^4) + p1(r^2+2*dy^2) + 2*p2*dx*dy. | |
void | cvProjectPoint (const double *pMintMext, const double *pSrc, double *pDes) |
projects a 3D point into the image plane | |
void | cvProjectPoint (const CvMat *pMintMext, const CvPoint2D64f *pSrc, CvPoint2D64f *pDes) |
projects a 3D point into the image plane | |
template<typename A , typename B > | |
void | cvProjectPoint (const CvMat *pMintMext, const A *pSrc, B *pDes) |
projects a 3D point into the image plane | |
bool | cvUndistort (const double *pIntrinsicDistort, const double *pDistortion, const double *pSrc, double *pDes, double maxError=1) |
Undistorts a point. | |
bool | cvUndistort (const CvMat *pIntrinsicDistort, const CvMat *pDistortion, const CvPoint2D64f *pSrc, CvPoint2D64f *pDes, double maxError=1) |
Undistorts a point. | |
void | cvUndistortExact (const CvMat *pIntrinsicDistort, const CvMat *pDistortion, const IplImage *pSrc, IplImage *pDes) |
Undistort a image by using the equations x = dx*(1 + k1r^2 + k2r^4) + 2*p1*dx*dy + p2(r^2+2*dx^2) y = dy*(1 + k1r^2 + k2r^4) + p1(r^2+2*dy^2) + 2*p2*dx*dy. | |
bool | Undistort (const CvMat *pIntrinsicDistort, const CvMat *pDistortion, const CvPoint *pSrc, CvPoint *pDes, double maxError=1) |
Undistorts a point. |
void cvDistort | ( | const double * | pIntrinsicDistort, |
const double * | pDistortion, | ||
const double * | pSrc, | ||
double * | pDes | ||
) | [inline] |
Distorts a point.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 26 of file cvgeometry.h.
void cvDistort | ( | const CvMat * | pIntrinsicDistort, |
const CvMat * | pDistortion, | ||
const CvPoint2D64f * | pSrc, | ||
CvPoint2D64f * | pDes | ||
) | [inline] |
Distorts a point.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 62 of file cvgeometry.h.
void cvDistort | ( | const CvMat * | pIntrinsicDistort, |
const CvMat * | pDistortion, | ||
const CvPoint * | pSrc, | ||
CvPoint * | pDes | ||
) | [inline] |
Distorts a point.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 73 of file cvgeometry.h.
void cvInitUndistortMapExact | ( | const CvMat * | pIntrinsicDistort, |
const CvMat * | pDistortion, | ||
CvMat * | pMapX, | ||
CvMat * | pMapY | ||
) | [inline] |
Undistort a image by using the equations
x = dx*(1 + k1r^2 + k2r^4) + 2*p1*dx*dy + p2(r^2+2*dx^2)
y = dy*(1 + k1r^2 + k2r^4) + p1(r^2+2*dy^2) + 2*p2*dx*dy.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pMapX | destination X map (it must be of the type 32fC1 -> float) |
pMapY | destination Y map (it must be of the type 32fC1 -> float) |
Definition at line 88 of file cvgeometry.h.
void cvProjectPoint | ( | const double * | pMintMext, |
const double * | pSrc, | ||
double * | pDes | ||
) | [inline] |
projects a 3D point into the image plane
pMintMext | = Mint*Mext [4x4] |
pSrc | source point 3D [x, y, z] |
pDes | destination point 2D [x, y] |
Definition at line 184 of file cvgeometry.h.
void cvProjectPoint | ( | const CvMat * | pMintMext, |
const CvPoint2D64f * | pSrc, | ||
CvPoint2D64f * | pDes | ||
) | [inline] |
projects a 3D point into the image plane
pMintMext | = Mint*Mext [4x4] |
pSrc | source point 3D [x, y, z] |
pDes | destination point 2D [x, y] |
Definition at line 198 of file cvgeometry.h.
void cvProjectPoint | ( | const CvMat * | pMintMext, |
const A * | pSrc, | ||
B * | pDes | ||
) | [inline] |
projects a 3D point into the image plane
pMintMext | = Mint*Mext [4x4] |
pSrc | source point 3D [x, y, z] |
pDes | destination point 2D [x, y] |
Definition at line 208 of file cvgeometry.h.
bool cvUndistort | ( | const double * | pIntrinsicDistort, |
const double * | pDistortion, | ||
const double * | pSrc, | ||
double * | pDes, | ||
double | maxError = 1 |
||
) | [inline] |
Undistorts a point.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 134 of file cvgeometry.h.
bool cvUndistort | ( | const CvMat * | pIntrinsicDistort, |
const CvMat * | pDistortion, | ||
const CvPoint2D64f * | pSrc, | ||
CvPoint2D64f * | pDes, | ||
double | maxError = 1 |
||
) | [inline] |
Undistorts a point.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 160 of file cvgeometry.h.
void cvUndistortExact | ( | const CvMat * | pIntrinsicDistort, |
const CvMat * | pDistortion, | ||
const IplImage * | pSrc, | ||
IplImage * | pDes | ||
) | [inline] |
Undistort a image by using the equations
x = dx*(1 + k1r^2 + k2r^4) + 2*p1*dx*dy + p2(r^2+2*dx^2)
y = dy*(1 + k1r^2 + k2r^4) + p1(r^2+2*dy^2) + 2*p2*dx*dy.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 118 of file cvgeometry.h.
bool Undistort | ( | const CvMat * | pIntrinsicDistort, |
const CvMat * | pDistortion, | ||
const CvPoint * | pSrc, | ||
CvPoint * | pDes, | ||
double | maxError = 1 |
||
) | [inline] |
Undistorts a point.
pIntrinsicDistort | Intrinsic Matrinx of the distort image (camera image) in [3x3] matrix |
pDistortion | DistortionCoeff pointer to an array [k1, k2, p1, p2] |
pSrc | source point [x, y] |
pDes | destination point [x, y] |
Definition at line 171 of file cvgeometry.h.