Cal3Bundler.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
18 #include <gtsam/base/Matrix.h>
19 #include <gtsam/base/Vector.h>
21 #include <gtsam/geometry/Point2.h>
22 #include <gtsam/geometry/Point3.h>
23 
24 namespace gtsam {
25 
26 /* ************************************************************************* */
27 Matrix3 Cal3Bundler::K() const {
28  // This function is needed to ensure skew = 0;
29  Matrix3 K;
30  K << fx_, 0, u0_, 0, fy_, v0_, 0, 0, 1.0;
31  return K;
32 }
33 
34 /* ************************************************************************* */
35 Vector4 Cal3Bundler::k() const {
36  Vector4 rvalue_;
37  rvalue_ << k1_, k2_, 0, 0;
38  return rvalue_;
39 }
40 
41 /* ************************************************************************* */
42 Vector3 Cal3Bundler::vector() const { return Vector3(fx_, k1_, k2_); }
43 
44 /* ************************************************************************* */
45 std::ostream& operator<<(std::ostream& os, const Cal3Bundler& cal) {
46  os << "f: " << cal.fx() << ", k1: " << cal.k1() << ", k2: " << cal.k2()
47  << ", px: " << cal.px() << ", py: " << cal.py();
48  return os;
49 }
50 
51 /* ************************************************************************* */
52 void Cal3Bundler::print(const std::string& s) const {
53  gtsam::print((Vector)(Vector(5) << fx_, k1_, k2_, u0_, v0_).finished(),
54  s + ".K");
55 }
56 
57 /* ************************************************************************* */
58 bool Cal3Bundler::equals(const Cal3Bundler& K, double tol) const {
59  return Cal3f::equals(static_cast<const Cal3f&>(K), tol) &&
60  std::fabs(k1_ - K.k1_) < tol && std::fabs(k2_ - K.k2_) < tol;
61 }
62 
63 /* ************************************************************************* */
65  OptionalJacobian<2, 2> Dp) const {
66  // r = x² + y²;
67  // g = (1 + k(1)*r + k(2)*r²);
68  // pi(:,i) = g * pn(:,i)
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;
73 
74  const double f_ = fx_;
75 
76  // Derivatives make use of intermediate variables above
77  if (Dcal) {
78  double rx = r * x, ry = r * y;
79  *Dcal << u, f_ * rx, f_ * r * rx, v, f_ * ry, f_ * r * ry;
80  }
81 
82  if (Dp) {
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;
86  *Dp *= f_;
87  }
88 
89  return Point2(u0_ + f_ * u, v0_ + f_ * v);
90 }
91 
92 /* ************************************************************************* */
94  OptionalJacobian<2, 2> Dp) const {
95  // Copied from Cal3DS2
96  // but specialized with k1, k2 non-zero only and fx=fy and s=0
97  double px = (pi.x() - u0_) / fx_, py = (pi.y() - v0_) / fx_;
98  const Point2 invKPi(px, py);
99  Point2 pn;
100 
101  // iterate until the uncalibrate is close to the actual pixel coordinate
102  const int maxIterations = 10;
103  int iteration = 0;
104  do {
105  // initialize pn with distortion included
106  const double rr = (px * px) + (py * py);
107  const double g = (1 + k1_ * rr + k2_ * rr * rr);
108  pn = invKPi / g;
109 
110  if (distance2(uncalibrate(pn), pi) <= tol_) break;
111 
112  // Set px and py using intrinsic coordinates since that is where radial
113  // distortion correction is done.
114  px = pn.x();
115  py = pn.y();
116  iteration++;
117 
118  } while (iteration < maxIterations);
119 
120  if (iteration >= maxIterations)
121  throw std::runtime_error(
122  "Cal3Bundler::calibrate fails to converge. need a better "
123  "initialization");
124 
125  calibrateJacobians<Cal3Bundler, dimension>(*this, pn, Dcal, Dp);
126 
127  return pn;
128 }
129 
130 /* ************************************************************************* */
131 Matrix2 Cal3Bundler::D2d_intrinsic(const Point2& p) const {
132  Matrix2 Dp;
133  uncalibrate(p, {}, Dp);
134  return Dp;
135 }
136 
137 /* ************************************************************************* */
138 Matrix23 Cal3Bundler::D2d_calibration(const Point2& p) const {
139  Matrix23 Dcal;
140  uncalibrate(p, Dcal, {});
141  return Dcal;
142 }
143 
144 /* ************************************************************************* */
146  Matrix23 Dcal;
147  Matrix2 Dp;
148  uncalibrate(p, Dcal, Dp);
149  Matrix25 H;
150  H << Dp, Dcal;
151  return H;
152 }
153 
154 } // namespace gtsam
gtsam::Cal3::fx_
double fx_
Definition: Cal3.h:71
gtsam::Cal3Bundler::D2d_calibration
Matrix23 D2d_calibration(const Point2 &p) const
Definition: Cal3Bundler.cpp:138
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::Cal3Bundler::k
Vector4 k() const
Radial distortion parameters (4 of them, 2 0)
Definition: Cal3Bundler.cpp:35
Vector.h
typedef and functions to augment Eigen's VectorXd
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
gtsam::distance2
double distance2(const Point2 &p, const Point2 &q, OptionalJacobian< 1, 2 > H1, OptionalJacobian< 1, 2 > H2)
distance between two points
Definition: Point2.cpp:39
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::Cal3f
Calibration model with a single focal length and zero skew.
Definition: Cal3f.h:35
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::Cal3::py
double py() const
image center in y
Definition: Cal3.h:154
gtsam::Cal3Bundler::tol_
double tol_
tolerance value when calibrating
Definition: Cal3Bundler.h:35
gtsam::Cal3Bundler::D2d_intrinsic
Matrix2 D2d_intrinsic(const Point2 &p) const
Definition: Cal3Bundler.cpp:131
gtsam::Cal3Bundler::print
void print(const std::string &s="") const override
print with optional string
Definition: Cal3Bundler.cpp:52
Point3.h
3D Point
gtsam::Cal3Bundler::vector
Vector3 vector() const
Definition: Cal3Bundler.cpp:42
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
os
ofstream os("timeSchurFactors.csv")
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::Cal3Bundler::D2d_intrinsic_calibration
Matrix25 D2d_intrinsic_calibration(const Point2 &p) const
Definition: Cal3Bundler.cpp:145
gtsam::Cal3::u0_
double u0_
Definition: Cal3.h:73
fixture::cal
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
Point2.h
2D Point
gtsam::Cal3f::equals
bool equals(const Cal3f &K, double tol=1e-9) const
assert equality up to a tolerance
Definition: Cal3f.cpp:50
boost::multiprecision::fabs
Real fabs(const Real &a)
Definition: boostmultiprec.cpp:119
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::Cal3Bundler::uncalibrate
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
Definition: Cal3Bundler.cpp:64
gtsam::Cal3Bundler
Calibration used by Bundler.
Definition: Cal3Bundler.h:32
gtsam::Cal3::fy_
double fy_
focal length
Definition: Cal3.h:71
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::Cal3Bundler::k1_
double k1_
Definition: Cal3Bundler.h:34
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::Cal3::fx
double fx() const
focal length x
Definition: Cal3.h:139
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
K
#define K
Definition: igam.h:8
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Cal3Bundler::equals
bool equals(const Cal3Bundler &K, double tol=1e-9) const
assert equality up to a tolerance
Definition: Cal3Bundler.cpp:58
gtsam::Cal3Bundler::k2_
double k2_
radial distortion coefficients
Definition: Cal3Bundler.h:34
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Cal3Bundler::K
Matrix3 K() const override
Standard 3*3 calibration matrix.
Definition: Cal3Bundler.cpp:27
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::tol
const G double tol
Definition: Group.h:79
pybind11
Definition: wrap/pybind11/pybind11/__init__.py:1
gtsam::Cal3::px
double px() const
image center in x
Definition: Cal3.h:151
gtsam::Cal3Bundler::calibrate
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3Bundler.cpp:93
Cal3Bundler.h
Calibration used by Bundler.
gtsam::Cal3::v0_
double v0_
principal point
Definition: Cal3.h:73


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:01:56