gtsam 4.1.1
gtsam
Cal3_S2.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
22#pragma once
23
24#include <gtsam/geometry/Cal3.h>
26
27namespace gtsam {
28
34class GTSAM_EXPORT Cal3_S2 : public Cal3 {
35 public:
36 enum { dimension = 5 };
37
39 using shared_ptr = boost::shared_ptr<Cal3_S2>;
40
43
45 Cal3_S2() = default;
46
48 Cal3_S2(double fx, double fy, double s, double u0, double v0)
49 : Cal3(fx, fy, s, u0, v0) {}
50
52 Cal3_S2(const Vector5& d) : Cal3(d) {}
53
60 Cal3_S2(double fov, int w, int h) : Cal3(fov, w, h) {}
61
69 Point2 uncalibrate(const Point2& p, OptionalJacobian<2, 5> Dcal = boost::none,
70 OptionalJacobian<2, 2> Dp = boost::none) const;
71
79 Point2 calibrate(const Point2& p, OptionalJacobian<2, 5> Dcal = boost::none,
80 OptionalJacobian<2, 2> Dp = boost::none) const;
81
87 Vector3 calibrate(const Vector3& p) const;
88
92
94 GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
95 const Cal3_S2& cal);
96
98 void print(const std::string& s = "Cal3_S2") const override;
99
101 bool equals(const Cal3_S2& K, double tol = 10e-9) const;
102
104 inline Cal3_S2 between(const Cal3_S2& q,
105 OptionalJacobian<5, 5> H1 = boost::none,
106 OptionalJacobian<5, 5> H2 = boost::none) const {
107 if (H1) *H1 = -I_5x5;
108 if (H2) *H2 = I_5x5;
109 return Cal3_S2(q.fx_ - fx_, q.fy_ - fy_, q.s_ - s_, q.u0_ - u0_,
110 q.v0_ - v0_);
111 }
112
116
118 inline static size_t Dim() { return dimension; }
119
121 inline Cal3_S2 retract(const Vector& d) const {
122 return Cal3_S2(fx_ + d(0), fy_ + d(1), s_ + d(2), u0_ + d(3), v0_ + d(4));
123 }
124
126 Vector5 localCoordinates(const Cal3_S2& T2) const {
127 return T2.vector() - vector();
128 }
129
133
134 private:
136 friend class boost::serialization::access;
137 template <class Archive>
138 void serialize(Archive& ar, const unsigned int /*version*/) {
139 ar& boost::serialization::make_nvp(
140 "Cal3_S2", boost::serialization::base_object<Cal3>(*this));
141 }
142
144};
145
146template <>
147struct traits<Cal3_S2> : public internal::Manifold<Cal3_S2> {};
148
149template <>
150struct traits<const Cal3_S2> : public internal::Manifold<Cal3_S2> {};
151
152} // \ namespace gtsam
2D Point
Common code for all Calibration models.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Template to create a binary predicate.
Definition: Testable.h:111
Definition: Cal3.h:69
Vector5 vector() const
vectorized form (column-wise)
Definition: Cal3.h:160
double fy_
focal length
Definition: Cal3.h:71
double s_
skew
Definition: Cal3.h:72
double v0_
principal point
Definition: Cal3.h:73
Definition: Cal3_S2.h:34
Cal3_S2()=default
Create a default calibration that leaves coordinates unchanged.
Cal3_S2(double fx, double fy, double s, double u0, double v0)
constructor from doubles
Definition: Cal3_S2.h:48
Cal3_S2 between(const Cal3_S2 &q, OptionalJacobian< 5, 5 > H1=boost::none, OptionalJacobian< 5, 5 > H2=boost::none) const
"Between", subtracts calibrations. between(p,q) == compose(inverse(p),q)
Definition: Cal3_S2.h:104
static size_t Dim()
return DOF, dimensionality of tangent space
Definition: Cal3_S2.h:118
Cal3_S2(const Vector5 &d)
constructor from vector
Definition: Cal3_S2.h:52
Vector5 localCoordinates(const Cal3_S2 &T2) const
Unretraction for the calibration.
Definition: Cal3_S2.h:126
Cal3_S2(double fov, int w, int h)
Easy constructor, takes fov in degrees, asssumes zero skew, unit aspect.
Definition: Cal3_S2.h:60
Cal3_S2 retract(const Vector &d) const
Given 5-dim tangent vector, create new calibration.
Definition: Cal3_S2.h:121