#include <Cal3Fisheye.h>
|
|
| 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 |
|
|
| Cal3Fisheye (const Vector9 &v) |
|
|
virtual boost::shared_ptr< Cal3Fisheye > | 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_ = 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...
|
|
Definition at line 49 of file Cal3Fisheye.h.
gtsam::Cal3Fisheye::Cal3Fisheye |
( |
| ) |
|
|
default |
Default Constructor with only unit focal length.
gtsam::Cal3Fisheye::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 |
|
) |
| |
|
inline |
gtsam::Cal3Fisheye::~Cal3Fisheye |
( |
| ) |
|
|
inlineoverride |
gtsam::Cal3Fisheye::Cal3Fisheye |
( |
const Vector9 & |
v | ) |
|
|
inlineexplicit |
Convert (distorted) image coordinates [u;v] to intrinsic coordinates [x_i, y_i]
- Parameters
-
p | point in image coordinates |
Dcal | optional 2*9 Jacobian wrpt intrinsic parameters |
Dp | optional 2*2 Jacobian wrpt intrinsic coordinates (xi, yi) |
- Returns
- point in intrinsic coordinates
Definition at line 107 of file Cal3Fisheye.cpp.
virtual boost::shared_ptr<Cal3Fisheye> gtsam::Cal3Fisheye::clone |
( |
| ) |
const |
|
inlinevirtual |
size_t gtsam::Cal3Fisheye::dim |
( |
| ) |
const |
|
inlineoverridevirtual |
static size_t gtsam::Cal3Fisheye::Dim |
( |
| ) |
|
|
inlinestatic |
Return dimensions of calibration manifold object.
Definition at line 158 of file Cal3Fisheye.h.
bool gtsam::Cal3Fisheye::equals |
( |
const Cal3Fisheye & |
K, |
|
|
double |
tol = 10e-9 |
|
) |
| const |
Vector4 gtsam::Cal3Fisheye::k |
( |
| ) |
const |
|
inline |
return distortion parameter vector
Definition at line 106 of file Cal3Fisheye.h.
double gtsam::Cal3Fisheye::k1 |
( |
| ) |
const |
|
inline |
double gtsam::Cal3Fisheye::k2 |
( |
| ) |
const |
|
inline |
Second distortion coefficient.
Definition at line 97 of file Cal3Fisheye.h.
double gtsam::Cal3Fisheye::k3 |
( |
| ) |
const |
|
inline |
First tangential distortion coefficient.
Definition at line 100 of file Cal3Fisheye.h.
double gtsam::Cal3Fisheye::k4 |
( |
| ) |
const |
|
inline |
Second tangential distortion coefficient.
Definition at line 103 of file Cal3Fisheye.h.
Given a different calibration, calculate update to obtain it.
Definition at line 166 of file Cal3Fisheye.h.
void gtsam::Cal3Fisheye::print |
( |
const std::string & |
s = "" | ) |
const |
|
overridevirtual |
Given delta vector, update calibration.
Definition at line 161 of file Cal3Fisheye.h.
double gtsam::Cal3Fisheye::Scaling |
( |
double |
r | ) |
|
|
static |
Helper function that calculates atan(r)/r.
Definition at line 35 of file Cal3Fisheye.cpp.
template<class Archive >
void gtsam::Cal3Fisheye::serialize |
( |
Archive & |
ar, |
|
|
const unsigned |
int |
|
) |
| |
|
inlineprivate |
convert intrinsic coordinates [x_i; y_i] to (distorted) image coordinates [u; v]
- Parameters
-
p | point in intrinsic coordinates |
Dcal | optional 2*9 Jacobian wrpt intrinsic parameters |
Dp | optional 2*2 Jacobian wrpt intrinsic coordinates (xi, yi) |
- Returns
- point in (distorted) image coordinates
Definition at line 47 of file Cal3Fisheye.cpp.
Vector9 gtsam::Cal3Fisheye::vector |
( |
| ) |
const |
friend class boost::serialization::access |
|
friend |
GTSAM_EXPORT friend std::ostream& operator<< |
( |
std::ostream & |
os, |
|
|
const Cal3Fisheye & |
cal |
|
) |
| |
|
friend |
double gtsam::Cal3Fisheye::k1_ = 0.0f |
|
private |
double gtsam::Cal3Fisheye::k2_ = 0.0f |
|
private |
fisheye distortion coefficients
Definition at line 51 of file Cal3Fisheye.h.
double gtsam::Cal3Fisheye::k3_ = 0.0f |
|
private |
double gtsam::Cal3Fisheye::k4_ = 0.0f |
|
private |
fisheye distortion coefficients
Definition at line 52 of file Cal3Fisheye.h.
double gtsam::Cal3Fisheye::tol_ = 1e-5 |
|
private |
tolerance value when calibrating
Definition at line 53 of file Cal3Fisheye.h.
The documentation for this class was generated from the following files: