46 const double x = p.x(),
y = p.y();
47 if (Dcal) *Dcal <<
x, 0.0,
y, 1.0, 0.0, 0.0,
y, 0.0, 0.0, 1.0;
55 const double u = p.x(),
v = p.y();
56 double delta_u = u -
u0_, delta_v =
v -
v0_;
57 double inv_fx = 1 /
fx_, inv_fy = 1 /
fy_;
58 double inv_fy_delta_v = inv_fy * delta_v;
59 double inv_fx_s_inv_fy = inv_fx *
s_ * inv_fy;
61 Point2 point(inv_fx * (delta_u -
s_ * inv_fy_delta_v), inv_fy_delta_v);
63 *Dcal << -inv_fx * point.x(), inv_fx *
s_ * inv_fy * inv_fy_delta_v,
64 -inv_fx * point.y(), -inv_fx, inv_fx_s_inv_fy, 0, -inv_fy * point.y(),
67 if (Dp) *Dp << inv_fx, -inv_fx_s_inv_fy, 0, inv_fy;
void print(const Matrix &A, const string &s, ostream &stream)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
bool equals(const Cal3_S2 &K, double tol=10e-9) const
Check if equal up to specified tolerance.
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 5 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
virtual Matrix3 K() const
return calibration matrix K
Point2 calibrate(const Point2 &p, OptionalJacobian< 2, 5 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
bool equals(const Cal3 &K, double tol=10e-9) const
Check if equal up to specified tolerance.
double v0_
principal point
ofstream os("timeSchurFactors.csv")
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
void print(const std::string &s="Cal3_S2") const override
print with optional string
Matrix3 inverse() const
Return inverted calibration matrix inv(K)
The most common 5DOF 3D->2D calibration.