Public Types | Protected Attributes | List of all members
gtsam::Cal3 Class Reference

#include <Cal3.h>

Inheritance diagram for gtsam::Cal3:
Inheritance graph
[legend]

Public Types

enum  { dimension = 5 }
 
using shared_ptr = boost::shared_ptr< Cal3 >
 

Public Member Functions

Standard Constructors
 Cal3 ()=default
 Create a default calibration that leaves coordinates unchanged. More...
 
 Cal3 (double fx, double fy, double s, double u0, double v0)
 constructor from doubles More...
 
 Cal3 (const Vector5 &d)
 constructor from vector More...
 
 Cal3 (double fov, int w, int h)
 
virtual ~Cal3 ()
 Virtual destructor. More...
 
Advanced Constructors
 Cal3 (const std::string &path)
 

Protected Attributes

double fx_ = 1.0f
 
double fy_ = 1.0f
 focal length More...
 
double s_ = 0.0f
 skew More...
 
double u0_ = 0.0f
 
double v0_ = 0.0f
 principal point More...
 

Testable

GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Cal3 &cal)
 Output stream operator. More...
 
virtual void print (const std::string &s="") const
 print with optional string More...
 
bool equals (const Cal3 &K, double tol=10e-9) const
 Check if equal up to specified tolerance. More...
 

Standard Interface

double fx () const
 focal length x More...
 
double fy () const
 focal length y More...
 
double aspectRatio () const
 aspect ratio More...
 
double skew () const
 skew More...
 
double px () const
 image center in x More...
 
double py () const
 image center in y More...
 
Point2 principalPoint () const
 return the principal point More...
 
Vector5 vector () const
 vectorized form (column-wise) More...
 
virtual Matrix3 K () const
 return calibration matrix K More...
 
Matrix3 inverse () const
 Return inverted calibration matrix inv(K) More...
 
virtual size_t dim () const
 return DOF, dimensionality of tangent space More...
 
static size_t Dim ()
 return DOF, dimensionality of tangent space More...
 

Advanced Interface

class boost::serialization::access
 Serialization function. More...
 
template<class Archive >
void serialize (Archive &ar, const unsigned int)
 

Detailed Description

Definition at line 69 of file Cal3.h.

Member Typedef Documentation

using gtsam::Cal3::shared_ptr = boost::shared_ptr<Cal3>

Definition at line 78 of file Cal3.h.

Member Enumeration Documentation

anonymous enum
Enumerator
dimension 

Definition at line 76 of file Cal3.h.

Constructor & Destructor Documentation

gtsam::Cal3::Cal3 ( )
default

Create a default calibration that leaves coordinates unchanged.

gtsam::Cal3::Cal3 ( double  fx,
double  fy,
double  s,
double  u0,
double  v0 
)
inline

constructor from doubles

Definition at line 87 of file Cal3.h.

gtsam::Cal3::Cal3 ( const Vector5 &  d)
inline

constructor from vector

Definition at line 91 of file Cal3.h.

gtsam::Cal3::Cal3 ( double  fov,
int  w,
int  h 
)

Easy constructor, takes fov in degrees, asssumes zero skew, unit aspect

Parameters
fovfield of view in degrees
wimage width
himage height

Definition at line 27 of file Cal3.cpp.

virtual gtsam::Cal3::~Cal3 ( )
inlinevirtual

Virtual destructor.

Definition at line 103 of file Cal3.h.

gtsam::Cal3::Cal3 ( const std::string &  path)

Load calibration parameters from calibration_info.txt file located in path directory.

The contents of calibration file should be the 5 parameters in order: fx, fy, s, u0, v0

Parameters
pathpath to directory containing calibration_info.txt.

Definition at line 35 of file Cal3.cpp.

Member Function Documentation

double gtsam::Cal3::aspectRatio ( ) const
inline

aspect ratio

Definition at line 145 of file Cal3.h.

virtual size_t gtsam::Cal3::dim ( ) const
inlinevirtual

return DOF, dimensionality of tangent space

Reimplemented in gtsam::Cal3Fisheye, gtsam::Cal3Bundler, gtsam::Cal3DS2_Base, gtsam::Cal3Unified, gtsam::Cal3_S2Stereo, and gtsam::Cal3DS2.

Definition at line 182 of file Cal3.h.

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

return DOF, dimensionality of tangent space

Definition at line 185 of file Cal3.h.

bool gtsam::Cal3::equals ( const Cal3 K,
double  tol = 10e-9 
) const

Check if equal up to specified tolerance.

Definition at line 59 of file Cal3.cpp.

double gtsam::Cal3::fx ( ) const
inline

focal length x

Definition at line 139 of file Cal3.h.

double gtsam::Cal3::fy ( ) const
inline

focal length y

Definition at line 142 of file Cal3.h.

Matrix3 gtsam::Cal3::inverse ( ) const

Return inverted calibration matrix inv(K)

Definition at line 65 of file Cal3.cpp.

virtual Matrix3 gtsam::Cal3::K ( ) const
inlinevirtual

return calibration matrix K

Reimplemented in gtsam::Cal3_S2Stereo, and gtsam::Cal3Bundler.

Definition at line 167 of file Cal3.h.

Point2 gtsam::Cal3::principalPoint ( ) const
inline

return the principal point

Definition at line 157 of file Cal3.h.

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

print with optional string

Reimplemented in gtsam::Cal3Fisheye, gtsam::Cal3_S2, gtsam::Cal3_S2Stereo, gtsam::Cal3DS2_Base, gtsam::Cal3Unified, gtsam::Cal3Bundler, and gtsam::Cal3DS2.

Definition at line 56 of file Cal3.cpp.

double gtsam::Cal3::px ( ) const
inline

image center in x

Definition at line 151 of file Cal3.h.

double gtsam::Cal3::py ( ) const
inline

image center in y

Definition at line 154 of file Cal3.h.

template<class Archive >
void gtsam::Cal3::serialize ( Archive &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 195 of file Cal3.h.

double gtsam::Cal3::skew ( ) const
inline

skew

Definition at line 148 of file Cal3.h.

Vector5 gtsam::Cal3::vector ( ) const
inline

vectorized form (column-wise)

Definition at line 160 of file Cal3.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function.

Definition at line 193 of file Cal3.h.

GTSAM_EXPORT friend std::ostream& operator<< ( std::ostream &  os,
const Cal3 cal 
)
friend

Output stream operator.

Definition at line 49 of file Cal3.cpp.

Member Data Documentation

double gtsam::Cal3::fx_ = 1.0f
protected

Definition at line 71 of file Cal3.h.

double gtsam::Cal3::fy_ = 1.0f
protected

focal length

Definition at line 71 of file Cal3.h.

double gtsam::Cal3::s_ = 0.0f
protected

skew

Definition at line 72 of file Cal3.h.

double gtsam::Cal3::u0_ = 0.0f
protected

Definition at line 73 of file Cal3.h.

double gtsam::Cal3::v0_ = 0.0f
protected

principal point

Definition at line 73 of file Cal3.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:05