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

#include <Cal3Fisheye.h>

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

Public Types

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

Public Member Functions

Standard Constructors
 Cal3Fisheye ()=default
 Default Constructor with only unit focal length. More...
 
 Cal3Fisheye (const double fx, const double fy, const double s, const double u0, const double v0, const double k1, const double k2, const double k3, const double k4, double tol=1e-5)
 
 ~Cal3Fisheye () override
 
Advanced Constructors
 Cal3Fisheye (const Vector9 &v)
 
Clone
virtual boost::shared_ptr< Cal3Fisheyeclone () const
 
- 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 Attributes

double k1_ = 0.0f
 
double k2_ = 0.0f
 fisheye distortion coefficients More...
 
double k3_ = 0.0f
 
double k4_ = 0.0f
 fisheye distortion coefficients More...
 
double tol_ = 1e-5
 tolerance value when calibrating More...
 

Standard Interface

double k1 () const
 First distortion coefficient. More...
 
double k2 () const
 Second distortion coefficient. More...
 
double k3 () const
 First tangential distortion coefficient. More...
 
double k4 () 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
 convert intrinsic coordinates [x_i; y_i] to (distorted) image coordinates [u; v] More...
 
Point2 calibrate (const Point2 &p, OptionalJacobian< 2, 9 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
 
static double Scaling (double r)
 Helper function that calculates atan(r)/r. More...
 

Testable

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

Manifold

size_t dim () const override
 Return dimensions of calibration manifold object. More...
 
Cal3Fisheye retract (const Vector &d) const
 Given delta vector, update calibration. More...
 
Vector localCoordinates (const Cal3Fisheye &T2) const
 Given a different calibration, calculate update to obtain it. 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::Cal3
static size_t Dim ()
 return DOF, dimensionality of tangent space 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 49 of file Cal3Fisheye.h.

Member Typedef Documentation

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

Definition at line 58 of file Cal3Fisheye.h.

Member Enumeration Documentation

anonymous enum
Enumerator
dimension 

Definition at line 56 of file Cal3Fisheye.h.

Constructor & Destructor Documentation

gtsam::Cal3Fisheye::Cal3Fisheye ( )
default

Default Constructor with only unit focal length.

gtsam::Cal3Fisheye::Cal3Fisheye ( const double  fx,
const double  fy,
const double  s,
const double  u0,
const double  v0,
const double  k1,
const double  k2,
const double  k3,
const double  k4,
double  tol = 1e-5 
)
inline

Definition at line 66 of file Cal3Fisheye.h.

gtsam::Cal3Fisheye::~Cal3Fisheye ( )
inlineoverride

Definition at line 76 of file Cal3Fisheye.h.

gtsam::Cal3Fisheye::Cal3Fisheye ( const Vector9 &  v)
inlineexplicit

Definition at line 82 of file Cal3Fisheye.h.

Member Function Documentation

Point2 gtsam::Cal3Fisheye::calibrate ( const Point2 p,
OptionalJacobian< 2, 9 >  Dcal = boost::none,
OptionalJacobian< 2, 2 >  Dp = boost::none 
) const

Convert (distorted) image coordinates [u;v] to intrinsic coordinates [x_i, y_i]

Parameters
ppoint in image coordinates
Dcaloptional 2*9 Jacobian wrpt intrinsic parameters
Dpoptional 2*2 Jacobian wrpt intrinsic coordinates (xi, yi)
Returns
point in intrinsic coordinates

Definition at line 107 of file Cal3Fisheye.cpp.

virtual boost::shared_ptr<Cal3Fisheye> gtsam::Cal3Fisheye::clone ( ) const
inlinevirtual
Returns
a deep copy of this object

Definition at line 175 of file Cal3Fisheye.h.

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

Return dimensions of calibration manifold object.

Reimplemented from gtsam::Cal3.

Definition at line 155 of file Cal3Fisheye.h.

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

Return dimensions of calibration manifold object.

Definition at line 158 of file Cal3Fisheye.h.

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

assert equality up to a tolerance

Definition at line 157 of file Cal3Fisheye.cpp.

Vector4 gtsam::Cal3Fisheye::k ( ) const
inline

return distortion parameter vector

Definition at line 106 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k1 ( ) const
inline

First distortion coefficient.

Definition at line 94 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k2 ( ) const
inline

Second distortion coefficient.

Definition at line 97 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k3 ( ) const
inline

First tangential distortion coefficient.

Definition at line 100 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k4 ( ) const
inline

Second tangential distortion coefficient.

Definition at line 103 of file Cal3Fisheye.h.

Vector gtsam::Cal3Fisheye::localCoordinates ( const Cal3Fisheye T2) const
inline

Given a different calibration, calculate update to obtain it.

Definition at line 166 of file Cal3Fisheye.h.

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

print with optional string

Reimplemented from gtsam::Cal3.

Definition at line 151 of file Cal3Fisheye.cpp.

Cal3Fisheye gtsam::Cal3Fisheye::retract ( const Vector d) const
inline

Given delta vector, update calibration.

Definition at line 161 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::Scaling ( double  r)
static

Helper function that calculates atan(r)/r.

Definition at line 35 of file Cal3Fisheye.cpp.

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

Definition at line 188 of file Cal3Fisheye.h.

Point2 gtsam::Cal3Fisheye::uncalibrate ( const Point2 p,
OptionalJacobian< 2, 9 >  Dcal = boost::none,
OptionalJacobian< 2, 2 >  Dp = boost::none 
) const

convert intrinsic coordinates [x_i; y_i] to (distorted) image coordinates [u; v]

Parameters
ppoint in intrinsic coordinates
Dcaloptional 2*9 Jacobian wrpt intrinsic parameters
Dpoptional 2*2 Jacobian wrpt intrinsic coordinates (xi, yi)
Returns
point in (distorted) image coordinates

Definition at line 47 of file Cal3Fisheye.cpp.

Vector9 gtsam::Cal3Fisheye::vector ( ) const

Return all parameters as a vector.

Definition at line 28 of file Cal3Fisheye.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 186 of file Cal3Fisheye.h.

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

Output stream operator.

Definition at line 143 of file Cal3Fisheye.cpp.

Member Data Documentation

double gtsam::Cal3Fisheye::k1_ = 0.0f
private

Definition at line 51 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k2_ = 0.0f
private

fisheye distortion coefficients

Definition at line 51 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k3_ = 0.0f
private

Definition at line 52 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::k4_ = 0.0f
private

fisheye distortion coefficients

Definition at line 52 of file Cal3Fisheye.h.

double gtsam::Cal3Fisheye::tol_ = 1e-5
private

tolerance value when calibrating

Definition at line 53 of file Cal3Fisheye.h.


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


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