Public Types | Private Types | List of all members
gtsam::Cal3DS2 Class Reference

#include <Cal3DS2.h>

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

Public Types

enum  { dimension = 9 }
 
- Public Types inherited from gtsam::Cal3DS2_Base
enum  { dimension = 9 }
 
- Public Types inherited from gtsam::Cal3
enum  { dimension = 5 }
 
using shared_ptr = boost::shared_ptr< Cal3 >
 

Public Member Functions

Standard Constructors
 Cal3DS2 ()=default
 Default Constructor with only unit focal length. More...
 
 Cal3DS2 (double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1=0.0, double p2=0.0, double tol=1e-5)
 
 ~Cal3DS2 () override
 
Advanced Constructors
 Cal3DS2 (const Vector9 &v)
 
Clone
boost::shared_ptr< Baseclone () const override
 
- Public Member Functions inherited from gtsam::Cal3DS2_Base
 Cal3DS2_Base ()=default
 Default Constructor with only unit focal length. More...
 
 Cal3DS2_Base (double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1=0.0, double p2=0.0, double tol=1e-5)
 
 ~Cal3DS2_Base () override
 
 Cal3DS2_Base (const Vector9 &v)
 
void print (const std::string &s="") const override
 print with optional string More...
 
bool equals (const Cal3DS2_Base &K, double tol=1e-8) const
 assert equality up to a tolerance More...
 
double k1 () const
 First distortion coefficient. More...
 
double k2 () const
 Second distortion coefficient. More...
 
double p1 () const
 First tangential distortion coefficient. More...
 
double p2 () const
 Second tangential distortion coefficient. More...
 
Vector4 k () const
 return distortion parameter vector More...
 
Vector9 vector () const
 Return all parameters as a vector. More...
 
Point2 uncalibrate (const Point2 &p, OptionalJacobian< 2, 9 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
 
Point2 calibrate (const Point2 &p, OptionalJacobian< 2, 9 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
 Convert (distorted) image coordinates uv to intrinsic coordinates xy. More...
 
Matrix2 D2d_intrinsic (const Point2 &p) const
 Derivative of uncalibrate wrpt intrinsic coordinates. More...
 
Matrix29 D2d_calibration (const Point2 &p) const
 Derivative of uncalibrate wrpt the calibration parameters. More...
 
size_t dim () const override
 return DOF, dimensionality of tangent space More...
 
- Public Member Functions inherited from gtsam::Cal3
 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...
 
 Cal3 (const std::string &path)
 
bool equals (const Cal3 &K, double tol=10e-9) const
 Check if equal up to specified tolerance. More...
 
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...
 

Private Types

using Base = Cal3DS2_Base
 

Testable

GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Cal3DS2 &cal)
 Output stream operator. More...
 
void print (const std::string &s="") const override
 print with optional string More...
 
bool equals (const Cal3DS2 &K, double tol=10e-9) const
 assert equality up to a tolerance More...
 

Manifold

Cal3DS2 retract (const Vector &d) const
 Given delta vector, update calibration. More...
 
Vector localCoordinates (const Cal3DS2 &T2) const
 Given a different calibration, calculate update to obtain it. More...
 
size_t dim () const override
 Return dimensions of calibration manifold object. More...
 
static size_t Dim ()
 Return dimensions of calibration manifold object. More...
 

Advanced Interface

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

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::Cal3DS2_Base
static size_t Dim ()
 return DOF, dimensionality of tangent space More...
 
- Static Public Member Functions inherited from gtsam::Cal3
static size_t Dim ()
 return DOF, dimensionality of tangent space More...
 
- Protected Attributes inherited from gtsam::Cal3DS2_Base
double k1_ = 0.0f
 
double k2_ = 0.0f
 radial 2nd-order and 4th-order More...
 
double p1_ = 0.0f
 
double p2_ = 0.0f
 tangential distortion More...
 
double tol_ = 1e-5
 tolerance value when calibrating More...
 
- Protected Attributes inherited from gtsam::Cal3
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...
 

Detailed Description

Definition at line 34 of file Cal3DS2.h.

Member Typedef Documentation

Definition at line 35 of file Cal3DS2.h.

Member Enumeration Documentation

anonymous enum
Enumerator
dimension 

Definition at line 38 of file Cal3DS2.h.

Constructor & Destructor Documentation

gtsam::Cal3DS2::Cal3DS2 ( )
default

Default Constructor with only unit focal length.

gtsam::Cal3DS2::Cal3DS2 ( double  fx,
double  fy,
double  s,
double  u0,
double  v0,
double  k1,
double  k2,
double  p1 = 0.0,
double  p2 = 0.0,
double  tol = 1e-5 
)
inline

Definition at line 46 of file Cal3DS2.h.

gtsam::Cal3DS2::~Cal3DS2 ( )
inlineoverride

Definition at line 50 of file Cal3DS2.h.

gtsam::Cal3DS2::Cal3DS2 ( const Vector9 &  v)
inline

Definition at line 56 of file Cal3DS2.h.

Member Function Documentation

boost::shared_ptr<Base> gtsam::Cal3DS2::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this object

Reimplemented from gtsam::Cal3DS2_Base.

Definition at line 93 of file Cal3DS2.h.

size_t gtsam::Cal3DS2::dim ( ) const
inlineoverridevirtual

Return dimensions of calibration manifold object.

Reimplemented from gtsam::Cal3.

Definition at line 83 of file Cal3DS2.h.

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

Return dimensions of calibration manifold object.

Definition at line 86 of file Cal3DS2.h.

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

assert equality up to a tolerance

Definition at line 37 of file Cal3DS2.cpp.

Vector gtsam::Cal3DS2::localCoordinates ( const Cal3DS2 T2) const

Given a different calibration, calculate update to obtain it.

Definition at line 48 of file Cal3DS2.cpp.

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

print with optional string

Reimplemented from gtsam::Cal3.

Definition at line 34 of file Cal3DS2.cpp.

Cal3DS2 gtsam::Cal3DS2::retract ( const Vector d) const

Given delta vector, update calibration.

Definition at line 43 of file Cal3DS2.cpp.

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

Definition at line 106 of file Cal3DS2.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 104 of file Cal3DS2.h.

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

Output stream operator.

Definition at line 28 of file Cal3DS2.cpp.


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


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