Cal3f.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 
12 /* ----------------------------------------------------------------------------
13 
14  * GTSAM Copyright 2010
15  * See LICENSE for the license information
16 
17  * -------------------------------------------------------------------------- */
18 
26 #include <gtsam/base/Matrix.h>
27 #include <gtsam/base/Vector.h>
28 #include <gtsam/geometry/Cal3f.h>
29 
30 #include <iostream>
31 
32 namespace gtsam {
33 
34 /* ************************************************************************* */
35 Cal3f::Cal3f(double f, double u0, double v0) : Cal3(f, f, 0.0, u0, v0) {}
36 
37 /* ************************************************************************* */
38 std::ostream& operator<<(std::ostream& os, const Cal3f& cal) {
39  os << "f: " << cal.fx_ << ", px: " << cal.u0_ << ", py: " << cal.v0_;
40  return os;
41 }
42 
43 /* ************************************************************************* */
44 void Cal3f::print(const std::string& s) const {
45  if (!s.empty()) std::cout << s << " ";
46  std::cout << *this << std::endl;
47 }
48 
49 /* ************************************************************************* */
50 bool Cal3f::equals(const Cal3f& K, double tol) const {
51  return Cal3::equals(static_cast<const Cal3&>(K), tol);
52 }
53 
54 /* ************************************************************************* */
56  Vector1 v;
57  v << fx_;
58  return v;
59 }
60 
61 /* ************************************************************************* */
63  OptionalJacobian<2, 2> Dp) const {
64  assert(fx_ == fy_ && s_ == 0.0);
65  const double x = p.x(), y = p.y();
66  const double u = fx_ * x + u0_;
67  const double v = fx_ * y + v0_;
68 
69  if (Dcal) {
70  Dcal->resize(2, 1);
71  (*Dcal) << x, y;
72  }
73 
74  if (Dp) {
75  Dp->resize(2, 2);
76  (*Dp) << fx_, 0.0, //
77  0.0, fx_;
78  }
79 
80  return Point2(u, v);
81 }
82 
83 /* ************************************************************************* */
85  OptionalJacobian<2, 2> Dp) const {
86  assert(fx_ == fy_ && s_ == 0.0);
87  const double u = pi.x(), v = pi.y();
88  double delta_u = u - u0_, delta_v = v - v0_;
89  double inv_f = 1.0 / fx_;
90  Point2 point(inv_f * delta_u, inv_f * delta_v);
91 
92  if (Dcal) {
93  Dcal->resize(2, 1);
94  (*Dcal) << -inv_f * point.x(), -inv_f * point.y();
95  }
96 
97  if (Dp) {
98  Dp->resize(2, 2);
99  (*Dp) << inv_f, 0.0, //
100  0.0, inv_f;
101  }
102 
103  return point;
104 }
105 
106 } // namespace gtsam
gtsam::Cal3::fx_
double fx_
Definition: Cal3.h:71
gtsam::Cal3f::Cal3f
Cal3f()=default
Default constructor.
Vector.h
typedef and functions to augment Eigen's VectorXd
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::Cal3f::print
void print(const std::string &s="") const override
print with optional string
Definition: Cal3f.cpp:44
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
v0
static const double v0
Definition: testCal3DFisheye.cpp:31
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
os
ofstream os("timeSchurFactors.csv")
gtsam::Cal3::u0_
double u0_
Definition: Cal3.h:73
fixture::cal
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
gtsam::Cal3f::equals
bool equals(const Cal3f &K, double tol=1e-9) const
assert equality up to a tolerance
Definition: Cal3f.cpp:50
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::Cal3
Common base class for all calibration models.
Definition: Cal3.h:69
gtsam::Cal3::fy_
double fy_
focal length
Definition: Cal3.h:71
Cal3f.h
Calibration model with a single focal length and zero skew.
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::Cal3::K
virtual Matrix3 K() const
return calibration matrix K
Definition: Cal3.h:167
y
Scalar * y
Definition: level1_cplx_impl.h:124
u0
static const double u0
Definition: testCal3DFisheye.cpp:31
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::Cal3::equals
bool equals(const Cal3 &K, double tol=10e-9) const
Check if equal up to specified tolerance.
Definition: Cal3.cpp:59
gtsam::Cal3f::vector
Vector1 vector() const
vectorized form (column-wise)
Definition: Cal3f.cpp:55
gtsam::Cal3f::calibrate
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 1 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3f.cpp:84
gtsam
traits
Definition: SFMdata.h:40
K
#define K
Definition: igam.h:8
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
p
float * p
Definition: Tutorial_Map_using.cpp:9
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::tol
const G double tol
Definition: Group.h:79
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::Cal3::s_
double s_
skew
Definition: Cal3.h:72
gtsam::Cal3f::uncalibrate
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 1 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
: convert intrinsic coordinates xy to image coordinates uv Version of uncalibrate with derivatives
Definition: Cal3f.cpp:62
gtsam::Cal3::v0_
double v0_
principal point
Definition: Cal3.h:73


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