Go to the documentation of this file.
46 os <<
"f: " <<
cal.
fx() <<
", k1: " <<
cal.k1() <<
", k2: " <<
cal.k2()
47 <<
", px: " <<
cal.
px() <<
", py: " <<
cal.
py();
69 const double x =
p.x(),
y =
p.y();
70 const double r =
x *
x +
y *
y;
71 const double g = 1. + (
k1_ +
k2_ * r) * r;
72 const double u =
g *
x,
v =
g *
y;
74 const double f_ =
fx_;
78 double rx = r *
x, ry = r *
y;
79 *Dcal << u, f_ * rx, f_ * r * rx,
v, f_ * ry, f_ * r * ry;
83 const double a = 2. * (
k1_ + 2. *
k2_ * r);
84 const double axx =
a *
x *
x, axy =
a *
x *
y, ayy =
a *
y *
y;
85 *Dp <<
g + axx, axy, axy,
g + ayy;
102 const int maxIterations = 10;
106 const double rr = (
px *
px) + (
py *
py);
107 const double g = (1 +
k1_ * rr +
k2_ * rr * rr);
118 }
while (iteration < maxIterations);
120 if (iteration >= maxIterations)
121 throw std::runtime_error(
122 "Cal3Bundler::calibrate fails to converge. need a better "
125 calibrateJacobians<Cal3Bundler, dimension>(*
this, pn, Dcal, Dp);
Matrix23 D2d_calibration(const Point2 &p) const
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Vector4 k() const
Radial distortion parameters (4 of them, 2 0)
typedef and functions to augment Eigen's VectorXd
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
double distance2(const Point2 &p, const Point2 &q, OptionalJacobian< 1, 2 > H1, OptionalJacobian< 1, 2 > H2)
distance between two points
typedef and functions to augment Eigen's MatrixXd
Calibration model with a single focal length and zero skew.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
double py() const
image center in y
double tol_
tolerance value when calibrating
Matrix2 D2d_intrinsic(const Point2 &p) const
void print(const std::string &s="") const override
print with optional string
ofstream os("timeSchurFactors.csv")
Matrix25 D2d_intrinsic_calibration(const Point2 &p) const
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
bool equals(const Cal3f &K, double tol=1e-9) const
assert equality up to a tolerance
void print(const Matrix &A, const string &s, ostream &stream)
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
Calibration used by Bundler.
void g(const string &key, int i)
double fx() const
focal length x
bool equals(const Cal3Bundler &K, double tol=1e-9) const
assert equality up to a tolerance
double k2_
radial distortion coefficients
Matrix3 K() const override
Standard 3*3 calibration matrix.
Array< int, Dynamic, 1 > v
double px() const
image center in x
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Calibration used by Bundler.
double v0_
principal point
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:01:56