PinholeCamera.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 
23 
24 namespace gtsam {
25 
32 template<typename Calibration>
33 class PinholeCamera: public PinholeBaseK<Calibration> {
34 
35 public:
36 
43 
44 private:
45 
47  Calibration K_;
48 
49  // Get dimensions of calibration type at compile time
51 
52 public:
53 
54  enum {
56  };
57 
60 
63  }
64 
66  explicit PinholeCamera(const Pose3& pose) :
67  Base(pose) {
68  }
69 
71  PinholeCamera(const Pose3& pose, const Calibration& K) :
72  Base(pose), K_(K) {
73  }
74 
78 
86  static PinholeCamera Level(const Calibration &K, const Pose2& pose2,
87  double height) {
88  return PinholeCamera(Base::LevelPose(pose2, height), K);
89  }
90 
92  static PinholeCamera Level(const Pose2& pose2, double height) {
93  return PinholeCamera::Level(Calibration(), pose2, height);
94  }
95 
105  static PinholeCamera Lookat(const Point3& eye, const Point3& target,
106  const Point3& upVector, const Calibration& K = Calibration()) {
107  return PinholeCamera(Base::LookatPose(eye, target, upVector), K);
108  }
109 
110  // Create PinholeCamera, with derivatives
111  static PinholeCamera Create(const Pose3& pose, const Calibration &K,
114  typedef Eigen::Matrix<double, DimK, 6> MatrixK6;
115  if (H1)
116  *H1 << I_6x6, MatrixK6::Zero();
117  typedef Eigen::Matrix<double, 6, DimK> Matrix6K;
118  typedef Eigen::Matrix<double, DimK, DimK> MatrixK;
119  if (H2)
120  *H2 << Matrix6K::Zero(), MatrixK::Identity();
121  return PinholeCamera(pose,K);
122  }
123 
127 
129  explicit PinholeCamera(const Vector &v) :
130  Base(v.head<6>()) {
131  if (v.size() > 6)
132  K_ = Calibration(v.tail<DimK>());
133  }
134 
136  PinholeCamera(const Vector &v, const Vector &K) :
137  Base(v), K_(K) {
138  }
139 
143 
145  bool equals(const Base &camera, double tol = 1e-9) const {
146  const PinholeCamera* e = dynamic_cast<const PinholeCamera*>(&camera);
147  return Base::equals(camera, tol) && K_.equals(e->calibration(), tol);
148  }
149 
151  void print(const std::string& s = "PinholeCamera") const override {
152  Base::print(s);
153  K_.print(s + ".calibration");
154  }
155 
159 
160  ~PinholeCamera() override {
161  }
162 
164  const Pose3& pose() const {
165  return Base::pose();
166  }
167 
170  if (H) {
171  H->setZero();
172  H->template block<6, 6>(0, 0) = I_6x6;
173  }
174  return Base::pose();
175  }
176 
178  const Calibration& calibration() const override {
179  return K_;
180  }
181 
185 
187  size_t dim() const {
188  return dimension;
189  }
190 
192  static size_t Dim() {
193  return dimension;
194  }
195 
197 
199  PinholeCamera retract(const Vector& d) const {
200  if ((size_t) d.size() == 6)
201  return PinholeCamera(this->pose().retract(d), calibration());
202  else
203  return PinholeCamera(this->pose().retract(d.head<6>()),
204  calibration().retract(d.tail(calibration().dim())));
205  }
206 
209  VectorK6 d;
210  d.template head<6>() = this->pose().localCoordinates(T2.pose());
211  d.template tail<DimK>() = calibration().localCoordinates(T2.calibration());
212  return d;
213  }
214 
217  return PinholeCamera(); // assumes that the default constructor is valid
218  }
219 
223 
225 
229  template<class POINT>
232  // We just call 3-derivative version in Base
233  if (Dcamera){
234  Matrix26 Dpose;
236  const Point2 pi = Base::project(pw, Dpose, Dpoint, Dcal);
237  *Dcamera << Dpose, Dcal;
238  return pi;
239  } else {
240  return Base::project(pw, {}, Dpoint, {});
241  }
242  }
243 
246  {}, OptionalJacobian<2, 3> Dpoint = {}) const {
247  return _project2(pw, Dcamera, Dpoint);
248  }
249 
252  {}, OptionalJacobian<2, 2> Dpoint = {}) const {
253  return _project2(pw, Dcamera, Dpoint);
254  }
255 
262  {}, OptionalJacobian<1, 3> Dpoint = {}) const {
263  Matrix16 Dpose_;
264  double result = this->pose().range(point, Dcamera ? &Dpose_ : 0, Dpoint);
265  if (Dcamera)
266  *Dcamera << Dpose_, Eigen::Matrix<double, 1, DimK>::Zero();
267  return result;
268  }
269 
276  {}, OptionalJacobian<1, 6> Dpose = {}) const {
277  Matrix16 Dpose_;
278  double result = this->pose().range(pose, Dcamera ? &Dpose_ : 0, Dpose);
279  if (Dcamera)
280  *Dcamera << Dpose_, Eigen::Matrix<double, 1, DimK>::Zero();
281  return result;
282  }
283 
289  template<class CalibrationB>
291  OptionalJacobian<1, dimension> Dcamera = {},
293  Matrix16 Dcamera_, Dother_;
294  double result = this->pose().range(camera.pose(), Dcamera ? &Dcamera_ : 0,
295  Dother ? &Dother_ : 0);
296  if (Dcamera) {
297  *Dcamera << Dcamera_, Eigen::Matrix<double, 1, DimK>::Zero();
298  }
299  if (Dother) {
300  Dother->setZero();
301  Dother->template block<1, 6>(0, 0) = Dother_;
302  }
303  return result;
304  }
305 
312  OptionalJacobian<1, dimension> Dcamera = {},
313  OptionalJacobian<1, 6> Dother = {}) const {
314  return range(camera.pose(), Dcamera, Dother);
315  }
316 
318  Matrix34 cameraProjectionMatrix() const {
319  return K_.K() * PinholeBase::pose().inverse().matrix().block(0, 0, 3, 4);
320  }
321 
324  return Eigen::Matrix<double,traits<Point2>::dimension,1>::Constant(2.0 * K_.fx());
325  }
326 
327 private:
328 
329 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
330 
331  friend class boost::serialization::access;
332  template<class Archive>
333  void serialize(Archive & ar, const unsigned int /*version*/) {
334  ar
335  & boost::serialization::make_nvp("PinholeBaseK",
336  boost::serialization::base_object<Base>(*this));
337  ar & BOOST_SERIALIZATION_NVP(K_);
338  }
339 #endif
340 
341 public:
343 };
344 
345 // manifold traits
346 
347 template <typename Calibration>
348 struct traits<PinholeCamera<Calibration> >
349  : public internal::Manifold<PinholeCamera<Calibration> > {};
350 
351 template <typename Calibration>
352 struct traits<const PinholeCamera<Calibration> >
353  : public internal::Manifold<PinholeCamera<Calibration> > {};
354 
355 // range traits, used in RangeFactor
356 template <typename Calibration, typename T>
357 struct Range<PinholeCamera<Calibration>, T> : HasRange<PinholeCamera<Calibration>, T, double> {};
358 
359 } // \ gtsam
gtsam::PinholeCamera::PinholeCamera
PinholeCamera()
Definition: PinholeCamera.h:62
gtsam::PinholeBaseK
Definition: PinholePose.h:33
gtsam::PinholeCamera::VectorK6
Eigen::Matrix< double, dimension, 1 > VectorK6
Definition: PinholeCamera.h:196
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::PinholeBase::Dpoint
static Matrix23 Dpoint(const Point2 &pn, double d, const Matrix3 &Rt)
Definition: CalibratedCamera.cpp:37
gtsam::PinholeBase::LookatPose
static Pose3 LookatPose(const Point3 &eye, const Point3 &target, const Point3 &upVector)
Definition: CalibratedCamera.cpp:58
gtsam::PinholeCamera::MeasurementVector
Point2Vector MeasurementVector
Definition: PinholeCamera.h:42
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
gtsam::PinholeCamera::Level
static PinholeCamera Level(const Calibration &K, const Pose2 &pose2, double height)
Definition: PinholeCamera.h:86
gtsam::PinholeCamera::_project2
Point2 _project2(const POINT &pw, OptionalJacobian< 2, dimension > Dcamera, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) const
Definition: PinholeCamera.h:230
gtsam::PinholeCamera::Matrix2K
Eigen::Matrix< double, 2, DimK > Matrix2K
Definition: PinholeCamera.h:224
gtsam::PinholeCamera::print
void print(const std::string &s="PinholeCamera") const override
print
Definition: PinholeCamera.h:151
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
gtsam::internal::Manifold
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
gtsam::PinholeCamera::PinholeCamera
PinholeCamera(const Vector &v)
Init from vector, can be 6D (default calibration) or dim.
Definition: PinholeCamera.h:129
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::PinholeCamera::range
double range(const PinholeCamera< CalibrationB > &camera, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6+CalibrationB::dimension > Dother={}) const
Definition: PinholeCamera.h:290
gtsam::PinholeCamera::project2
Point2 project2(const Unit3 &pw, OptionalJacobian< 2, dimension > Dcamera={}, OptionalJacobian< 2, 2 > Dpoint={}) const
project a point at infinity from world coordinates into the image
Definition: PinholeCamera.h:251
gtsam::Pose3::matrix
Matrix4 matrix() const
Definition: Pose3.cpp:323
gtsam::PinholeCamera::Lookat
static PinholeCamera Lookat(const Point3 &eye, const Point3 &target, const Point3 &upVector, const Calibration &K=Calibration())
Definition: PinholeCamera.h:105
gtsam::PinholeBaseK< Calibration >::project
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
gtsam::Pose3::range
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
Definition: Pose3.cpp:399
gtsam::PinholeCamera::calibration
const Calibration & calibration() const override
return calibration
Definition: PinholeCamera.h:178
gtsam::PinholeCamera::Identity
static PinholeCamera Identity()
for Canonical
Definition: PinholeCamera.h:216
gtsam::PinholeBase::equals
bool equals(const PinholeBase &camera, double tol=1e-9) const
assert equality up to a tolerance
Definition: CalibratedCamera.cpp:69
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::PinholeCamera::Base
PinholeBaseK< Calibration > Base
base class has 3D pose as private member
Definition: PinholeCamera.h:46
gtsam::PinholeCamera::PinholeCamera
PinholeCamera(const Pose3 &pose, const Calibration &K)
Definition: PinholeCamera.h:71
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Pose3::inverse
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:49
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::PinholeCamera::PinholeCamera
PinholeCamera(const Pose3 &pose)
Definition: PinholeCamera.h:66
gtsam::PinholeCamera::pose
const Pose3 & pose() const
return pose
Definition: PinholeCamera.h:164
gtsam::PinholeCamera::equals
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
Definition: PinholeCamera.h:145
gtsam::PinholeCamera::dim
size_t dim() const
Definition: PinholeCamera.h:187
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::PinholeCamera::~PinholeCamera
~PinholeCamera() override
Definition: PinholeCamera.h:160
gtsam::Range
Definition: BearingRange.h:41
head
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
Definition: BlockMethods.h:1208
gtsam::PinholeCamera::Create
static PinholeCamera Create(const Pose3 &pose, const Calibration &K, OptionalJacobian< dimension, 6 > H1={}, OptionalJacobian< dimension, DimK > H2={})
Definition: PinholeCamera.h:111
gtsam::LieGroup::localCoordinates
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
gtsam::CalibratedCamera
Definition: CalibratedCamera.h:251
gtsam::PinholeCamera::defaultErrorWhenTriangulatingBehindCamera
Vector defaultErrorWhenTriangulatingBehindCamera() const
for Nonlinear Triangulation
Definition: PinholeCamera.h:323
gtsam::PinholeCamera::range
double range(const Pose3 &pose, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
Definition: PinholeCamera.h:275
gtsam::PinholeCamera::range
double range(const CalibratedCamera &camera, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
Definition: PinholeCamera.h:311
gtsam::PinholeCamera::Level
static PinholeCamera Level(const Pose2 &pose2, double height)
PinholeCamera::level with default calibration.
Definition: PinholeCamera.h:92
gtsam::PinholeCamera::range
double range(const Point3 &point, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
Definition: PinholeCamera.h:261
gtsam::PinholeCamera::getPose
const Pose3 & getPose(OptionalJacobian< 6, dimension > H) const
return pose, with derivative
Definition: PinholeCamera.h:169
gtsam
traits
Definition: chartTesting.h:28
gtsam::traits
Definition: Group.h:36
K
#define K
Definition: igam.h:8
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::PinholeCamera::PinholeCamera
PinholeCamera(const Vector &v, const Vector &K)
Init from Vector and calibration.
Definition: PinholeCamera.h:136
gtsam::PinholeCamera::Dim
static size_t Dim()
Definition: PinholeCamera.h:192
gtsam::HasRange
Definition: BearingRange.h:197
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::Point2Vector
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:49
gtsam::PinholeCamera::project2
Point2 project2(const Point3 &pw, OptionalJacobian< 2, dimension > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
project a 3D point from world coordinates into the image
Definition: PinholeCamera.h:245
gtsam::PinholeCamera::DimK
static const int DimK
Definition: PinholeCamera.h:50
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::PinholeCamera::localCoordinates
VectorK6 localCoordinates(const PinholeCamera &T2) const
return canonical coordinate
Definition: PinholeCamera.h:208
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::PinholeCamera::K_
Calibration K_
Calibration, part of class now.
Definition: PinholeCamera.h:47
gtsam::FixedDimension
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
BearingRange.h
Bearing-Range product.
camera
static const CalibratedCamera camera(kDefaultPose)
gtsam::PinholeBase::Dpose
static Matrix26 Dpose(const Point2 &pn, double d)
Definition: CalibratedCamera.cpp:27
gtsam::PinholeCamera::retract
PinholeCamera retract(const Vector &d) const
move a cameras according to d
Definition: PinholeCamera.h:199
gtsam::PinholeCamera::dimension
@ dimension
Definition: PinholeCamera.h:55
gtsam::PinholeBase::LevelPose
static Pose3 LevelPose(const Pose2 &pose2, double height)
Definition: CalibratedCamera.cpp:49
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
PinholePose.h
Pinhole camera with known calibration.
gtsam::PinholeCamera::Measurement
Point2 Measurement
Definition: PinholeCamera.h:41
gtsam::PinholeCamera::cameraProjectionMatrix
Matrix34 cameraProjectionMatrix() const
for Linear Triangulation
Definition: PinholeCamera.h:318
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:02:47