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 
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  inline constexpr static auto dimension = 6;
256 
259 
262  }
263 
265  explicit CalibratedCamera(const Pose3& pose) :
266  PinholeBase(pose) {
267  }
268 
272 
273  // Create CalibratedCamera, with derivatives
276  if (H1)
277  *H1 << I_6x6;
278  return CalibratedCamera(pose);
279  }
280 
287  static CalibratedCamera Level(const Pose2& pose2, double height);
288 
297  static CalibratedCamera Lookat(const Point3& eye, const Point3& target,
298  const Point3& upVector);
299 
303 
305  explicit CalibratedCamera(const Vector &v) :
306  PinholeBase(v) {
307  }
308 
312 
314  CalibratedCamera retract(const Vector& d) const;
315 
317  Vector localCoordinates(const CalibratedCamera& T2) const;
318 
320  void print(const std::string& s = "CalibratedCamera") const override {
322  }
323 
325  inline size_t dim() const {
326  return dimension;
327  }
328 
330  inline static size_t Dim() {
331  return dimension;
332  }
333 
337 
343  {}, OptionalJacobian<2, 3> Dpoint = {}) const;
344 
346  Point3 backproject(const Point2& pn, double depth,
347  OptionalJacobian<3, 6> Dresult_dpose = {},
348  OptionalJacobian<3, 2> Dresult_dp = {},
349  OptionalJacobian<3, 1> Dresult_ddepth = {}) const {
350 
351  Matrix32 Dpoint_dpn;
352  Matrix31 Dpoint_ddepth;
354  Dresult_dp ? &Dpoint_dpn : 0,
355  Dresult_ddepth ? &Dpoint_ddepth : 0);
356 
357  Matrix33 Dresult_dpoint;
358  const Point3 result = pose().transformFrom(point, Dresult_dpose,
359  (Dresult_ddepth ||
360  Dresult_dp) ? &Dresult_dpoint : 0);
361 
362  if (Dresult_dp)
363  *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
364  if (Dresult_ddepth)
365  *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
366 
367  return result;
368  }
369 
375  double range(const Point3& point,
376  OptionalJacobian<1, 6> Dcamera = {},
377  OptionalJacobian<1, 3> Dpoint = {}) const {
378  return pose().range(point, Dcamera, Dpoint);
379  }
380 
386  double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = {},
387  OptionalJacobian<1, 6> Dpose = {}) const {
388  return this->pose().range(pose, Dcamera, Dpose);
389  }
390 
396  double range(const CalibratedCamera& camera, //
397  OptionalJacobian<1, 6> H1 = {}, //
398  OptionalJacobian<1, 6> H2 = {}) const {
399  return pose().range(camera.pose(), H1, H2);
400  }
401 
403 
404 private:
405 
408 
409 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
410 
411  friend class boost::serialization::access;
412  template<class Archive>
413  void serialize(Archive & ar, const unsigned int /*version*/) {
414  ar
415  & boost::serialization::make_nvp("PinholeBase",
416  boost::serialization::base_object<PinholeBase>(*this));
417  }
418 #endif
419 
421 };
422 
423 // manifold traits
424 template <>
425 struct traits<CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
426 
427 template <>
428 struct traits<const CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
429 
430 // range traits, used in RangeFactor
431 template <typename T>
432 struct Range<CalibratedCamera, T> : HasRange<CalibratedCamera, T, double> {};
433 
434 } // namespace gtsam
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::CalibratedCamera::range
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1={}, OptionalJacobian< 1, 6 > H2={}) const
Definition: CalibratedCamera.h:396
BackprojectFromCamera
static Point3 BackprojectFromCamera(const CalibratedCamera &camera, const Point2 &point, const double &depth)
Definition: testCalibratedCamera.cpp:188
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::CalibratedCamera::CalibratedCamera
CalibratedCamera()
default constructor
Definition: CalibratedCamera.h:261
d
static const double d[K][N]
Definition: igam.h:11
gtsam::ThreadsafeException
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
Definition: ThreadsafeException.h:40
gtsam::PinholeBase::translationInterval
static std::pair< size_t, size_t > translationInterval()
Definition: CalibratedCamera.h:225
gtsam::utils.numerical_derivative.retract
def retract(a, np.ndarray xi)
Definition: numerical_derivative.py:44
gtsam::PinholeBase::print
virtual void print(const std::string &s="PinholeBase") const
print
Definition: CalibratedCamera.cpp:74
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
concepts.h
gtsam::internal::Manifold
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::CheiralityException::CheiralityException
CheiralityException()
Definition: CalibratedCamera.h:36
gtsam::CalibratedCamera::range
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
Definition: CalibratedCamera.h:375
gtsam::CalibratedCamera::Create
static CalibratedCamera Create(const Pose3 &pose, OptionalJacobian< dimension, 6 > H1={})
Definition: CalibratedCamera.h:274
Point2.h
2D Point
gtsam::CheiralityException
Definition: CalibratedCamera.h:34
gtsam::project2
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
Definition: slam/expressions.h:151
gtsam::PinholeBase::PinholeBase
PinholeBase(const Pose3 &pose)
Constructor with pose.
Definition: CalibratedCamera.h:128
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::PinholeBase::Translation
Point3 Translation
Definition: CalibratedCamera.h:60
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
ThreadsafeException.h
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::CalibratedCamera::range
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
Definition: CalibratedCamera.h:386
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::CalibratedCamera::print
void print(const std::string &s="CalibratedCamera") const override
print
Definition: CalibratedCamera.h:320
gtsam::PinholeBase::pose_
Pose3 pose_
3D pose of camera
Definition: CalibratedCamera.h:71
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:310
gtsam::PinholeBase::PinholeBase
PinholeBase()
Default constructor.
Definition: CalibratedCamera.h:125
gtsam::CheiralityException::nearbyVariable
Key nearbyVariable() const
Definition: CalibratedCamera.h:43
gtsam::CalibratedCamera::CalibratedCamera
CalibratedCamera(const Pose3 &pose)
construct with pose
Definition: CalibratedCamera.h:265
Manifold.h
Base class and basic functions for Manifold types.
gtsam::PinholeBase
Definition: CalibratedCamera.h:54
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
Eigen::Triplet< double >
gtsam::Range
Definition: BearingRange.h:41
gtsam::CalibratedCamera
Definition: CalibratedCamera.h:251
pc
int RealScalar int RealScalar int RealScalar * pc
Definition: level1_cplx_impl.h:119
gtsam::equals
Definition: Testable.h:112
gtsam::getPose
Pose3_ getPose(const Expression< PinholeCamera< CALIBRATION > > &cam)
Definition: slam/expressions.h:177
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:316
gtsam::PinholeBase::PinholeBase
PinholeBase(const Vector &v)
Definition: CalibratedCamera.h:134
gtsam
traits
Definition: SFMdata.h:40
gtsam::PinholeBase::translation
const Point3 & translation() const
get translation
Definition: CalibratedCamera.h:164
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::CalibratedCamera::dim
size_t dim() const
Definition: CalibratedCamera.h:325
std
Definition: BFloat16.h:88
gtsam::HasRange
Definition: BearingRange.h:195
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::PinholeBase::pose
const Pose3 & pose() const
return pose, constant version
Definition: CalibratedCamera.h:154
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::CalibratedCamera::Dim
static size_t Dim()
Definition: CalibratedCamera.h:330
gtsam::Point2Vector
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:49
gtsam::CalibratedCamera::CalibratedCamera
CalibratedCamera(const Vector &v)
construct from vector
Definition: CalibratedCamera.h:305
gtsam::PinholeBase::Rotation
Rot3 Rotation
Definition: CalibratedCamera.h:59
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::CheiralityException::j_
Key j_
Definition: CalibratedCamera.h:46
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
BearingRange.h
Bearing-Range product.
camera
static const CalibratedCamera camera(kDefaultPose)
Project
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpressionFactor.cpp:40
gtsam::CheiralityException::CheiralityException
CheiralityException(Key j)
Definition: CalibratedCamera.h:39
gtsam::CalibratedCamera::backproject
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:346
depth
static double depth
Definition: testSphericalCamera.cpp:64
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::project
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Definition: slam/expressions.h:131
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::PinholeBase::rotation
const Rot3 & rotation() const
get rotation
Definition: CalibratedCamera.h:159
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::PinholeBase::Measurement
Point2 Measurement
Definition: CalibratedCamera.h:66
gtsam::Pose2
Definition: Pose2.h:39
gtsam::PinholeBase::MeasurementVector
Point2Vector MeasurementVector
Definition: CalibratedCamera.h:67


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:13