Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two views. More...
#include <FundamentalMatrix.h>
Public Member Functions | |
FundamentalMatrix () | |
Default constructor. More... | |
FundamentalMatrix (const Matrix3 &F) | |
Construct from a 3x3 matrix using SVD. More... | |
FundamentalMatrix (const Matrix3 &Ka, const EssentialMatrix &E, const Matrix3 &Kb) | |
Construct from essential matrix and calibration matrices. More... | |
FundamentalMatrix (const Matrix3 &Ka, const Pose3 &aPb, const Matrix3 &Kb) | |
Construct from calibration matrices Ka, Kb, and pose aPb. More... | |
FundamentalMatrix (const Matrix3 &U, double s, const Matrix3 &V) | |
Construct from U, V, and scalar s. More... | |
Matrix3 | matrix () const |
Return the fundamental matrix representation. More... | |
Testable | |
Print the FundamentalMatrix | |
void | print (const std::string &s="") const |
bool | equals (const FundamentalMatrix &other, double tol=1e-9) const |
Private Member Functions | |
FundamentalMatrix (const Rot3 &U, double s, const Rot3 &V) | |
Private constructor for internal use. More... | |
void | initialize (Matrix3 U, double s, Matrix3 V) |
Initialize SO(3) matrices from general O(3) matrices. More... | |
Private Attributes | |
double | s_ |
Scalar parameter for S. More... | |
Rot3 | U_ |
Left rotation. More... | |
Rot3 | V_ |
Right rotation. More... | |
Manifold | |
enum | { dimension = 7 } |
size_t | dim () const |
Vector | localCoordinates (const FundamentalMatrix &F) const |
Return local coordinates with respect to another FundamentalMatrix. More... | |
FundamentalMatrix | retract (const Vector &delta) const |
Retract the given vector to get a new FundamentalMatrix. More... | |
static size_t | Dim () |
Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two views.
The FundamentalMatrix class encapsulates the fundamental matrix, which relates corresponding points in stereo images. It is parameterized by two rotation matrices (U and V) and a scalar parameter (s). Using these values, the fundamental matrix is represented as
F = U * diag(1, s, 0) * V^T
Definition at line 28 of file FundamentalMatrix.h.
anonymous enum |
Enumerator | |
---|---|
dimension |
Definition at line 101 of file FundamentalMatrix.h.
|
inline |
Default constructor.
Definition at line 36 of file FundamentalMatrix.h.
gtsam::FundamentalMatrix::FundamentalMatrix | ( | const Matrix3 & | U, |
double | s, | ||
const Matrix3 & | V | ||
) |
Construct from U, V, and scalar s.
Initializes the FundamentalMatrix From the SVD representation U*diag(1,s,0)*V^T. It will internally convert to using SO(3).
Definition at line 31 of file FundamentalMatrix.cpp.
gtsam::FundamentalMatrix::FundamentalMatrix | ( | const Matrix3 & | F | ) |
Construct from a 3x3 matrix using SVD.
Initializes the FundamentalMatrix by performing SVD on the given matrix and ensuring U and V are not reflections.
F | A 3x3 matrix representing the fundamental matrix |
Definition at line 36 of file FundamentalMatrix.cpp.
|
inline |
Construct from essential matrix and calibration matrices.
Initializes the FundamentalMatrix from the given essential matrix E and calibration matrices Ka and Kb, using F = Ka^(-T) * E * Kb^(-1) and then calls constructor that decomposes F via SVD.
E | Essential matrix |
Ka | Calibration matrix for the left camera |
Kb | Calibration matrix for the right camera |
Definition at line 68 of file FundamentalMatrix.h.
|
inline |
Construct from calibration matrices Ka, Kb, and pose aPb.
Initializes the FundamentalMatrix from the given calibration matrices Ka and Kb, and the pose aPb.
Ka | Calibration matrix for the left camera |
aPb | Pose from the left to the right camera |
Kb | Calibration matrix for the right camera |
Definition at line 83 of file FundamentalMatrix.h.
|
inlineprivate |
Private constructor for internal use.
Definition at line 113 of file FundamentalMatrix.h.
|
inlinestatic |
Definition at line 102 of file FundamentalMatrix.h.
|
inline |
Definition at line 103 of file FundamentalMatrix.h.
bool gtsam::FundamentalMatrix::equals | ( | const FundamentalMatrix & | other, |
double | tol = 1e-9 |
||
) | const |
Check if the FundamentalMatrix is equal to another within a tolerance
Definition at line 81 of file FundamentalMatrix.cpp.
|
private |
Initialize SO(3) matrices from general O(3) matrices.
Definition at line 60 of file FundamentalMatrix.cpp.
Vector gtsam::FundamentalMatrix::localCoordinates | ( | const FundamentalMatrix & | F | ) | const |
Return local coordinates with respect to another FundamentalMatrix.
Definition at line 87 of file FundamentalMatrix.cpp.
Matrix3 gtsam::FundamentalMatrix::matrix | ( | ) | const |
Return the fundamental matrix representation.
Definition at line 72 of file FundamentalMatrix.cpp.
void gtsam::FundamentalMatrix::print | ( | const std::string & | s = "" | ) | const |
Definition at line 77 of file FundamentalMatrix.cpp.
FundamentalMatrix gtsam::FundamentalMatrix::retract | ( | const Vector & | delta | ) | const |
Retract the given vector to get a new FundamentalMatrix.
Definition at line 95 of file FundamentalMatrix.cpp.
|
private |
Scalar parameter for S.
Definition at line 31 of file FundamentalMatrix.h.
|
private |
Left rotation.
Definition at line 30 of file FundamentalMatrix.h.
|
private |
Right rotation.
Definition at line 32 of file FundamentalMatrix.h.