|
std::vector< TooN::Matrix< 3 > > | tag::five_point (const std::tr1::array< std::pair< TooN::Vector< 3 >, TooN::Vector< 3 > >, 5 > &points) |
|
std::vector< TooN::SE3<> > | tag::se3_from_E (const TooN::Matrix< 3 > &E) |
|
TooN::SE3 | tag::optimize_epipolar (const std::vector< std::pair< TooN::Vector< 3 >, TooN::Vector< 3 > > > &points, const TooN::SE3<> &initial) |
|
std::pair< double, double > | tag::essential_reprojection_errors_squared (const TooN::Matrix< 3 > &E, const TooN::Vector< 3 > &q, const TooN::Vector< 3 > &p) |
|
std::pair< double, double > | tag::essential_reprojection_errors (const TooN::Matrix< 3 > &E, const TooN::Vector< 3 > &q, const TooN::Vector< 3 > &p) |
|
template<class V , class M > |
void | tag::getCrossProductMatrix (const V &vec, M &result) |
|
template<class V > |
TooN::Matrix< 3 > | tag::getCrossProductMatrix (const V &vec) |
|
template<class M > |
void | tag::getEssentialMatrix (const TooN::SE3<> &transform, M &E) |
|
TooN::Matrix< 3 > | tag::getEssentialMatrix (const TooN::SE3<> &transform) |
|
various functions dealing with essential matrices including 5 point estimation after Nister, reconstruction of R,t from essential matrix after Horn, and construction of E from R,t.
std::pair<double, double> tag::essential_reprojection_errors |
( |
const TooN::Matrix< 3 > & |
E, |
|
|
const TooN::Vector< 3 > & |
q, |
|
|
const TooN::Vector< 3 > & |
p |
|
) |
| |
Given an essential matrix E and two points p and q, this functions computes the reprojection errors given by the signed distance from p to the line defined by and the signed distance from q to the line defined by . If E is not an essential matrix then the errors will not be sensible.
- Parameters
-
E | E: essential matrix |
q | q: right hand (first) point |
p | p: left hand (second) point |
- Returns
- the reprojection errors
std::pair<double, double> tag::essential_reprojection_errors_squared |
( |
const TooN::Matrix< 3 > & |
E, |
|
|
const TooN::Vector< 3 > & |
q, |
|
|
const TooN::Vector< 3 > & |
p |
|
) |
| |
Given an essential matrix E and two points p and q, this functions computes the reprojection errors given by the squared distance from p to the line defined by and the squared distance from q to the line defined by . If E is not an essential matrix then the errors will not be sensible. This function avoids a sqrt compared to tag::essential_reprojection_errors.
- Parameters
-
E | E: essential matrix |
q | q: right hand (first) point |
p | p: left hand (second) point |
- Returns
- the reprojection errors
std::vector<TooN::Matrix<3> > tag::five_point |
( |
const std::tr1::array< std::pair< TooN::Vector< 3 >, TooN::Vector< 3 > >, 5 > & |
points | ) |
|
Computes essential matrices representing the epipolar geometry between correspondences. This function implements Nister's 5 point algorithm. For all of the input points pairs, each out matrix satisfies the condition:
- Parameters
-
points | a array of pairs of directions in 3 space containing correspondences |
initial | an inital value for the transformation used as starting point of the optimization |
- Returns
- the optimized transformation
template<class V , class M >
void tag::getCrossProductMatrix |
( |
const V & |
vec, |
|
|
M & |
result |
|
) |
| |
|
inline |
template<class V >
TooN::Matrix<3> tag::getCrossProductMatrix |
( |
const V & |
vec | ) |
|
|
inline |
creates an returns a cross product matrix M from a 3 vector v, such that for all vectors w, the following holds: v ^ w = M * w
- Parameters
-
- Returns
- the 3x3 matrix to set to the cross product matrix
References tag::getCrossProductMatrix().
template<class M >
void tag::getEssentialMatrix |
( |
const TooN::SE3<> & |
transform, |
|
|
M & |
E |
|
) |
| |
|
inline |
creates the essential matrix corresponding to a given transformation
- Parameters
-
| transform | the transformation as SE3 |
[out] | E | the 3x3 matrix set to the essential matrix |
Referenced by tag::getEssentialMatrix().
TooN::Matrix<3> tag::getEssentialMatrix |
( |
const TooN::SE3<> & |
transform | ) |
|
|
inline |
creates and returns the essential matrix corresponding to a given transformation
- Parameters
-
transform | the transformation as SE3 |
- Returns
- the 3x3 matrix set to the essential matrix
References tag::getEssentialMatrix().
TooN::SE3 tag::optimize_epipolar |
( |
const std::vector< std::pair< TooN::Vector< 3 >, TooN::Vector< 3 > > > & |
points, |
|
|
const TooN::SE3<> & |
initial |
|
) |
| |
optimizes a transformation representing the epipolar geometry between correspondences. This function minimizes the algebraic error of the epipolar geometry through non-linear optimization of the rotation and direction of the translation. For all of the input points pairs, each out matrix satisfies the condition:
- Parameters
-
points | a vector of pairs of directions in 3 space containing correspondences |
initial | an inital value for the transformation used as starting point of the optimization |
- Returns
- the optimized transformation
References tag::getCrossProductMatrix().
std::vector< TooN::SE3<> > tag::se3_from_E |
( |
const TooN::Matrix< 3 > & |
E | ) |
|
reconstructs possible R,t from essential matrix E. The implementation follows the algorithm in Recovering Baseline and Orientation from 'Essential' Matrix BKP Horn, Jan 1990
- Parameters
-
- Returns
- vector with 4 SE3s representing the possible transformations
References tag::getCrossProductMatrix().