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 #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:
47 };
48 
54 class GTSAM_EXPORT PinholeBase {
55 
56 public:
57 
59  typedef Rot3 Rotation;
61 
68 
69 private:
70 
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 
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
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 
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.
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1={}, OptionalJacobian< 1, 6 > H2={}) const
#define max(a, b)
Definition: datatypes.h:20
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Pose3_ getPose(const Expression< PinholeCamera< CALIBRATION > > &cam)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:308
static std::pair< size_t, size_t > translationInterval()
static Point3 BackprojectFromCamera(const CalibratedCamera &camera, const Point2 &point, const double &depth)
std::string serialize(const T &input)
serializes to a string
int RealScalar int RealScalar int RealScalar * pc
static double depth
Vector2 Point2
Definition: Point2.h:32
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
Pose2_ Expmap(const Vector3_ &xi)
Pose3 pose_
3D pose of camera
Definition: BFloat16.h:88
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
PinholeBase()
Default constructor.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange [*:*] noreverse nowriteback set trange [*:*] noreverse nowriteback set urange [*:*] noreverse nowriteback set vrange [*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
const Point3 & translation() const
get translation
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
virtual void print(const std::string &s="PinholeBase") const
print
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
void print(const std::string &s="CalibratedCamera") const override
print
CalibratedCamera(const Pose3 &pose)
construct with pose
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
const Pose3 & pose() const
return pose, constant version
Base class and basic functions for Manifold types.
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
Array< int, Dynamic, 1 > v
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
CalibratedCamera(const Vector &v)
construct from vector
static CalibratedCamera Create(const Pose3 &pose, OptionalJacobian< dimension, 6 > H1={})
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
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
traits
Definition: chartTesting.h:28
PinholeBase(const Vector &v)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Bearing-Range product.
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:49
CalibratedCamera()
default constructor
float * p
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
const Rot3 & rotation() const
get rotation
static Pose3 pose2
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:315
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
Point2Vector MeasurementVector
static const CalibratedCamera camera(kDefaultPose)
2D Point
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::ptrdiff_t j


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:00