GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
CalibratedCamera.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 
22 #include <gtsam/geometry/Point2.h>
23 #include <gtsam/geometry/Pose3.h>
24 #include <gtsam/base/concepts.h>
25 #include <gtsam/base/Manifold.h>
26 #include <gtsam/base/ThreadsafeException.h>
27 #include <gtsam/dllexport.h>
28 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
29 #include <boost/serialization/nvp.hpp>
30 #endif
31 
32 namespace gtsam {
33 
34 class GTSAM_EXPORT CheiralityException: public ThreadsafeException<CheiralityException> {
35 public:
37  : CheiralityException(std::numeric_limits<Key>::max()) {}
38 
40  : ThreadsafeException<CheiralityException>("CheiralityException"),
41  j_(j) {}
42 
43  Key nearbyVariable() const {return j_;}
44 
45 private:
46  Key j_;
47 };
48 
54 class GTSAM_EXPORT PinholeBase {
55 
56 public:
57 
59  typedef Rot3 Rotation;
60  typedef Point3 Translation;
61 
67  typedef Point2Vector MeasurementVector;
68 
69 private:
70 
71  Pose3 pose_;
72 
73 protected:
74 
77 
83  static Matrix26 Dpose(const Point2& pn, double d);
84 
91  static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt);
92 
94 
95 public:
96 
99 
107  static Pose3 LevelPose(const Pose2& pose2, double height);
108 
117  static Pose3 LookatPose(const Point3& eye, const Point3& target,
118  const Point3& upVector);
119 
123 
126 
128  explicit PinholeBase(const Pose3& pose) : pose_(pose) {}
129 
133 
134  explicit PinholeBase(const Vector& v) : pose_(Pose3::Expmap(v)) {}
135 
137  virtual ~PinholeBase() = default;
138 
142 
144  bool equals(const PinholeBase &camera, double tol = 1e-9) const;
145 
147  virtual void print(const std::string& s = "PinholeBase") const;
148 
152 
154  const Pose3& pose() const {
155  return pose_;
156  }
157 
159  const Rot3& rotation() const {
160  return pose_.rotation();
161  }
162 
164  const Point3& translation() const {
165  return pose_.translation();
166  }
167 
169  const Pose3& getPose(OptionalJacobian<6, 6> H) const;
170 
174 
180  static Point2 Project(const Point3& pc, //
181  OptionalJacobian<2, 3> Dpoint = {});
182 
188  static Point2 Project(const Unit3& pc, //
189  OptionalJacobian<2, 2> Dpoint = {});
190 
192  std::pair<Point2, bool> projectSafe(const Point3& pw) const;
193 
199  Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose =
200  {}, OptionalJacobian<2, 3> Dpoint = {}) const;
201 
207  Point2 project2(const Unit3& point,
208  OptionalJacobian<2, 6> Dpose = {},
209  OptionalJacobian<2, 2> Dpoint = {}) const;
210 
212  static Point3 BackprojectFromCamera(const Point2& p, const double depth,
213  OptionalJacobian<3, 2> Dpoint = {},
214  OptionalJacobian<3, 1> Ddepth = {});
215 
219 
225  inline static std::pair<size_t, size_t> translationInterval() {
226  return {3, 5};
227  }
228 
230 
231 private:
232 
233 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
234 
235  friend class boost::serialization::access;
236  template<class Archive>
237  void serialize(Archive & ar, const unsigned int /*version*/) {
238  ar & BOOST_SERIALIZATION_NVP(pose_);
239  }
240 #endif
241 };
242 // end of class PinholeBase
243 
251 class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
252 
253 public:
254 
255  enum {
256  dimension = 6
257  };
258 
261 
264  }
265 
267  explicit CalibratedCamera(const Pose3& pose) :
268  PinholeBase(pose) {
269  }
270 
274 
275  // Create CalibratedCamera, with derivatives
276  static CalibratedCamera Create(const Pose3& pose,
278  if (H1)
279  *H1 << I_6x6;
280  return CalibratedCamera(pose);
281  }
282 
289  static CalibratedCamera Level(const Pose2& pose2, double height);
290 
299  static CalibratedCamera Lookat(const Point3& eye, const Point3& target,
300  const Point3& upVector);
301 
305 
307  explicit CalibratedCamera(const Vector &v) :
308  PinholeBase(v) {
309  }
310 
314 
316  CalibratedCamera retract(const Vector& d) const;
317 
319  Vector localCoordinates(const CalibratedCamera& T2) const;
320 
322  void print(const std::string& s = "CalibratedCamera") const override {
324  }
325 
327  inline size_t dim() const {
328  return dimension;
329  }
330 
332  inline static size_t Dim() {
333  return dimension;
334  }
335 
339 
344  Point2 project(const Point3& point, OptionalJacobian<2, 6> Dcamera =
345  {}, OptionalJacobian<2, 3> Dpoint = {}) const;
346 
348  Point3 backproject(const Point2& pn, double depth,
349  OptionalJacobian<3, 6> Dresult_dpose = {},
350  OptionalJacobian<3, 2> Dresult_dp = {},
351  OptionalJacobian<3, 1> Dresult_ddepth = {}) const {
352 
353  Matrix32 Dpoint_dpn;
354  Matrix31 Dpoint_ddepth;
355  const Point3 point = BackprojectFromCamera(pn, depth,
356  Dresult_dp ? &Dpoint_dpn : 0,
357  Dresult_ddepth ? &Dpoint_ddepth : 0);
358 
359  Matrix33 Dresult_dpoint;
360  const Point3 result = pose().transformFrom(point, Dresult_dpose,
361  (Dresult_ddepth ||
362  Dresult_dp) ? &Dresult_dpoint : 0);
363 
364  if (Dresult_dp)
365  *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
366  if (Dresult_ddepth)
367  *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
368 
369  return result;
370  }
371 
377  double range(const Point3& point,
378  OptionalJacobian<1, 6> Dcamera = {},
379  OptionalJacobian<1, 3> Dpoint = {}) const {
380  return pose().range(point, Dcamera, Dpoint);
381  }
382 
388  double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = {},
389  OptionalJacobian<1, 6> Dpose = {}) const {
390  return this->pose().range(pose, Dcamera, Dpose);
391  }
392 
398  double range(const CalibratedCamera& camera, //
399  OptionalJacobian<1, 6> H1 = {}, //
400  OptionalJacobian<1, 6> H2 = {}) const {
401  return pose().range(camera.pose(), H1, H2);
402  }
403 
405 
406 private:
407 
410 
411 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
412 
413  friend class boost::serialization::access;
414  template<class Archive>
415  void serialize(Archive & ar, const unsigned int /*version*/) {
416  ar
417  & boost::serialization::make_nvp("PinholeBase",
418  boost::serialization::base_object<PinholeBase>(*this));
419  }
420 #endif
421 
423 };
424 
425 // manifold traits
426 template <>
427 struct traits<CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
428 
429 template <>
430 struct traits<const CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
431 
432 // range traits, used in RangeFactor
433 template <typename T>
434 struct Range<CalibratedCamera, T> : HasRange<CalibratedCamera, T, double> {};
435 
436 } // namespace gtsam
PinholeBase(const Pose3 &pose)
Constructor with pose.
Definition: CalibratedCamera.h:128
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1={}, OptionalJacobian< 1, 6 > H2={}) const
Definition: CalibratedCamera.h:398
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Definition: expressions.h:131
Definition: CalibratedCamera.h:251
Point2 Measurement
Definition: CalibratedCamera.h:66
static std::pair< size_t, size_t > translationInterval()
Definition: CalibratedCamera.h:225
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Definition: BearingRange.h:197
Vector2 Point2
Definition: Point2.h:32
Definition: Group.h:43
PinholeBase()
Default constructor.
Definition: CalibratedCamera.h:125
const Point3 & translation() const
get translation
Definition: CalibratedCamera.h:164
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
Definition: CalibratedCamera.h:388
Definition: CalibratedCamera.h:54
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
size_t dim() const
Definition: CalibratedCamera.h:327
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Definition: Testable.h:112
Definition: Pose2.h:39
void print(const std::string &s="CalibratedCamera") const override
print
Definition: CalibratedCamera.h:322
CalibratedCamera(const Pose3 &pose)
construct with pose
Definition: CalibratedCamera.h:267
static Pose3 Expmap(const Vector6 &xi, OptionalJacobian< 6, 6 > Hxi={})
Exponential map at identity - create a rotation from canonical coordinates .
const Pose3 & pose() const
return pose, constant version
Definition: CalibratedCamera.h:154
Base class and basic functions for Manifold types.
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
Definition: ThreadsafeException.h:40
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
CalibratedCamera(const Vector &v)
construct from vector
Definition: CalibratedCamera.h:307
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
Definition: CalibratedCamera.h:377
Definition: BearingRange.h:41
Point3 backproject(const Point2 &pn, double depth, OptionalJacobian< 3, 6 > Dresult_dpose={}, OptionalJacobian< 3, 2 > Dresult_dp={}, OptionalJacobian< 3, 1 > Dresult_ddepth={}) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition: CalibratedCamera.h:348
Definition: chartTesting.h:28
Definition: OptionalJacobian.h:38
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Bearing-Range product.
static size_t Dim()
Definition: CalibratedCamera.h:332
CalibratedCamera()
default constructor
Definition: CalibratedCamera.h:263
const Rot3 & rotation() const
get rotation
Definition: CalibratedCamera.h:159
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: CalibratedCamera.h:34
Vector3 Point3
Definition: Point3.h:38
2D Point
3D Pose
Definition: Pose3.h:37
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Rot3 Rotation
Definition: CalibratedCamera.h:59
virtual void print(const std::string &s="PinholeBase") const
print