Cal3DS2_Base.h
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 
20 #pragma once
21 
22 #include <gtsam/geometry/Cal3.h>
23 #include <gtsam/geometry/Point2.h>
24 #include <memory>
25 
26 namespace gtsam {
27 
42 class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
43  protected:
44  double k1_ = 0.0f, k2_ = 0.0f;
45  double p1_ = 0.0f, p2_ = 0.0f;
46  double tol_ = 1e-5;
47 
48  public:
49  enum { dimension = 9 };
50 
52  using shared_ptr = std::shared_ptr<Cal3DS2_Base>;
53 
56 
58  Cal3DS2_Base() = default;
59 
60  Cal3DS2_Base(double fx, double fy, double s, double u0, double v0, double k1,
61  double k2, double p1 = 0.0, double p2 = 0.0, double tol = 1e-5)
62  : Cal3(fx, fy, s, u0, v0),
63  k1_(k1),
64  k2_(k2),
65  p1_(p1),
66  p2_(p2),
67  tol_(tol) {}
68 
69  ~Cal3DS2_Base() override {}
70 
74 
75  Cal3DS2_Base(const Vector9& v)
76  : Cal3(v(0), v(1), v(2), v(3), v(4)),
77  k1_(v(5)),
78  k2_(v(6)),
79  p1_(v(7)),
80  p2_(v(8)) {}
81 
85 
87  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
88  const Cal3DS2_Base& cal);
89 
91  void print(const std::string& s = "") const override;
92 
94  bool equals(const Cal3DS2_Base& K, double tol = 1e-8) const;
95 
99 
101  inline double k1() const { return k1_; }
102 
104  inline double k2() const { return k2_; }
105 
107  inline double p1() const { return p1_; }
108 
110  inline double p2() const { return p2_; }
111 
113  Vector4 k() const { return Vector4(k1_, k2_, p1_, p2_); }
114 
116  Vector9 vector() const;
117 
126  OptionalJacobian<2, 2> Dp = {}) const;
127 
129  Point2 calibrate(const Point2& p, OptionalJacobian<2, 9> Dcal = {},
130  OptionalJacobian<2, 2> Dp = {}) const;
131 
133  Matrix2 D2d_intrinsic(const Point2& p) const;
134 
136  Matrix29 D2d_calibration(const Point2& p) const;
137 
139  size_t dim() const override { return Dim(); }
140 
142  inline static size_t Dim() { return dimension; }
143 
147 
149  virtual std::shared_ptr<Cal3DS2_Base> clone() const {
150  return std::shared_ptr<Cal3DS2_Base>(new Cal3DS2_Base(*this));
151  }
152 
154 
155  private:
158 
159 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
160 
161  friend class boost::serialization::access;
162  template <class Archive>
163  void serialize(Archive& ar, const unsigned int /*version*/) {
164  ar& boost::serialization::make_nvp(
165  "Cal3DS2_Base", boost::serialization::base_object<Cal3>(*this));
166  ar& BOOST_SERIALIZATION_NVP(k1_);
167  ar& BOOST_SERIALIZATION_NVP(k2_);
168  ar& BOOST_SERIALIZATION_NVP(p1_);
169  ar& BOOST_SERIALIZATION_NVP(p2_);
170  ar& BOOST_SERIALIZATION_NVP(tol_);
171  }
172 #endif
173 
175 };
176 }
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.cal
cal
Definition: test_ProjectionFactorRollingShutter.py:27
gtsam::Cal3DS2_Base::p2
double p2() const
Second tangential distortion coefficient.
Definition: Cal3DS2_Base.h:110
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
v0
static const double v0
Definition: testCal3DFisheye.cpp:31
gtsam::Cal3DS2_Base::Dim
static size_t Dim()
return DOF, dimensionality of tangent space
Definition: Cal3DS2_Base.h:142
fx
const double fx
Definition: testSmartStereoFactor_iSAM2.cpp:47
gtsam::Cal3DS2_Base
Calibration of a camera with radial distortion.
Definition: Cal3DS2_Base.h:42
Cal3.h
Common code for all Calibration models.
gtsam::Cal3DS2_Base::k1
double k1() const
First distortion coefficient.
Definition: Cal3DS2_Base.h:101
gtsam::Cal3DS2_Base::dim
size_t dim() const override
return DOF, dimensionality of tangent space
Definition: Cal3DS2_Base.h:139
os
ofstream os("timeSchurFactors.csv")
gtsam::Cal3DS2_Base::k2
double k2() const
Second distortion coefficient.
Definition: Cal3DS2_Base.h:104
Point2.h
2D Point
gtsam::Cal3DS2_Base::~Cal3DS2_Base
~Cal3DS2_Base() override
Definition: Cal3DS2_Base.h:69
gtsam::Cal3DS2_Base::k
Vector4 k() const
return distortion parameter vector
Definition: Cal3DS2_Base.h:113
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
gtsam::Cal3DS2_Base::Cal3DS2_Base
Cal3DS2_Base(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1=0.0, double p2=0.0, double tol=1e-5)
Definition: Cal3DS2_Base.h:60
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::Cal3DS2_Base::clone
virtual std::shared_ptr< Cal3DS2_Base > clone() const
Definition: Cal3DS2_Base.h:149
k1
double k1(double x)
Definition: k1.c:133
gtsam::Cal3
Common base class for all calibration models.
Definition: Cal3.h:69
gtsam::Cal3DS2_Base::p1
double p1() const
First tangential distortion coefficient.
Definition: Cal3DS2_Base.h:107
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::uncalibrate
Point2_ uncalibrate(const Expression< CALIBRATION > &K, const Point2_ &xy_hat)
Definition: slam/expressions.h:172
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
gtsam::equals
Definition: Testable.h:112
u0
static const double u0
Definition: testCal3DFisheye.cpp:31
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
gtsam::Cal3::shared_ptr
std::shared_ptr< Cal3 > shared_ptr
Definition: Cal3.h:78
gtsam::Cal3DS2_Base::Cal3DS2_Base
Cal3DS2_Base(const Vector9 &v)
Definition: Cal3DS2_Base.h:75
fy
const double fy
Definition: testSmartStereoFactor_iSAM2.cpp:48


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:03