gtsam 4.1.1
gtsam
SimpleCamera.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
19#pragma once
20
29
30namespace gtsam {
31
39
40#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
45class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 {
46
47 typedef PinholeCamera<Cal3_S2> Base;
48 typedef boost::shared_ptr<SimpleCamera> shared_ptr;
49
50public:
51
54
56 SimpleCamera() :
57 Base() {
58 }
59
61 explicit SimpleCamera(const Pose3& pose) :
62 Base(pose) {
63 }
64
66 SimpleCamera(const Pose3& pose, const Cal3_S2& K) :
67 Base(pose, K) {
68 }
69
73
81 static SimpleCamera Level(const Cal3_S2 &K, const Pose2& pose2,
82 double height) {
83 return SimpleCamera(Base::LevelPose(pose2, height), K);
84 }
85
87 static SimpleCamera Level(const Pose2& pose2, double height) {
88 return SimpleCamera::Level(Cal3_S2(), pose2, height);
89 }
90
100 static SimpleCamera Lookat(const Point3& eye, const Point3& target,
101 const Point3& upVector, const Cal3_S2& K = Cal3_S2()) {
102 return SimpleCamera(Base::LookatPose(eye, target, upVector), K);
103 }
104
108
110 explicit SimpleCamera(const Vector &v) :
111 Base(v) {
112 }
113
115 SimpleCamera(const Vector &v, const Vector &K) :
116 Base(v, K) {
117 }
118
120 SimpleCamera::shared_ptr clone() const { return boost::make_shared<SimpleCamera>(*this); }
121
122
126
128 SimpleCamera retract(const Vector& d) const {
129 if ((size_t) d.size() == 6)
130 return SimpleCamera(this->pose().retract(d), calibration());
131 else
132 return SimpleCamera(this->pose().retract(d.head(6)),
133 calibration().retract(d.tail(calibration().dim())));
134 }
135
137
138};
139
141GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P);
142
143// manifold traits
144template <>
145struct traits<SimpleCamera> : public internal::Manifold<SimpleCamera> {};
146
147template <>
148struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
149
150// range traits, used in RangeFactor
151template <typename T>
152struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
153
154#endif
155
156} // namespace gtsam
The most common 5DOF 3D->2D calibration.
Unified Calibration Model, see Mei07icra for details.
Base class for all pinhole cameras.
Calibration used by Bundler.
Bearing-Range product.
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Calibration of a fisheye camera.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
Definition: Cal3_S2.h:34
Definition: PinholeCamera.h:33
Definition: Pose2.h:36
Definition: Pose3.h:37