Class for representing a simple fundamental matrix. More...
#include <FundamentalMatrix.h>
Public Member Functions | |
Matrix3 | matrix () const |
SimpleFundamentalMatrix () | |
Default constructor. More... | |
SimpleFundamentalMatrix (const EssentialMatrix &E, double fa, double fb, const Point2 &ca, const Point2 &cb) | |
Construct from essential matrix and focal lengths. More... | |
Testable | |
Print the SimpleFundamentalMatrix | |
void | print (const std::string &s="") const |
bool | equals (const SimpleFundamentalMatrix &other, double tol=1e-9) const |
Check equality within a tolerance. More... | |
Private Member Functions | |
Matrix3 | Ka () const |
Return the left calibration matrix. More... | |
Matrix3 | Kb () const |
Return the right calibration matrix. More... | |
Private Attributes | |
Point2 | ca_ |
Principal point for left camera. More... | |
Point2 | cb_ |
Principal point for right camera. More... | |
EssentialMatrix | E_ |
Essential matrix. More... | |
double | fa_ |
Focal length for left camera. More... | |
double | fb_ |
Focal length for right camera. More... | |
Manifold | |
enum | { dimension = 7 } |
size_t | dim () const |
Vector | localCoordinates (const SimpleFundamentalMatrix &F) const |
Return local coordinates with respect to another SimpleFundamentalMatrix. More... | |
SimpleFundamentalMatrix | retract (const Vector &delta) const |
Retract the given vector to get a new SimpleFundamentalMatrix. More... | |
static size_t | Dim () |
Class for representing a simple fundamental matrix.
This class represents a simple fundamental matrix, which is a parameterization of the essential matrix and focal lengths for left and right cameras. Principal points are not part of the manifold but a convenience.
Definition at line 128 of file FundamentalMatrix.h.
anonymous enum |
Enumerator | |
---|---|
dimension |
Definition at line 175 of file FundamentalMatrix.h.
|
inline |
Default constructor.
Definition at line 144 of file FundamentalMatrix.h.
|
inline |
Construct from essential matrix and focal lengths.
E | Essential matrix |
fa | Focal length for left camera |
fb | Focal length for right camera |
ca | Principal point for left camera |
cb | Principal point for right camera |
Definition at line 155 of file FundamentalMatrix.h.
|
inlinestatic |
Definition at line 176 of file FundamentalMatrix.h.
|
inline |
Definition at line 177 of file FundamentalMatrix.h.
bool gtsam::SimpleFundamentalMatrix::equals | ( | const SimpleFundamentalMatrix & | other, |
double | tol = 1e-9 |
||
) | const |
Check equality within a tolerance.
Definition at line 126 of file FundamentalMatrix.cpp.
|
private |
Return the left calibration matrix.
Definition at line 103 of file FundamentalMatrix.cpp.
|
private |
Return the right calibration matrix.
Definition at line 109 of file FundamentalMatrix.cpp.
Vector gtsam::SimpleFundamentalMatrix::localCoordinates | ( | const SimpleFundamentalMatrix & | F | ) | const |
Return local coordinates with respect to another SimpleFundamentalMatrix.
Definition at line 133 of file FundamentalMatrix.cpp.
Matrix3 gtsam::SimpleFundamentalMatrix::matrix | ( | ) | const |
Return the fundamental matrix representation F = Ka^(-T) * E * Kb^(-1)
Definition at line 115 of file FundamentalMatrix.cpp.
void gtsam::SimpleFundamentalMatrix::print | ( | const std::string & | s = "" | ) | const |
Definition at line 119 of file FundamentalMatrix.cpp.
SimpleFundamentalMatrix gtsam::SimpleFundamentalMatrix::retract | ( | const Vector & | delta | ) | const |
Retract the given vector to get a new SimpleFundamentalMatrix.
Definition at line 142 of file FundamentalMatrix.cpp.
|
private |
Principal point for left camera.
Definition at line 133 of file FundamentalMatrix.h.
|
private |
Principal point for right camera.
Definition at line 134 of file FundamentalMatrix.h.
|
private |
Essential matrix.
Definition at line 130 of file FundamentalMatrix.h.
|
private |
Focal length for left camera.
Definition at line 131 of file FundamentalMatrix.h.
|
private |
Focal length for right camera.
Definition at line 132 of file FundamentalMatrix.h.