The most common 5DOF 3D->2D calibration, stereo version. More...
#include <Cal3_S2Stereo.h>

Public Types | |
| using | shared_ptr = std::shared_ptr< Cal3_S2Stereo > |
Public Types inherited from gtsam::Cal3_S2 | |
| using | shared_ptr = std::shared_ptr< Cal3_S2 > |
Public Types inherited from gtsam::Cal3 | |
| using | shared_ptr = std::shared_ptr< Cal3 > |
Public Member Functions | |
| Point2 | calibrate (const Point2 &p, OptionalJacobian< 2, 6 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| Vector3 | calibrate (const Vector3 &p) const |
| Point2 | uncalibrate (const Point2 &p, OptionalJacobian< 2, 6 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
Public Member Functions inherited from gtsam::Cal3_S2 | |
| Cal3_S2 ()=default | |
| Create a default calibration that leaves coordinates unchanged. More... | |
| Cal3_S2 (double fx, double fy, double s, double u0, double v0) | |
| constructor from doubles More... | |
| Cal3_S2 (const Vector5 &d) | |
| constructor from vector More... | |
| Cal3_S2 (double fov, int w, int h) | |
| Point2 | uncalibrate (const Point2 &p, OptionalJacobian< 2, 5 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| Point2 | calibrate (const Point2 &p, OptionalJacobian< 2, 5 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const |
| Vector3 | calibrate (const Vector3 &p) const |
| bool | equals (const Cal3_S2 &K, double tol=10e-9) const |
| Check if equal up to specified tolerance. More... | |
| Cal3_S2 | between (const Cal3_S2 &q, OptionalJacobian< 5, 5 > H1={}, OptionalJacobian< 5, 5 > H2={}) const |
| "Between", subtracts calibrations. between(p,q) == compose(inverse(p),q) More... | |
| Cal3_S2 | retract (const Vector &d) const |
| Given 5-dim tangent vector, create new calibration. More... | |
| Vector5 | localCoordinates (const Cal3_S2 &T2) const |
| Unretraction for the 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 Attributes | |
| constexpr static auto | dimension = 6 |
| shared pointer to stereo calibration object More... | |
Static Public Attributes inherited from gtsam::Cal3_S2 | |
| constexpr static auto | dimension = 5 |
| shared pointer to calibration object More... | |
Static Public Attributes inherited from gtsam::Cal3 | |
| constexpr static auto | dimension = 5 |
| shared pointer to calibration object More... | |
Private Attributes | |
| double | b_ = 1.0f |
| Stereo baseline. More... | |
Standard Constructors | |
| Cal3_S2Stereo ()=default | |
| default calibration leaves coordinates unchanged More... | |
| Cal3_S2Stereo (double fx, double fy, double s, double u0, double v0, double b) | |
| constructor from doubles More... | |
| Cal3_S2Stereo (const Vector6 &d) | |
| constructor from vector More... | |
| Cal3_S2Stereo (double fov, int w, int h, double b) | |
| easy constructor; field-of-view in degrees, assumes zero skew More... | |
Testable | |
| void | print (const std::string &s="") const override |
| print with optional string More... | |
| bool | equals (const Cal3_S2Stereo &other, double tol=10e-9) const |
| Check if equal up to specified tolerance. More... | |
| GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Cal3_S2Stereo &cal) |
| Output stream operator. More... | |
Standard Interface | |
| const Cal3_S2 & | calibration () const |
| return calibration, same for left and right More... | |
| Matrix3 | K () const override |
| return calibration matrix K, same for left and right More... | |
| double | baseline () const |
| return baseline More... | |
| Vector6 | vector () const |
| vectorized form (column-wise) More... | |
Manifold | |
| size_t | dim () const override |
| return DOF, dimensionality of tangent space More... | |
| Cal3_S2Stereo | retract (const Vector &d) const |
| Given 6-dim tangent vector, create new calibration. More... | |
| Vector6 | localCoordinates (const Cal3_S2Stereo &T2) const |
| Unretraction for the calibration. More... | |
| static size_t | Dim () |
| return DOF, dimensionality of tangent space More... | |
Additional Inherited Members | |
Static Public Member Functions inherited from gtsam::Cal3_S2 | |
| 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... | |
The most common 5DOF 3D->2D calibration, stereo version.
Definition at line 30 of file Cal3_S2Stereo.h.
| using gtsam::Cal3_S2Stereo::shared_ptr = std::shared_ptr<Cal3_S2Stereo> |
Definition at line 38 of file Cal3_S2Stereo.h.
|
default |
default calibration leaves coordinates unchanged
|
inline |
constructor from doubles
Definition at line 47 of file Cal3_S2Stereo.h.
|
inline |
constructor from vector
Definition at line 51 of file Cal3_S2Stereo.h.
easy constructor; field-of-view in degrees, assumes zero skew
Definition at line 55 of file Cal3_S2Stereo.h.
|
inline |
return baseline
Definition at line 111 of file Cal3_S2Stereo.h.
| Point2 gtsam::Cal3_S2Stereo::calibrate | ( | const Point2 & | p, |
| OptionalJacobian< 2, 6 > | Dcal = {}, |
||
| OptionalJacobian< 2, 2 > | Dp = {} |
||
| ) | const |
Convert image coordinates uv to intrinsic coordinates xy
| p | point in image coordinates |
| Dcal | optional 2*6 Jacobian wrpt Cal3_S2Stereo parameters |
| Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |
Definition at line 55 of file Cal3_S2Stereo.cpp.
Convert homogeneous image coordinates to intrinsic coordinates
| p | point in image coordinates |
Definition at line 85 of file Cal3_S2Stereo.h.
|
inline |
return calibration, same for left and right
Definition at line 105 of file Cal3_S2Stereo.h.
|
inlinestatic |
return DOF, dimensionality of tangent space
Definition at line 128 of file Cal3_S2Stereo.h.
|
inlineoverridevirtual |
return DOF, dimensionality of tangent space
Reimplemented from gtsam::Cal3.
Definition at line 125 of file Cal3_S2Stereo.h.
| bool gtsam::Cal3_S2Stereo::equals | ( | const Cal3_S2Stereo & | other, |
| double | tol = 10e-9 |
||
| ) | const |
Check if equal up to specified tolerance.
Definition at line 39 of file Cal3_S2Stereo.cpp.
|
inlineoverridevirtual |
return calibration matrix K, same for left and right
Reimplemented from gtsam::Cal3.
Definition at line 108 of file Cal3_S2Stereo.h.
|
inline |
Unretraction for the calibration.
Definition at line 137 of file Cal3_S2Stereo.h.
|
overridevirtual |
print with optional string
Reimplemented from gtsam::Cal3_S2.
Definition at line 32 of file Cal3_S2Stereo.cpp.
|
inline |
Given 6-dim tangent vector, create new calibration.
Definition at line 131 of file Cal3_S2Stereo.h.
| Point2 gtsam::Cal3_S2Stereo::uncalibrate | ( | const Point2 & | p, |
| OptionalJacobian< 2, 6 > | Dcal = {}, |
||
| OptionalJacobian< 2, 2 > | Dp = {} |
||
| ) | const |
Convert intrinsic coordinates xy to image coordinates uv, fixed derivaitves
| p | point in intrinsic coordinates |
| Dcal | optional 2*6 Jacobian wrpt Cal3_S2Stereo parameters |
| Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |
Definition at line 46 of file Cal3_S2Stereo.cpp.
|
inline |
vectorized form (column-wise)
Definition at line 114 of file Cal3_S2Stereo.h.
|
friend |
Output stream operator.
Definition at line 25 of file Cal3_S2Stereo.cpp.
|
private |
Stereo baseline.
Definition at line 32 of file Cal3_S2Stereo.h.
|
inlinestaticconstexpr |
shared pointer to stereo calibration object
Definition at line 35 of file Cal3_S2Stereo.h.