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 <string>
26 
27 namespace gtsam {
28 
49 class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
50  private:
51  double k1_ = 0.0f, k2_ = 0.0f;
52  double k3_ = 0.0f, k4_ = 0.0f;
53  double tol_ = 1e-5;
54 
55  public:
56  enum { dimension = 9 };
58  using shared_ptr = boost::shared_ptr<Cal3Fisheye>;
59 
62 
64  Cal3Fisheye() = default;
65 
66  Cal3Fisheye(const double fx, const double fy, const double s, const double u0,
67  const double v0, const double k1, const double k2,
68  const double k3, const double k4, double tol = 1e-5)
69  : Cal3(fx, fy, s, u0, v0),
70  k1_(k1),
71  k2_(k2),
72  k3_(k3),
73  k4_(k4),
74  tol_(tol) {}
75 
76  ~Cal3Fisheye() override {}
77 
81 
82  explicit Cal3Fisheye(const Vector9& v)
83  : Cal3(v(0), v(1), v(2), v(3), v(4)),
84  k1_(v(5)),
85  k2_(v(6)),
86  k3_(v(7)),
87  k4_(v(8)) {}
88 
92 
94  inline double k1() const { return k1_; }
95 
97  inline double k2() const { return k2_; }
98 
100  inline double k3() const { return k3_; }
101 
103  inline double k4() const { return k4_; }
104 
106  Vector4 k() const { return Vector4(k1_, k2_, k3_, k4_); }
107 
109  Vector9 vector() const;
110 
112  static double Scaling(double r);
113 
122  Point2 uncalibrate(const Point2& p, OptionalJacobian<2, 9> Dcal = boost::none,
123  OptionalJacobian<2, 2> Dp = boost::none) const;
124 
133  Point2 calibrate(const Point2& p, OptionalJacobian<2, 9> Dcal = boost::none,
134  OptionalJacobian<2, 2> Dp = boost::none) const;
135 
139 
141  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
142  const Cal3Fisheye& cal);
143 
145  void print(const std::string& s = "") const override;
146 
148  bool equals(const Cal3Fisheye& K, double tol = 10e-9) const;
149 
153 
155  size_t dim() const override { return Dim(); }
156 
158  inline static size_t Dim() { return dimension; }
159 
161  inline Cal3Fisheye retract(const Vector& d) const {
162  return Cal3Fisheye(vector() + d);
163  }
164 
167  return T2.vector() - vector();
168  }
169 
173 
175  virtual boost::shared_ptr<Cal3Fisheye> clone() const {
176  return boost::shared_ptr<Cal3Fisheye>(new Cal3Fisheye(*this));
177  }
178 
180 
181  private:
184 
186  friend class boost::serialization::access;
187  template <class Archive>
188  void serialize(Archive& ar, const unsigned int /*version*/) {
189  ar& boost::serialization::make_nvp(
190  "Cal3Fisheye", boost::serialization::base_object<Cal3>(*this));
191  ar& BOOST_SERIALIZATION_NVP(k1_);
192  ar& BOOST_SERIALIZATION_NVP(k2_);
193  ar& BOOST_SERIALIZATION_NVP(k3_);
194  ar& BOOST_SERIALIZATION_NVP(k4_);
195  }
196 
198 };
199 
200 template <>
201 struct traits<Cal3Fisheye> : public internal::Manifold<Cal3Fisheye> {};
202 
203 template <>
204 struct traits<const Cal3Fisheye> : public internal::Manifold<Cal3Fisheye> {};
205 
206 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
double k2() const
Second distortion coefficient.
Definition: Cal3Fisheye.h:97
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
static size_t Dim()
Return dimensions of calibration manifold object.
Definition: Cal3Fisheye.h:158
~Cal3Fisheye() override
Definition: Cal3Fisheye.h:76
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
double k4() const
Second tangential distortion coefficient.
Definition: Cal3Fisheye.h:103
double k1() const
First distortion coefficient.
Definition: Cal3Fisheye.h:94
void serialize(Archive &ar, const unsigned int)
Definition: Cal3Fisheye.h:188
Cal3Fisheye retract(const Vector &d) const
Given delta vector, update calibration.
Definition: Cal3Fisheye.h:161
UniformScaling< float > Scaling(float s)
const double fy
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< Cal3 > shared_ptr
Definition: Cal3.h:78
size_t dim() const override
Return dimensions of calibration manifold object.
Definition: Cal3Fisheye.h:155
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Common code for all Calibration models.
static const double u0
double k3() const
First tangential distortion coefficient.
Definition: Cal3Fisheye.h:100
Vector9 vector() const
Return all parameters as a vector.
Definition: Cal3Fisheye.cpp:28
traits
Definition: chartTesting.h:28
Vector localCoordinates(const Cal3Fisheye &T2) const
Given a different calibration, calculate update to obtain it.
Definition: Cal3Fisheye.h:166
ofstream os("timeSchurFactors.csv")
static const double v0
Point2_ uncalibrate(const Expression< CALIBRATION > &K, const Point2_ &xy_hat)
float * p
Cal3Fisheye(const Vector9 &v)
Definition: Cal3Fisheye.h:82
const G double tol
Definition: Group.h:83
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:66
Vector4 k() const
return distortion parameter vector
Definition: Cal3Fisheye.h:106
virtual boost::shared_ptr< Cal3Fisheye > clone() const
Definition: Cal3Fisheye.h:175


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:44