Cal3DS2.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 
21 #pragma once
22 
24 #include <memory>
25 
26 namespace gtsam {
27 
35 class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
36  using Base = Cal3DS2_Base;
37 
38  public:
39  enum { dimension = 9 };
40 
42  using shared_ptr = std::shared_ptr<Cal3DS2>;
43 
46 
48  Cal3DS2() = default;
49 
50  Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1,
51  double k2, double p1 = 0.0, double p2 = 0.0, double tol = 1e-5)
52  : Base(fx, fy, s, u0, v0, k1, k2, p1, p2, tol) {}
53 
54  ~Cal3DS2() override {}
55 
59 
60  Cal3DS2(const Vector9& v) : Base(v) {}
61 
65 
67  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
68  const Cal3DS2& cal);
69 
71  void print(const std::string& s = "") const override;
72 
74  bool equals(const Cal3DS2& K, double tol = 10e-9) const;
75 
79 
81  Cal3DS2 retract(const Vector& d) const;
82 
84  Vector localCoordinates(const Cal3DS2& T2) const;
85 
87  size_t dim() const override { return Dim(); }
88 
90  inline static size_t Dim() { return dimension; }
91 
95 
97  std::shared_ptr<Base> clone() const override {
98  return std::shared_ptr<Base>(new Cal3DS2(*this));
99  }
100 
102 
103  private:
106 
107 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
108 
109  friend class boost::serialization::access;
110  template <class Archive>
111  void serialize(Archive& ar, const unsigned int /*version*/) {
112  ar& boost::serialization::make_nvp(
113  "Cal3DS2", boost::serialization::base_object<Cal3DS2_Base>(*this));
114  }
115 #endif
116 
118 };
119 
120 template <>
121 struct traits<Cal3DS2> : public internal::Manifold<Cal3DS2> {};
122 
123 template <>
124 struct traits<const Cal3DS2> : public internal::Manifold<Cal3DS2> {};
125 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
std::shared_ptr< Base > clone() const override
Definition: Cal3DS2.h:97
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
Vector3f p1
std::string serialize(const T &input)
serializes to a string
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Calibration of a camera with radial distortion.
Definition: Cal3DS2_Base.h:42
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
std::shared_ptr< Cal3 > shared_ptr
Definition: Cal3.h:78
size_t dim() const override
Return dimensions of calibration manifold object.
Definition: Cal3DS2.h:87
~Cal3DS2() override
Definition: Cal3DS2.h:54
const double fy
Eigen::VectorXd Vector
Definition: Vector.h:38
Cal3DS2(const Vector9 &v)
Definition: Cal3DS2.h:60
Array< int, Dynamic, 1 > v
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
static const double u0
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
Definition: Cal3DS2.h:35
Cal3DS2(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.h:50
traits
Definition: chartTesting.h:28
static size_t Dim()
Return dimensions of calibration manifold object.
Definition: Cal3DS2.h:90
ofstream os("timeSchurFactors.csv")
static const double v0
static Point3 p2
const G double tol
Definition: Group.h:86
const double fx


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