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<CheiralityException> {
33 public:
35  : CheiralityException(std::numeric_limits<Key>::max()) {}
36 
38  : ThreadsafeException<CheiralityException>("CheiralityException"),
39  j_(j) {}
40 
41  Key nearbyVariable() const {return j_;}
42 
43 private:
45 };
46 
52 class GTSAM_EXPORT PinholeBase {
53 
54 public:
55 
57  typedef Rot3 Rotation;
59 
66 
67 private:
68 
70 
71 protected:
72 
75 
81  static Matrix26 Dpose(const Point2& pn, double d);
82 
89  static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt);
90 
92 
93 public:
94 
97 
105  static Pose3 LevelPose(const Pose2& pose2, double height);
106 
115  static Pose3 LookatPose(const Point3& eye, const Point3& target,
116  const Point3& upVector);
117 
121 
124 
126  explicit PinholeBase(const Pose3& pose) : pose_(pose) {}
127 
131 
132  explicit PinholeBase(const Vector& v) : pose_(Pose3::Expmap(v)) {}
133 
135  virtual ~PinholeBase() = default;
136 
140 
142  bool equals(const PinholeBase &camera, double tol = 1e-9) const;
143 
145  virtual void print(const std::string& s = "PinholeBase") const;
146 
150 
152  const Pose3& pose() const {
153  return pose_;
154  }
155 
157  const Rot3& rotation() const {
158  return pose_.rotation();
159  }
160 
162  const Point3& translation() const {
163  return pose_.translation();
164  }
165 
167  const Pose3& getPose(OptionalJacobian<6, 6> H) const;
168 
172 
178  static Point2 Project(const Point3& pc, //
179  OptionalJacobian<2, 3> Dpoint = boost::none);
180 
186  static Point2 Project(const Unit3& pc, //
187  OptionalJacobian<2, 2> Dpoint = boost::none);
188 
190  std::pair<Point2, bool> projectSafe(const Point3& pw) const;
191 
198  boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
199 
205  Point2 project2(const Unit3& point,
206  OptionalJacobian<2, 6> Dpose = boost::none,
207  OptionalJacobian<2, 2> Dpoint = boost::none) const;
208 
210  static Point3 BackprojectFromCamera(const Point2& p, const double depth,
211  OptionalJacobian<3, 2> Dpoint = boost::none,
212  OptionalJacobian<3, 1> Ddepth = boost::none);
213 
217 
223  inline static std::pair<size_t, size_t> translationInterval() {
224  return std::make_pair(3, 5);
225  }
226 
228 
229 private:
230 
232  friend class boost::serialization::access;
233  template<class Archive>
234  void serialize(Archive & ar, const unsigned int /*version*/) {
235  ar & BOOST_SERIALIZATION_NVP(pose_);
236  }
237 };
238 // end of class PinholeBase
239 
247 class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
248 
249 public:
250 
251  enum {
252  dimension = 6
253  };
254 
257 
260  }
261 
263  explicit CalibratedCamera(const Pose3& pose) :
264  PinholeBase(pose) {
265  }
266 
270 
271  // Create CalibratedCamera, with derivatives
273  OptionalJacobian<dimension, 6> H1 = boost::none) {
274  if (H1)
275  *H1 << I_6x6;
276  return CalibratedCamera(pose);
277  }
278 
285  static CalibratedCamera Level(const Pose2& pose2, double height);
286 
295  static CalibratedCamera Lookat(const Point3& eye, const Point3& target,
296  const Point3& upVector);
297 
301 
303  explicit CalibratedCamera(const Vector &v) :
304  PinholeBase(v) {
305  }
306 
310 
312  virtual ~CalibratedCamera() {
313  }
314 
318 
320  CalibratedCamera retract(const Vector& d) const;
321 
323  Vector localCoordinates(const CalibratedCamera& T2) const;
324 
326  void print(const std::string& s = "CalibratedCamera") const override {
328  }
329 
331  inline size_t dim() const {
332  return dimension;
333  }
334 
336  inline static size_t Dim() {
337  return dimension;
338  }
339 
343 
349  boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
350 
352  Point3 backproject(const Point2& pn, double depth,
353  OptionalJacobian<3, 6> Dresult_dpose = boost::none,
354  OptionalJacobian<3, 2> Dresult_dp = boost::none,
355  OptionalJacobian<3, 1> Dresult_ddepth = boost::none) const {
356 
357  Matrix32 Dpoint_dpn;
358  Matrix31 Dpoint_ddepth;
359  const Point3 point = BackprojectFromCamera(pn, depth,
360  Dresult_dp ? &Dpoint_dpn : 0,
361  Dresult_ddepth ? &Dpoint_ddepth : 0);
362 
363  Matrix33 Dresult_dpoint;
364  const Point3 result = pose().transformFrom(point, Dresult_dpose,
365  (Dresult_ddepth ||
366  Dresult_dp) ? &Dresult_dpoint : 0);
367 
368  if (Dresult_dp)
369  *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
370  if (Dresult_ddepth)
371  *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
372 
373  return result;
374  }
375 
381  double range(const Point3& point,
382  OptionalJacobian<1, 6> Dcamera = boost::none,
383  OptionalJacobian<1, 3> Dpoint = boost::none) const {
384  return pose().range(point, Dcamera, Dpoint);
385  }
386 
392  double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = boost::none,
393  OptionalJacobian<1, 6> Dpose = boost::none) const {
394  return this->pose().range(pose, Dcamera, Dpose);
395  }
396 
402  double range(const CalibratedCamera& camera, //
403  OptionalJacobian<1, 6> H1 = boost::none, //
404  OptionalJacobian<1, 6> H2 = boost::none) const {
405  return pose().range(camera.pose(), H1, H2);
406  }
407 
409 
410 private:
411 
414 
416  friend class boost::serialization::access;
417  template<class Archive>
418  void serialize(Archive & ar, const unsigned int /*version*/) {
419  ar
420  & boost::serialization::make_nvp("PinholeBase",
421  boost::serialization::base_object<PinholeBase>(*this));
422  }
423 
425 };
426 
427 // manifold traits
428 template <>
429 struct traits<CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
430 
431 template <>
432 struct traits<const CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
433 
434 // range traits, used in RangeFactor
435 template <typename T>
436 struct Range<CalibratedCamera, T> : HasRange<CalibratedCamera, T, double> {};
437 
438 } // namespace gtsam
PinholeBase(const Pose3 &pose)
Constructor with pose.
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
#define max(a, b)
Definition: datatypes.h:20
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
static std::pair< size_t, size_t > translationInterval()
static Point3 BackprojectFromCamera(const CalibratedCamera &camera, const Point2 &point, const double &depth)
virtual ~CalibratedCamera()
destructor
virtual void print(const std::string &s="PinholeBase") const
print
int RealScalar int RealScalar int RealScalar * pc
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1=boost::none, OptionalJacobian< 1, 6 > H2=boost::none) const
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
Pose2_ Expmap(const Vector3_ &xi)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Pose3 pose_
3D pose of camera
Definition: Half.h:150
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
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 Pose3 & pose() const
return pose, constant version
const Rot3 & rotation() const
get rotation
Point3 point(10, 0,-5)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
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
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
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:42
Base class and basic functions for Manifold types.
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
CalibratedCamera(const Vector &v)
construct from vector
traits
Definition: chartTesting.h:28
PinholeBase(const Vector &v)
Bearing-Range product.
static CalibratedCamera Create(const Pose3 &pose, OptionalJacobian< dimension, 6 > H1=boost::none)
CalibratedCamera()
default constructor
float * p
void serialize(Archive &ar, const unsigned int)
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
const G double tol
Definition: Group.h:83
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
void serialize(Archive &ar, const unsigned int)
Point2Vector MeasurementVector
static const CalibratedCamera camera(kDefaultPose)
2D Point
3D Pose
const Point3 & translation() const
get translation
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


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