Cal3Fisheye.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 
25 #include <memory>
26 
27 #include <string>
28 
29 namespace gtsam {
30 
51 class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
52  private:
53  double k1_ = 0.0f, k2_ = 0.0f;
54  double k3_ = 0.0f, k4_ = 0.0f;
55  double tol_ = 1e-5;
56 
57  public:
58  enum { dimension = 9 };
60  using shared_ptr = std::shared_ptr<Cal3Fisheye>;
61 
64 
66  Cal3Fisheye() = default;
67 
68  Cal3Fisheye(const double fx, const double fy, const double s, const double u0,
69  const double v0, const double k1, const double k2,
70  const double k3, const double k4, double tol = 1e-5)
71  : Cal3(fx, fy, s, u0, v0),
72  k1_(k1),
73  k2_(k2),
74  k3_(k3),
75  k4_(k4),
76  tol_(tol) {}
77 
78  ~Cal3Fisheye() override {}
79 
83 
84  explicit Cal3Fisheye(const Vector9& v)
85  : Cal3(v(0), v(1), v(2), v(3), v(4)),
86  k1_(v(5)),
87  k2_(v(6)),
88  k3_(v(7)),
89  k4_(v(8)) {}
90 
94 
96  inline double k1() const { return k1_; }
97 
99  inline double k2() const { return k2_; }
100 
102  inline double k3() const { return k3_; }
103 
105  inline double k4() const { return k4_; }
106 
108  Vector4 k() const { return Vector4(k1_, k2_, k3_, k4_); }
109 
111  Vector9 vector() const;
112 
114  static double Scaling(double r);
115 
125  OptionalJacobian<2, 2> Dp = {}) const;
126 
135  Point2 calibrate(const Point2& p, OptionalJacobian<2, 9> Dcal = {},
136  OptionalJacobian<2, 2> Dp = {}) const;
137 
141 
143  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
144  const Cal3Fisheye& cal);
145 
147  void print(const std::string& s = "") const override;
148 
150  bool equals(const Cal3Fisheye& K, double tol = 10e-9) const;
151 
155 
157  size_t dim() const override { return Dim(); }
158 
160  inline static size_t Dim() { return dimension; }
161 
163  inline Cal3Fisheye retract(const Vector& d) const {
164  return Cal3Fisheye(vector() + d);
165  }
166 
169  return T2.vector() - vector();
170  }
171 
175 
177  virtual std::shared_ptr<Cal3Fisheye> clone() const {
178  return std::shared_ptr<Cal3Fisheye>(new Cal3Fisheye(*this));
179  }
180 
182 
183  private:
186 
187 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
188 
189  friend class boost::serialization::access;
190  template <class Archive>
191  void serialize(Archive& ar, const unsigned int /*version*/) {
192  ar& boost::serialization::make_nvp(
193  "Cal3Fisheye", boost::serialization::base_object<Cal3>(*this));
194  ar& BOOST_SERIALIZATION_NVP(k1_);
195  ar& BOOST_SERIALIZATION_NVP(k2_);
196  ar& BOOST_SERIALIZATION_NVP(k3_);
197  ar& BOOST_SERIALIZATION_NVP(k4_);
198  }
199 #endif
200 
202 };
203 
204 template <>
205 struct traits<Cal3Fisheye> : public internal::Manifold<Cal3Fisheye> {};
206 
207 template <>
208 struct traits<const Cal3Fisheye> : public internal::Manifold<Cal3Fisheye> {};
209 
210 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
std::string serialize(const T &input)
serializes to a string
Vector2 Point2
Definition: Point2.h:32
static size_t Dim()
Return dimensions of calibration manifold object.
Definition: Cal3Fisheye.h:160
~Cal3Fisheye() override
Definition: Cal3Fisheye.h:78
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Vector localCoordinates(const Cal3Fisheye &T2) const
Given a different calibration, calculate update to obtain it.
Definition: Cal3Fisheye.h:168
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
double k3() const
First tangential distortion coefficient.
Definition: Cal3Fisheye.h:102
std::shared_ptr< Cal3 > shared_ptr
Definition: Cal3.h:78
Common base class for all calibration models.
Definition: Cal3.h:69
Vector9 vector() const
Return all parameters as a vector.
Definition: Cal3Fisheye.cpp:28
UniformScaling< float > Scaling(float s)
Vector4 k() const
return distortion parameter vector
Definition: Cal3Fisheye.h:108
const double fy
Eigen::VectorXd Vector
Definition: Vector.h:38
size_t dim() const override
Return dimensions of calibration manifold object.
Definition: Cal3Fisheye.h:157
Array< int, Dynamic, 1 > v
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
double k2() const
Second distortion coefficient.
Definition: Cal3Fisheye.h:99
Common code for all Calibration models.
static const double u0
traits
Definition: chartTesting.h:28
double k4() const
Second tangential distortion coefficient.
Definition: Cal3Fisheye.h:105
ofstream os("timeSchurFactors.csv")
double k1() const
First distortion coefficient.
Definition: Cal3Fisheye.h:96
static const double v0
Point2_ uncalibrate(const Expression< CALIBRATION > &K, const Point2_ &xy_hat)
float * p
Cal3Fisheye(const Vector9 &v)
Definition: Cal3Fisheye.h:84
const G double tol
Definition: Group.h:86
const double fx
2D Point
Cal3Fisheye(const double fx, const double fy, const double s, const double u0, const double v0, const double k1, const double k2, const double k3, const double k4, double tol=1e-5)
Definition: Cal3Fisheye.h:68
Cal3Fisheye retract(const Vector &d) const
Given delta vector, update calibration.
Definition: Cal3Fisheye.h:163
Calibration of a fisheye camera.
Definition: Cal3Fisheye.h:51
virtual std::shared_ptr< Cal3Fisheye > clone() const
Definition: Cal3Fisheye.h:177


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:00