#include <Homography.hh>
Public Member Functions | |
bool | ComputeAff (double a1[2], double a2[2], double a3[2], double b1[2], double b2[2], double b3[2], double H[9]) |
bool | ComputeHom (double a1[2], double a2[2], double a3[2], double a4[2], double b1[2], double b2[2], double b3[2], double b4[2], double H[9]) |
bool | ComputeHomLS (double H[9], bool normalize=true) |
bool | ComputeHomRobustLS (double H[9], bool normalize=true, double thrInlier=1., double thrAngle=1.) |
bool | EstimateAff (double H[9], int &nbOutliers, double inlPcent=.8, bool returnOutl=false, int normalize=1, int verbose=1) |
bool | EstimateHom (double H[9], int &nbOutliers, double inlPcent=.8, bool returnOutl=false, int normalize=1, int NLrefine=HOMEST_SYM_XFER_ERROR, int verbose=1) |
Homography () | |
Homography (unsigned nbPoints, unsigned nbLines=0) | |
void | InsertNext (double pt1[2], double pt2[2]) |
void | InsertNextLn (double ln1[2], double ln2[2]) |
void | InsertNextLn (double a1[2], double b1[2], double a2[2], double b2[2]) |
void | InsertNextPt (double pt1[2], double pt2[2]) |
void | LinePts2Para (double p1[2], double p2[2], double l[3]) |
void | Resize (unsigned nbPoints, unsigned nbLines=0) |
void | SetFirst () |
~Homography () | |
Public Attributes | |
Array< int > | outl |
Array< int > | outlLns |
Private Member Functions | |
void | CountInlierLns (double H[9], double thr, double thrAngle, int &inl) |
void | CountInlierPts (double H[9], double thr, int &inl) |
void | DenormalizeH (double nH[9], double T1[9], double T2[9], double H[9]) |
void | GetRandIdx (unsigned size, unsigned num, P::Array< unsigned > &idx) |
void | InsertLineCoeff (Vector2 &ln1, Vector2 &ln2, double *d) |
void | InsertPointCoeff (Vector2 &pt1, Vector2 &pt2, double *d) |
void | NormalizeH (double H[9], double T1[9], double T2[9], double nH[9]) |
void | NormalizeLns (double T[9], Array< Vector2 > &in, unsigned numLns, Array< Vector2 > &out) |
void | NormalizePts (Array< Vector2 > &in, unsigned numPts, Array< Vector2 > &out, double T[9]) |
void | SetDataMatrix (double *d, double H[9], double thr, double thrAngle, int &numInl) |
void | SetDataMatrixLns (Array< Vector2 > &lns1, Array< Vector2 > &lns2, unsigned numLns, unsigned start, CvMat *A) |
void | SetDataMatrixPts (Array< Vector2 > &pts1, Array< Vector2 > &pts2, unsigned numPts, unsigned start, CvMat *A) |
bool | SolveHomography (CvMat *A, CvMat *W, CvMat *Ut, CvMat *Vt, double H[9]) |
Private Attributes | |
double * | invT |
unsigned | lastLn |
unsigned | lastPt |
Array< Vector2 > | lns1 |
Array< Vector2 > | lns2 |
Array< Vector2 > | pts1 |
Array< Vector2 > | pts2 |
double * | T1 |
Definition at line 27 of file Homography.hh.
Definition at line 22 of file Homography.cc.
P::Homography::Homography | ( | unsigned | nbPoints, |
unsigned | nbLines = 0 |
||
) |
Definition at line 27 of file Homography.cc.
Definition at line 42 of file Homography.cc.
bool P::Homography::ComputeAff | ( | double | a1[2], |
double | a2[2], | ||
double | a3[2], | ||
double | b1[2], | ||
double | b2[2], | ||
double | b3[2], | ||
double | H[9] | ||
) |
Compute affine mapping of three points
Definition at line 523 of file Homography.cc.
bool P::Homography::ComputeHom | ( | double | a1[2], |
double | a2[2], | ||
double | a3[2], | ||
double | a4[2], | ||
double | b1[2], | ||
double | b2[2], | ||
double | b3[2], | ||
double | b4[2], | ||
double | H[9] | ||
) |
Compute projective mapping of four points
Definition at line 470 of file Homography.cc.
bool P::Homography::ComputeHomLS | ( | double | H[9], |
bool | normalize = true |
||
) |
Compute the least squares homography matrix using points and lines This implementation needs points (for normalisation) and also uses lines for least squares
Definition at line 560 of file Homography.cc.
bool P::Homography::ComputeHomRobustLS | ( | double | H[9], |
bool | normalize = true , |
||
double | thrInlier = 1. , |
||
double | thrAngle = 1. |
||
) |
Compute the least squares homography matrix using points and lines This implementation needs points (for normalisation) and also uses lines for least squares
Definition at line 615 of file Homography.cc.
void P::Homography::CountInlierLns | ( | double | H[9], |
double | thr, | ||
double | thrAngle, | ||
int & | inl | ||
) | [private] |
Count point inlier
Definition at line 84 of file Homography.cc.
void P::Homography::CountInlierPts | ( | double | H[9], |
double | thr, | ||
int & | inl | ||
) | [private] |
Count point inlier
Definition at line 68 of file Homography.cc.
void P::Homography::DenormalizeH | ( | double | nH[9], |
double | T1[9], | ||
double | T2[9], | ||
double | H[9] | ||
) | [private] |
Denormalize H H = T2^-1 * nH * T1
Definition at line 389 of file Homography.cc.
bool P::Homography::EstimateAff | ( | double | H[9], |
int & | nbOutliers, | ||
double | inlPcent = .8 , |
||
bool | returnOutl = false , |
||
int | normalize = 1 , |
||
int | verbose = 1 |
||
) |
Compute affine homography matrix robust to outlier
Definition at line 446 of file Homography.cc.
bool P::Homography::EstimateHom | ( | double | H[9], |
int & | nbOutliers, | ||
double | inlPcent = .8 , |
||
bool | returnOutl = false , |
||
int | normalize = 1 , |
||
int | NLrefine = HOMEST_SYM_XFER_ERROR , |
||
int | verbose = 1 |
||
) |
Compute homography matrix robust to outlier
Definition at line 414 of file Homography.cc.
void P::Homography::GetRandIdx | ( | unsigned | size, |
unsigned | num, | ||
P::Array< unsigned > & | idx | ||
) | [private] |
GetRandIdx
Definition at line 52 of file Homography.cc.
void P::Homography::InsertLineCoeff | ( | Vector2 & | ln1, |
Vector2 & | ln2, | ||
double * | d | ||
) | [inline, private] |
Insert a line to the least squares homography matrix
Definition at line 131 of file Homography.hh.
void P::Homography::InsertNext | ( | double | pt1[2], |
double | pt2[2] | ||
) | [inline] |
insert next point
Definition at line 191 of file Homography.hh.
void P::Homography::InsertNextLn | ( | double | ln1[2], |
double | ln2[2] | ||
) | [inline] |
insert next line definition of lines: ax + by + c = 1 ( a ) ( a/c ) -> l = | b | = | b/c | ( c ) ( 1 )
Definition at line 238 of file Homography.hh.
void P::Homography::InsertNextLn | ( | double | a1[2], |
double | b1[2], | ||
double | a2[2], | ||
double | b2[2] | ||
) | [inline] |
insert line defined by two points [a1 b1] and [a2 b2]
Definition at line 259 of file Homography.hh.
void P::Homography::InsertNextPt | ( | double | pt1[2], |
double | pt2[2] | ||
) | [inline] |
insert next point
Definition at line 212 of file Homography.hh.
void P::Homography::InsertPointCoeff | ( | Vector2 & | pt1, |
Vector2 & | pt2, | ||
double * | d | ||
) | [inline, private] |
Insert a point to the least squares homography matrix
Definition at line 99 of file Homography.hh.
void P::Homography::LinePts2Para | ( | double | p1[2], |
double | p2[2], | ||
double | l[3] | ||
) | [inline] |
Compute parameters of a line defined by two points
Definition at line 287 of file Homography.hh.
void P::Homography::NormalizeH | ( | double | H[9], |
double | T1[9], | ||
double | T2[9], | ||
double | nH[9] | ||
) | [private] |
Normalize H nH = T2 * H * T1^-1
Definition at line 376 of file Homography.cc.
void P::Homography::NormalizeLns | ( | double | T[9], |
Array< Vector2 > & | in, | ||
unsigned | numLns, | ||
Array< Vector2 > & | out | ||
) | [private] |
Normalize lines (see Dubrofsky, 2008)
Definition at line 278 of file Homography.cc.
void P::Homography::NormalizePts | ( | Array< Vector2 > & | in, |
unsigned | numPts, | ||
Array< Vector2 > & | out, | ||
double | T[9] | ||
) | [private] |
Normalize points suggested by Hartley
Definition at line 235 of file Homography.cc.
void P::Homography::Resize | ( | unsigned | nbPoints, |
unsigned | nbLines = 0 |
||
) | [inline] |
allocate memory for points
Definition at line 163 of file Homography.hh.
void P::Homography::SetDataMatrix | ( | double * | d, |
double | H[9], | ||
double | thr, | ||
double | thrAngle, | ||
int & | numInl | ||
) | [private] |
set least squares deata matrix (Ai*h = 0)
Definition at line 133 of file Homography.cc.
void P::Homography::SetDataMatrixLns | ( | Array< Vector2 > & | lns1, |
Array< Vector2 > & | lns2, | ||
unsigned | numLns, | ||
unsigned | start, | ||
CvMat * | A | ||
) | [private] |
Construct data matrix
Definition at line 336 of file Homography.cc.
void P::Homography::SetDataMatrixPts | ( | Array< Vector2 > & | pts1, |
Array< Vector2 > & | pts2, | ||
unsigned | numPts, | ||
unsigned | start, | ||
CvMat * | A | ||
) | [private] |
Construct data matrix
Definition at line 297 of file Homography.cc.
void P::Homography::SetFirst | ( | ) | [inline] |
set last pointer to first point
Definition at line 182 of file Homography.hh.
bool P::Homography::SolveHomography | ( | CvMat * | A, |
CvMat * | W, | ||
CvMat * | Ut, | ||
CvMat * | Vt, | ||
double | H[9] | ||
) | [private] |
Uses SVD to solve the matrix
Definition at line 213 of file Homography.cc.
double * P::Homography::invT [private] |
Definition at line 36 of file Homography.hh.
unsigned P::Homography::lastLn [private] |
Definition at line 34 of file Homography.hh.
unsigned P::Homography::lastPt [private] |
Definition at line 33 of file Homography.hh.
Array<Vector2> P::Homography::lns1 [private] |
Definition at line 31 of file Homography.hh.
Array<Vector2> P::Homography::lns2 [private] |
Definition at line 31 of file Homography.hh.
Array<int> P::Homography::outl |
Definition at line 57 of file Homography.hh.
Definition at line 58 of file Homography.hh.
Array<Vector2> P::Homography::pts1 [private] |
Definition at line 30 of file Homography.hh.
Array<Vector2> P::Homography::pts2 [private] |
Definition at line 30 of file Homography.hh.
double* P::Homography::T1 [private] |
Definition at line 36 of file Homography.hh.