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 
23 #include <gtsam/geometry/Cal3DS2.h>
25 #include <gtsam/geometry/Cal3_S2.h>
27 
28 namespace gtsam {
29 
36 
37 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
38 
42 class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 {
43 
45  typedef boost::shared_ptr<SimpleCamera> shared_ptr;
46 
47 public:
48 
51 
53  SimpleCamera() :
54  Base() {
55  }
56 
58  explicit SimpleCamera(const Pose3& pose) :
59  Base(pose) {
60  }
61 
63  SimpleCamera(const Pose3& pose, const Cal3_S2& K) :
64  Base(pose, K) {
65  }
66 
70 
78  static SimpleCamera Level(const Cal3_S2 &K, const Pose2& pose2,
79  double height) {
80  return SimpleCamera(Base::LevelPose(pose2, height), K);
81  }
82 
84  static SimpleCamera Level(const Pose2& pose2, double height) {
85  return SimpleCamera::Level(Cal3_S2(), pose2, height);
86  }
87 
97  static SimpleCamera Lookat(const Point3& eye, const Point3& target,
98  const Point3& upVector, const Cal3_S2& K = Cal3_S2()) {
99  return SimpleCamera(Base::LookatPose(eye, target, upVector), K);
100  }
101 
105 
107  explicit SimpleCamera(const Vector &v) :
108  Base(v) {
109  }
110 
112  SimpleCamera(const Vector &v, const Vector &K) :
113  Base(v, K) {
114  }
115 
117  SimpleCamera::shared_ptr clone() const { return boost::make_shared<SimpleCamera>(*this); }
118 
119 
123 
125  SimpleCamera retract(const Vector& d) const {
126  if ((size_t) d.size() == 6)
127  return SimpleCamera(this->pose().retract(d), calibration());
128  else
129  return SimpleCamera(this->pose().retract(d.head(6)),
130  calibration().retract(d.tail(calibration().dim())));
131  }
132 
134 
135 };
136 
138 GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P);
139 
140 // manifold traits
141 template <>
142 struct traits<SimpleCamera> : public internal::Manifold<SimpleCamera> {};
143 
144 template <>
145 struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
146 
147 // range traits, used in RangeFactor
148 template <typename T>
149 struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
150 
151 #endif
152 
153 } // namespace gtsam
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
ArrayXcf v
Definition: Cwise_arg.cpp:1
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Base class for all pinhole cameras.
Eigen::VectorXd Vector
Definition: Vector.h:38
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
traits
Definition: chartTesting.h:28
Bearing-Range product.
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
Unified Calibration Model, see Mei07icra for details.
Calibration used by Bundler.
The most common 5DOF 3D->2D calibration.


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