Calibration model with a single focal length and zero skew. More...
#include <Cal3f.h>
Public Types | |
enum | { dimension = 1 } |
using | shared_ptr = std::shared_ptr< Cal3f > |
Public Types inherited from gtsam::Cal3 | |
enum | { dimension = 5 } |
using | shared_ptr = std::shared_ptr< Cal3 > |
Constructors | |
Cal3f ()=default | |
Default constructor. More... | |
Cal3f (double f, double u0, double v0) | |
~Cal3f () override=default | |
Testable | |
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... | |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Cal3f &cal) |
Output stream operator. More... | |
Standard Interface | |
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 |
Manifold | |
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... | |
static size_t | Dim () |
Return DOF, dimensionality of tangent space. More... | |
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... | |
using gtsam::Cal3f::shared_ptr = std::shared_ptr<Cal3f> |
|
default |
Default constructor.
gtsam::Cal3f::Cal3f | ( | double | f, |
double | u0, | ||
double | v0 | ||
) |
|
overridedefault |
Point2 gtsam::Cal3f::calibrate | ( | const Point2 & | pi, |
OptionalJacobian< 2, 1 > | Dcal = {} , |
||
OptionalJacobian< 2, 2 > | Dp = {} |
||
) | const |
|
inlinestatic |
|
inlineoverridevirtual |
Return DOF, dimensionality of tangent space.
Reimplemented from gtsam::Cal3.
|
overridevirtual |
Point2 gtsam::Cal3f::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
p | point in intrinsic coordinates |
Dcal | optional 2*1 Jacobian wrpt focal length |
Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |
Vector1 gtsam::Cal3f::vector | ( | ) | const |
|
friend |