Public Types | Private Types | Private Member Functions | Private Attributes | Friends | List of all members
gtsam::Cal3Unified Class Reference

#include <Cal3Unified.h>

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

Public Types

enum  { dimension = 10 }
 
- 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
 Cal3Unified ()=default
 Default Constructor with only unit focal length. More...
 
 Cal3Unified (double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1=0.0, double p2=0.0, double xi=0.0)
 
 ~Cal3Unified () override
 
Advanced Constructors
 Cal3Unified (const Vector10 &v)
 
Standard Interface
double xi () const
 mirror parameter More...
 
Vector10 vector () const
 Return all parameters as a vector. More...
 
Point2 uncalibrate (const Point2 &p, OptionalJacobian< 2, 10 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
 
Point2 calibrate (const Point2 &p, OptionalJacobian< 2, 10 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
 Conver a pixel coordinate to ideal coordinate. More...
 
Point2 spaceToNPlane (const Point2 &p) const
 Convert a 3D point to normalized unit plane. More...
 
Point2 nPlaneToSpace (const Point2 &p) const
 Convert a normalized unit plane point to 3D space. More...
 
- 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)
 
virtual boost::shared_ptr< Cal3DS2_Baseclone () const
 
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...
 
- 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
 
using This = Cal3Unified
 

Private Member Functions

template<class Archive >
void serialize (Archive &ar, const unsigned int)
 

Private Attributes

double xi_ = 0.0f
 mirror parameter More...
 

Friends

class boost::serialization::access
 

Testable

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

Manifold

Cal3Unified retract (const Vector &d) const
 Given delta vector, update calibration. More...
 
Vector localCoordinates (const Cal3Unified &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...
 

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 45 of file Cal3Unified.h.

Member Typedef Documentation

Definition at line 47 of file Cal3Unified.h.

Definition at line 46 of file Cal3Unified.h.

Member Enumeration Documentation

anonymous enum
Enumerator
dimension 

Definition at line 53 of file Cal3Unified.h.

Constructor & Destructor Documentation

gtsam::Cal3Unified::Cal3Unified ( )
default

Default Constructor with only unit focal length.

gtsam::Cal3Unified::Cal3Unified ( double  fx,
double  fy,
double  s,
double  u0,
double  v0,
double  k1,
double  k2,
double  p1 = 0.0,
double  p2 = 0.0,
double  xi = 0.0 
)
inline

Definition at line 61 of file Cal3Unified.h.

gtsam::Cal3Unified::~Cal3Unified ( )
inlineoverride

Definition at line 65 of file Cal3Unified.h.

gtsam::Cal3Unified::Cal3Unified ( const Vector10 &  v)
inline

Definition at line 71 of file Cal3Unified.h.

Member Function Documentation

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

Conver a pixel coordinate to ideal coordinate.

Definition at line 103 of file Cal3Unified.cpp.

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

Return dimensions of calibration manifold object.

Reimplemented from gtsam::Cal3DS2_Base.

Definition at line 130 of file Cal3Unified.h.

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

Return dimensions of calibration manifold object.

Definition at line 133 of file Cal3Unified.h.

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

assert equality up to a tolerance

Definition at line 49 of file Cal3Unified.cpp.

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

Given a different calibration, calculate update to obtain it.

Definition at line 138 of file Cal3Unified.cpp.

Point2 gtsam::Cal3Unified::nPlaneToSpace ( const Point2 p) const

Convert a normalized unit plane point to 3D space.

Definition at line 116 of file Cal3Unified.cpp.

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

print with optional string

Reimplemented from gtsam::Cal3DS2_Base.

Definition at line 43 of file Cal3Unified.cpp.

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

Given delta vector, update calibration.

Definition at line 133 of file Cal3Unified.cpp.

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

Definition at line 141 of file Cal3Unified.h.

Point2 gtsam::Cal3Unified::spaceToNPlane ( const Point2 p) const

Convert a 3D point to normalized unit plane.

Definition at line 125 of file Cal3Unified.cpp.

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

convert intrinsic coordinates xy to image coordinates uv

Parameters
ppoint in intrinsic coordinates
Dcaloptional 2*10 Jacobian wrpt Cal3Unified parameters
Dpoptional 2*2 Jacobian wrpt intrinsic coordinates
Returns
point in image coordinates

Definition at line 56 of file Cal3Unified.cpp.

Vector10 gtsam::Cal3Unified::vector ( ) const

Return all parameters as a vector.

Definition at line 29 of file Cal3Unified.cpp.

double gtsam::Cal3Unified::xi ( ) const
inline

mirror parameter

Definition at line 93 of file Cal3Unified.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 139 of file Cal3Unified.h.

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

Output stream operator.

Definition at line 36 of file Cal3Unified.cpp.

Member Data Documentation

double gtsam::Cal3Unified::xi_ = 0.0f
private

mirror parameter

Definition at line 50 of file Cal3Unified.h.


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


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