gtsam  4.0.0
gtsam
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>
27 #include <gtsam/dllexport.h>
28 #include <boost/serialization/nvp.hpp>
29 
30 namespace gtsam {
31 
32 class GTSAM_EXPORT CheiralityException: public ThreadsafeException<
33  CheiralityException> {
34 public:
36  : CheiralityException(std::numeric_limits<Key>::max()) {}
37 
39  : ThreadsafeException<CheiralityException>("CheiralityException"),
40  j_(j) {}
41 
42  Key nearbyVariable() const {return j_;}
43 
44 private:
45  Key j_;
46 };
47 
53 class GTSAM_EXPORT PinholeBase {
54 
55 public:
56 
58  typedef Rot3 Rotation;
59  typedef Point3 Translation;
60 
66  typedef Point2Vector MeasurementVector;
67 
68 private:
69 
70  Pose3 pose_;
71 
72 protected:
73 
76 
82  static Matrix26 Dpose(const Point2& pn, double d);
83 
90  static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt);
91 
93 
94 public:
95 
98 
106  static Pose3 LevelPose(const Pose2& pose2, double height);
107 
116  static Pose3 LookatPose(const Point3& eye, const Point3& target,
117  const Point3& upVector);
118 
122 
125  }
126 
128  explicit PinholeBase(const Pose3& pose) :
129  pose_(pose) {
130  }
131 
135 
136  explicit PinholeBase(const Vector &v) :
137  pose_(Pose3::Expmap(v)) {
138  }
139 
143 
145  bool equals(const PinholeBase &camera, double tol = 1e-9) const;
146 
148  void print(const std::string& s = "PinholeBase") const;
149 
153 
155  const Pose3& pose() const {
156  return pose_;
157  }
158 
160  const Rot3& rotation() const {
161  return pose_.rotation();
162  }
163 
165  const Point3& translation() const {
166  return pose_.translation();
167  }
168 
170  const Pose3& getPose(OptionalJacobian<6, 6> H) const;
171 
175 
181  static Point2 Project(const Point3& pc, //
182  OptionalJacobian<2, 3> Dpoint = boost::none);
183 
189  static Point2 Project(const Unit3& pc, //
190  OptionalJacobian<2, 2> Dpoint = boost::none);
191 
193  std::pair<Point2, bool> projectSafe(const Point3& pw) const;
194 
200  Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose =
201  boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
202 
208  Point2 project2(const Unit3& point,
209  OptionalJacobian<2, 6> Dpose = boost::none,
210  OptionalJacobian<2, 2> Dpoint = boost::none) const;
211 
213  static Point3 BackprojectFromCamera(const Point2& p, const double depth,
214  OptionalJacobian<3, 2> Dpoint = boost::none,
215  OptionalJacobian<3, 1> Ddepth = boost::none);
216 
220 
226  inline static std::pair<size_t, size_t> translationInterval() {
227  return std::make_pair(3, 5);
228  }
229 
231 
232 private:
233 
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 };
241 // end of class PinholeBase
242 
250 class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
251 
252 public:
253 
254  enum {
255  dimension = 6
256  };
257 
260 
263  }
264 
266  explicit CalibratedCamera(const Pose3& pose) :
267  PinholeBase(pose) {
268  }
269 
273 
274  // Create CalibratedCamera, with derivatives
275  static CalibratedCamera Create(const Pose3& pose,
276  OptionalJacobian<dimension, 6> H1 = boost::none) {
277  if (H1)
278  *H1 << I_6x6;
279  return CalibratedCamera(pose);
280  }
281 
288  static CalibratedCamera Level(const Pose2& pose2, double height);
289 
298  static CalibratedCamera Lookat(const Point3& eye, const Point3& target,
299  const Point3& upVector);
300 
304 
306  explicit CalibratedCamera(const Vector &v) :
307  PinholeBase(v) {
308  }
309 
313 
315  virtual ~CalibratedCamera() {
316  }
317 
321 
323  CalibratedCamera retract(const Vector& d) const;
324 
326  Vector localCoordinates(const CalibratedCamera& T2) const;
327 
329  inline size_t dim() const {
330  return 6;
331  }
332 
334  inline static size_t Dim() {
335  return 6;
336  }
337 
341 
346  Point2 project(const Point3& point, OptionalJacobian<2, 6> Dcamera =
347  boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
348 
350  Point3 backproject(const Point2& pn, double depth,
351  OptionalJacobian<3, 6> Dresult_dpose = boost::none,
352  OptionalJacobian<3, 2> Dresult_dp = boost::none,
353  OptionalJacobian<3, 1> Dresult_ddepth = boost::none) const {
354 
355  Matrix32 Dpoint_dpn;
356  Matrix31 Dpoint_ddepth;
357  const Point3 point = BackprojectFromCamera(pn, depth,
358  Dresult_dp ? &Dpoint_dpn : 0,
359  Dresult_ddepth ? &Dpoint_ddepth : 0);
360 
361  Matrix33 Dresult_dpoint;
362  const Point3 result = pose().transformFrom(point, Dresult_dpose,
363  (Dresult_ddepth ||
364  Dresult_dp) ? &Dresult_dpoint : 0);
365 
366  if (Dresult_dp)
367  *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
368  if (Dresult_ddepth)
369  *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
370 
371  return result;
372  }
373 
379  double range(const Point3& point,
380  OptionalJacobian<1, 6> Dcamera = boost::none,
381  OptionalJacobian<1, 3> Dpoint = boost::none) const {
382  return pose().range(point, Dcamera, Dpoint);
383  }
384 
390  double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = boost::none,
391  OptionalJacobian<1, 6> Dpose = boost::none) const {
392  return this->pose().range(pose, Dcamera, Dpose);
393  }
394 
400  double range(const CalibratedCamera& camera, //
401  OptionalJacobian<1, 6> H1 = boost::none, //
402  OptionalJacobian<1, 6> H2 = boost::none) const {
403  return pose().range(camera.pose(), H1, H2);
404  }
405 
407 
408 private:
409 
412 
414  friend class boost::serialization::access;
415  template<class Archive>
416  void serialize(Archive & ar, const unsigned int /*version*/) {
417  ar
418  & boost::serialization::make_nvp("PinholeBase",
419  boost::serialization::base_object<PinholeBase>(*this));
420  }
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
Point3 backproject(const Point2 &pn, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition: CalibratedCamera.h:350
Definition: CalibratedCamera.h:53
Base class and basic functions for Manifold types.
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Definition: Point3.h:45
Base exception type that uses tbb_exception if GTSAM is compiled with TBB.
Definition: ThreadsafeException.h:39
const Point3 & translation(OptionalJacobian< 3, 6 > H=boost::none) const
get translation
Definition: Pose3.cpp:265
PinholeBase()
default constructor
Definition: CalibratedCamera.h:124
const Rot3 & rotation() const
get rotation
Definition: CalibratedCamera.h:160
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1=boost::none, OptionalJacobian< 1, 6 > H2=boost::none) const
Calculate range to another camera.
Definition: CalibratedCamera.h:400
Bearing-Range product.
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Definition: Rot3.h:56
Point3 transformFrom(const Point3 &p, OptionalJacobian< 3, 6 > Dpose=boost::none, OptionalJacobian< 3, 3 > Dpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:312
Definition: CalibratedCamera.h:32
double range(const Point3 &point, OptionalJacobian< 1, 6 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const
Calculate range to a landmark.
Definition: Pose3.cpp:348
2D Point
Definition: BearingRange.h:193
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Definition: expressions.h:57
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
PinholeBase(const Pose3 &pose)
constructor with pose
Definition: CalibratedCamera.h:128
Definition: CalibratedCamera.h:250
Rot3 Rotation
Pose Concept requirements.
Definition: CalibratedCamera.h:58
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
const Point3 & translation() const
get translation
Definition: CalibratedCamera.h:165
Definition: Pose2.h:36
3D Pose
CalibratedCamera(const Pose3 &pose)
construct with pose
Definition: CalibratedCamera.h:266
virtual ~CalibratedCamera()
destructor
Definition: CalibratedCamera.h:315
Definition: BearingRange.h:39
Definition: Point2.h:40
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
Calculate range to another pose.
Definition: CalibratedCamera.h:390
const Rot3 & rotation(OptionalJacobian< 3, 6 > H=boost::none) const
get rotation
Definition: Pose3.cpp:272
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
size_t dim() const
Definition: CalibratedCamera.h:329
CalibratedCamera()
default constructor
Definition: CalibratedCamera.h:262
const Pose3 & pose() const
return pose, constant version
Definition: CalibratedCamera.h:155
Point2 Measurement
Some classes template on either PinholeCamera or StereoCamera, and this typedef informs those classes...
Definition: CalibratedCamera.h:65
Definition: Pose3.h:37
static std::pair< size_t, size_t > translationInterval()
Return the start and end indices (inclusive) of the translation component of the exponential map para...
Definition: CalibratedCamera.h:226
CalibratedCamera(const Vector &v)
construct from vector
Definition: CalibratedCamera.h:306
static size_t Dim()
Definition: CalibratedCamera.h:334
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Calculate range to a landmark.
Definition: CalibratedCamera.h:379
Base exception type that uses tbb_exception if GTSAM is compiled with TBB.