Public Member Functions | Private Member Functions | Private Attributes | List of all members
gtsam::SimpleFundamentalMatrix Class Reference

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
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 ()
 

Detailed Description

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.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
dimension 

Definition at line 175 of file FundamentalMatrix.h.

Constructor & Destructor Documentation

◆ SimpleFundamentalMatrix() [1/2]

gtsam::SimpleFundamentalMatrix::SimpleFundamentalMatrix ( )
inline

Default constructor.

Definition at line 144 of file FundamentalMatrix.h.

◆ SimpleFundamentalMatrix() [2/2]

gtsam::SimpleFundamentalMatrix::SimpleFundamentalMatrix ( const EssentialMatrix E,
double  fa,
double  fb,
const Point2 ca,
const Point2 cb 
)
inline

Construct from essential matrix and focal lengths.

Parameters
EEssential matrix
faFocal length for left camera
fbFocal length for right camera
caPrincipal point for left camera
cbPrincipal point for right camera

Definition at line 155 of file FundamentalMatrix.h.

Member Function Documentation

◆ Dim()

static size_t gtsam::SimpleFundamentalMatrix::Dim ( )
inlinestatic

Definition at line 176 of file FundamentalMatrix.h.

◆ dim()

size_t gtsam::SimpleFundamentalMatrix::dim ( ) const
inline

Definition at line 177 of file FundamentalMatrix.h.

◆ equals()

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.

◆ Ka()

Matrix3 gtsam::SimpleFundamentalMatrix::Ka ( ) const
private

Return the left calibration matrix.

Definition at line 103 of file FundamentalMatrix.cpp.

◆ Kb()

Matrix3 gtsam::SimpleFundamentalMatrix::Kb ( ) const
private

Return the right calibration matrix.

Definition at line 109 of file FundamentalMatrix.cpp.

◆ localCoordinates()

Vector gtsam::SimpleFundamentalMatrix::localCoordinates ( const SimpleFundamentalMatrix F) const

Return local coordinates with respect to another SimpleFundamentalMatrix.

Definition at line 133 of file FundamentalMatrix.cpp.

◆ matrix()

Matrix3 gtsam::SimpleFundamentalMatrix::matrix ( ) const

Return the fundamental matrix representation F = Ka^(-T) * E * Kb^(-1)

Definition at line 115 of file FundamentalMatrix.cpp.

◆ print()

void gtsam::SimpleFundamentalMatrix::print ( const std::string &  s = "") const

Definition at line 119 of file FundamentalMatrix.cpp.

◆ retract()

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.

Member Data Documentation

◆ ca_

Point2 gtsam::SimpleFundamentalMatrix::ca_
private

Principal point for left camera.

Definition at line 133 of file FundamentalMatrix.h.

◆ cb_

Point2 gtsam::SimpleFundamentalMatrix::cb_
private

Principal point for right camera.

Definition at line 134 of file FundamentalMatrix.h.

◆ E_

EssentialMatrix gtsam::SimpleFundamentalMatrix::E_
private

Essential matrix.

Definition at line 130 of file FundamentalMatrix.h.

◆ fa_

double gtsam::SimpleFundamentalMatrix::fa_
private

Focal length for left camera.

Definition at line 131 of file FundamentalMatrix.h.

◆ fb_

double gtsam::SimpleFundamentalMatrix::fb_
private

Focal length for right camera.

Definition at line 132 of file FundamentalMatrix.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:16:28