Calibration of a fisheye camera. More...
#include <Cal3Fisheye.h>

Public Types | |
| using | shared_ptr = std::shared_ptr< Cal3Fisheye > |
Public Types inherited from gtsam::Cal3 | |
| using | shared_ptr = std::shared_ptr< Cal3 > |
Static Public Attributes | |
| constexpr static auto | dimension = 9 |
| shared pointer to fisheye calibration object More... | |
Static Public Attributes inherited from gtsam::Cal3 | |
| constexpr static auto | dimension = 5 |
| shared pointer to calibration object 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 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) | |
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={}, OptionalJacobian< 2, 2 > Dp={}) const |
| convert intrinsic coordinates [x_i; y_i] to (distorted) image coordinates [u; v] More... | |
| Point2 | calibrate (const Point2 &p, OptionalJacobian< 2, 9 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| static double | Scaling (double r) |
| Helper function that calculates atan(r)/r. More... | |
Testable | |
| 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... | |
| GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Cal3Fisheye &cal) |
| Output stream operator. 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... | |
Clone | |
| virtual std::shared_ptr< Cal3Fisheye > | clone () const |
Additional Inherited Members | |
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... | |
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... | |
Calibration of a fisheye camera.
Uses same distortionmodel as OpenCV, with https://docs.opencv.org/master/db/d58/group__calib3d__fisheye.html 3D point in camera frame p = (x, y, z) Intrinsic coordinates: [x_i;y_i] = [x/z; y/z] Distorted coordinates: r² = (x_i)² + (y_i)² th = atan(r) th_d = th(1 + k1*th² + k2*th⁴ + k3*th⁶ + k4*th⁸) [x_d; y_d] = (th_d / r)*[x_i; y_i] Pixel coordinates: K = [fx s u0; 0 fy v0 ;0 0 1] [u; v; 1] = K*[x_d; y_d; 1]
Definition at line 51 of file Cal3Fisheye.h.
| using gtsam::Cal3Fisheye::shared_ptr = std::shared_ptr<Cal3Fisheye> |
Definition at line 60 of file Cal3Fisheye.h.
|
default |
Default Constructor with only unit focal length.
|
inline |
Definition at line 68 of file Cal3Fisheye.h.
|
inlineoverride |
Definition at line 78 of file Cal3Fisheye.h.
|
inlineexplicit |
Definition at line 84 of file Cal3Fisheye.h.
| Point2 gtsam::Cal3Fisheye::calibrate | ( | const Point2 & | p, |
| OptionalJacobian< 2, 9 > | Dcal = {}, |
||
| OptionalJacobian< 2, 2 > | Dp = {} |
||
| ) | const |
Convert (distorted) image coordinates [u;v] to intrinsic coordinates [x_i, y_i]
| p | point in image coordinates |
| Dcal | optional 2*9 Jacobian wrpt intrinsic parameters |
| Dp | optional 2*2 Jacobian wrpt intrinsic coordinates (xi, yi) |
Definition at line 111 of file Cal3Fisheye.cpp.
|
inlinevirtual |
Definition at line 177 of file Cal3Fisheye.h.
|
inlinestatic |
Return dimensions of calibration manifold object.
Definition at line 160 of file Cal3Fisheye.h.
|
inlineoverridevirtual |
Return dimensions of calibration manifold object.
Reimplemented from gtsam::Cal3.
Definition at line 157 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 171 of file Cal3Fisheye.cpp.
|
inline |
return distortion parameter vector
Definition at line 108 of file Cal3Fisheye.h.
|
inline |
First distortion coefficient.
Definition at line 96 of file Cal3Fisheye.h.
|
inline |
Second distortion coefficient.
Definition at line 99 of file Cal3Fisheye.h.
|
inline |
First tangential distortion coefficient.
Definition at line 102 of file Cal3Fisheye.h.
|
inline |
Second tangential distortion coefficient.
Definition at line 105 of file Cal3Fisheye.h.
|
inline |
Given a different calibration, calculate update to obtain it.
Definition at line 168 of file Cal3Fisheye.h.
|
overridevirtual |
print with optional string
Reimplemented from gtsam::Cal3.
Definition at line 165 of file Cal3Fisheye.cpp.
|
inline |
Given delta vector, update calibration.
Definition at line 163 of file Cal3Fisheye.h.
|
static |
Helper function that calculates atan(r)/r.
Definition at line 35 of file Cal3Fisheye.cpp.
| Point2 gtsam::Cal3Fisheye::uncalibrate | ( | const Point2 & | p, |
| OptionalJacobian< 2, 9 > | Dcal = {}, |
||
| OptionalJacobian< 2, 2 > | Dp = {} |
||
| ) | const |
convert intrinsic coordinates [x_i; y_i] to (distorted) image coordinates [u; v]
| p | point in intrinsic coordinates |
| Dcal | optional 2*9 Jacobian wrpt intrinsic parameters |
| Dp | optional 2*2 Jacobian wrpt intrinsic coordinates (xi, yi) |
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.
|
friend |
Output stream operator.
Definition at line 157 of file Cal3Fisheye.cpp.
|
inlinestaticconstexpr |
shared pointer to fisheye calibration object
Definition at line 58 of file Cal3Fisheye.h.
|
private |
Definition at line 53 of file Cal3Fisheye.h.
|
private |
fisheye distortion coefficients
Definition at line 53 of file Cal3Fisheye.h.
|
private |
Definition at line 54 of file Cal3Fisheye.h.
|
private |
fisheye distortion coefficients
Definition at line 54 of file Cal3Fisheye.h.
|
private |
tolerance value when calibrating
Definition at line 55 of file Cal3Fisheye.h.