Calibration used by Bundler. More...
#include <Cal3Bundler.h>

Public Types | |
| using | shared_ptr = std::shared_ptr< Cal3Bundler > |
Public Types inherited from gtsam::Cal3f | |
| using | shared_ptr = std::shared_ptr< Cal3f > |
Public Types inherited from gtsam::Cal3 | |
| using | shared_ptr = std::shared_ptr< Cal3 > |
Static Public Attributes | |
| constexpr static auto | dimension = 3 |
Static Public Attributes inherited from gtsam::Cal3f | |
| constexpr static auto | dimension = 1 |
Static Public Attributes inherited from gtsam::Cal3 | |
| constexpr static auto | dimension = 5 |
| shared pointer to calibration object More... | |
Private Attributes | |
| double | k1_ = 0.0 |
| double | k2_ = 0.0 |
| radial distortion coefficients More... | |
| double | tol_ = 1e-5 |
| tolerance value when calibrating More... | |
Constructors | |
| Cal3Bundler ()=default | |
| Default constructor. More... | |
| Cal3Bundler (double f, double k1, double k2, double u0=0, double v0=0, double tol=1e-5) | |
| ~Cal3Bundler () override=default | |
Testable | |
| void | print (const std::string &s="") const override |
| print with optional string More... | |
| bool | equals (const Cal3Bundler &K, double tol=1e-9) const |
| assert equality up to a tolerance More... | |
| GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Cal3Bundler &cal) |
| Output stream operator. More... | |
Standard Interface | |
| double | k1 () const |
| distortion parameter k1 More... | |
| double | k2 () const |
| distortion parameter k2 More... | |
| Matrix3 | K () const override |
| Standard 3*3 calibration matrix. More... | |
| Vector4 | k () const |
| Radial distortion parameters (4 of them, 2 0) More... | |
| Vector3 | vector () const |
| Point2 | uncalibrate (const Point2 &p, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| : convert intrinsic coordinates xy to image coordinates uv Version of uncalibrate with derivatives More... | |
| Point2 | calibrate (const Point2 &pi, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| Matrix2 | D2d_intrinsic (const Point2 &p) const |
| Matrix23 | D2d_calibration (const Point2 &p) const |
| Matrix25 | D2d_intrinsic_calibration (const Point2 &p) const |
Manifold | |
| size_t | dim () const override |
| Return DOF, dimensionality of tangent space. More... | |
| Cal3Bundler | retract (const Vector &d) const |
| Update calibration with tangent space delta. More... | |
| Vector3 | localCoordinates (const Cal3Bundler &T2) const |
| Calculate local coordinates to another calibration. More... | |
| static size_t | Dim () |
| Return DOF, dimensionality of tangent space. More... | |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::Cal3f | |
| Cal3f ()=default | |
| Default constructor. More... | |
| Cal3f (double f, double u0, double v0) | |
| ~Cal3f () override=default | |
| void | print (const std::string &s="") const override |
| print with optional string More... | |
| bool | equals (const Cal3f &K, double tol=1e-9) const |
| assert equality up to a tolerance More... | |
| double | f () const |
| focal length More... | |
| Vector1 | vector () const |
| vectorized form (column-wise) More... | |
| Point2 | uncalibrate (const Point2 &p, OptionalJacobian< 2, 1 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| : convert intrinsic coordinates xy to image coordinates uv Version of uncalibrate with derivatives More... | |
| Point2 | calibrate (const Point2 &pi, OptionalJacobian< 2, 1 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| size_t | dim () const override |
| Return DOF, dimensionality of tangent space. More... | |
| Cal3f | retract (const Vector &d) const |
| Update calibration with tangent space delta. More... | |
| Vector1 | localCoordinates (const Cal3f &T2) const |
| Calculate local coordinates to another calibration. 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... | |
| Matrix3 | inverse () const |
| Return inverted calibration matrix inv(K) More... | |
Static Public Member Functions inherited from gtsam::Cal3f | |
| 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::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 used by Bundler.
Definition at line 32 of file Cal3Bundler.h.
| using gtsam::Cal3Bundler::shared_ptr = std::shared_ptr<Cal3Bundler> |
Definition at line 41 of file Cal3Bundler.h.
|
default |
Default constructor.
|
inline |
Constructor
| f | focal length |
| k1 | first radial distortion coefficient (quadratic) |
| k2 | second radial distortion coefficient (quartic) |
| u0 | optional image center (default 0), considered a constant |
| v0 | optional image center (default 0), considered a constant |
| tol | optional calibration tolerance value |
Definition at line 58 of file Cal3Bundler.h.
|
overridedefault |
| Point2 gtsam::Cal3Bundler::calibrate | ( | const Point2 & | pi, |
| OptionalJacobian< 2, 3 > | Dcal = {}, |
||
| OptionalJacobian< 2, 2 > | Dp = {} |
||
| ) | const |
Convert a pixel coordinate to ideal coordinate xy
| pi | point in image coordinates |
| Dcal | optional 2*3 Jacobian wrpt Cal3Bundler parameters |
| Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |
Definition at line 93 of file Cal3Bundler.cpp.
| Matrix23 gtsam::Cal3Bundler::D2d_calibration | ( | const Point2 & | p | ) | const |
Definition at line 138 of file Cal3Bundler.cpp.
| Matrix2 gtsam::Cal3Bundler::D2d_intrinsic | ( | const Point2 & | p | ) | const |
Definition at line 131 of file Cal3Bundler.cpp.
| Matrix25 gtsam::Cal3Bundler::D2d_intrinsic_calibration | ( | const Point2 & | p | ) | const |
Definition at line 145 of file Cal3Bundler.cpp.
|
inlinestatic |
Return DOF, dimensionality of tangent space.
Definition at line 131 of file Cal3Bundler.h.
|
inlineoverridevirtual |
Return DOF, dimensionality of tangent space.
Reimplemented from gtsam::Cal3.
Definition at line 128 of file Cal3Bundler.h.
| bool gtsam::Cal3Bundler::equals | ( | const Cal3Bundler & | K, |
| double | tol = 1e-9 |
||
| ) | const |
assert equality up to a tolerance
Definition at line 58 of file Cal3Bundler.cpp.
| Vector4 gtsam::Cal3Bundler::k | ( | ) | const |
Radial distortion parameters (4 of them, 2 0)
Definition at line 35 of file Cal3Bundler.cpp.
|
overridevirtual |
Standard 3*3 calibration matrix.
Reimplemented from gtsam::Cal3.
Definition at line 27 of file Cal3Bundler.cpp.
|
inline |
distortion parameter k1
Definition at line 83 of file Cal3Bundler.h.
|
inline |
distortion parameter k2
Definition at line 86 of file Cal3Bundler.h.
|
inline |
Calculate local coordinates to another calibration.
Definition at line 139 of file Cal3Bundler.h.
|
overridevirtual |
print with optional string
Reimplemented from gtsam::Cal3.
Definition at line 52 of file Cal3Bundler.cpp.
|
inline |
Update calibration with tangent space delta.
Definition at line 134 of file Cal3Bundler.h.
| Point2 gtsam::Cal3Bundler::uncalibrate | ( | const Point2 & | p, |
| OptionalJacobian< 2, 3 > | Dcal = {}, |
||
| OptionalJacobian< 2, 2 > | Dp = {} |
||
| ) | const |
: convert intrinsic coordinates xy to image coordinates uv Version of uncalibrate with derivatives
| p | point in intrinsic coordinates |
| Dcal | optional 2*3 Jacobian wrpt Cal3Bundler parameters |
| Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |
Definition at line 64 of file Cal3Bundler.cpp.
| Vector3 gtsam::Cal3Bundler::vector | ( | ) | const |
Definition at line 42 of file Cal3Bundler.cpp.
|
friend |
Output stream operator.
Definition at line 45 of file Cal3Bundler.cpp.
|
inlinestaticconstexpr |
Definition at line 40 of file Cal3Bundler.h.
|
private |
Definition at line 34 of file Cal3Bundler.h.
|
private |
radial distortion coefficients
Definition at line 34 of file Cal3Bundler.h.
|
private |
tolerance value when calibrating
Definition at line 35 of file Cal3Bundler.h.