#include <Cal3DS2_Base.h>
|
|
| 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_Base > | clone () const |
|
| 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...
|
|
|
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...
|
|
size_t | dim () const override |
| return DOF, dimensionality of tangent space More...
|
|
static size_t | Dim () |
| return DOF, dimensionality of tangent space More...
|
|
Definition at line 41 of file Cal3DS2_Base.h.
gtsam::Cal3DS2_Base::Cal3DS2_Base |
( |
| ) |
|
|
default |
Default Constructor with only unit focal length.
gtsam::Cal3DS2_Base::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 |
|
) |
| |
|
inline |
gtsam::Cal3DS2_Base::~Cal3DS2_Base |
( |
| ) |
|
|
inlineoverride |
gtsam::Cal3DS2_Base::Cal3DS2_Base |
( |
const Vector9 & |
v | ) |
|
|
inline |
Convert (distorted) image coordinates uv to intrinsic coordinates xy.
Definition at line 133 of file Cal3DS2_Base.cpp.
virtual boost::shared_ptr<Cal3DS2_Base> gtsam::Cal3DS2_Base::clone |
( |
| ) |
const |
|
inlinevirtual |
Matrix29 gtsam::Cal3DS2_Base::D2d_calibration |
( |
const Point2 & |
p | ) |
const |
Derivative of uncalibrate wrpt the calibration parameters.
Definition at line 180 of file Cal3DS2_Base.cpp.
Matrix2 gtsam::Cal3DS2_Base::D2d_intrinsic |
( |
const Point2 & |
p | ) |
const |
Derivative of uncalibrate wrpt intrinsic coordinates.
Definition at line 169 of file Cal3DS2_Base.cpp.
size_t gtsam::Cal3DS2_Base::dim |
( |
| ) |
const |
|
inlineoverridevirtual |
static size_t gtsam::Cal3DS2_Base::Dim |
( |
| ) |
|
|
inlinestatic |
return DOF, dimensionality of tangent space
Definition at line 138 of file Cal3DS2_Base.h.
bool gtsam::Cal3DS2_Base::equals |
( |
const Cal3DS2_Base & |
K, |
|
|
double |
tol = 1e-8 |
|
) |
| const |
Vector4 gtsam::Cal3DS2_Base::k |
( |
| ) |
const |
|
inline |
double gtsam::Cal3DS2_Base::k1 |
( |
| ) |
const |
|
inline |
double gtsam::Cal3DS2_Base::k2 |
( |
| ) |
const |
|
inline |
double gtsam::Cal3DS2_Base::p1 |
( |
| ) |
const |
|
inline |
First tangential distortion coefficient.
Definition at line 103 of file Cal3DS2_Base.h.
double gtsam::Cal3DS2_Base::p2 |
( |
| ) |
const |
|
inline |
Second tangential distortion coefficient.
Definition at line 106 of file Cal3DS2_Base.h.
void gtsam::Cal3DS2_Base::print |
( |
const std::string & |
s = "" | ) |
const |
|
overridevirtual |
template<class Archive >
void gtsam::Cal3DS2_Base::serialize |
( |
Archive & |
ar, |
|
|
const unsigned |
int |
|
) |
| |
|
inlineprivate |
convert intrinsic coordinates xy to (distorted) image coordinates uv
- Parameters
-
p | point in intrinsic coordinates |
Dcal | optional 2*9 Jacobian wrpt Cal3DS2 parameters |
Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |
- Returns
- point in (distorted) image coordinates
Definition at line 94 of file Cal3DS2_Base.cpp.
Vector9 gtsam::Cal3DS2_Base::vector |
( |
| ) |
const |
friend class boost::serialization::access |
|
friend |
GTSAM_EXPORT friend std::ostream& operator<< |
( |
std::ostream & |
os, |
|
|
const Cal3DS2_Base & |
cal |
|
) |
| |
|
friend |
double gtsam::Cal3DS2_Base::k1_ = 0.0f |
|
protected |
double gtsam::Cal3DS2_Base::k2_ = 0.0f |
|
protected |
double gtsam::Cal3DS2_Base::p1_ = 0.0f |
|
protected |
double gtsam::Cal3DS2_Base::p2_ = 0.0f |
|
protected |
double gtsam::Cal3DS2_Base::tol_ = 1e-5 |
|
protected |
The documentation for this class was generated from the following files: