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  inline constexpr static auto dimension = 6 + DimK;
55 
58 
61  }
62 
64  explicit PinholeCamera(const Pose3& pose) :
65  Base(pose) {
66  }
67 
69  PinholeCamera(const Pose3& pose, const Calibration& K) :
70  Base(pose), K_(K) {
71  }
72 
76 
84  static PinholeCamera Level(const Calibration &K, const Pose2& pose2,
85  double height) {
86  return PinholeCamera(Base::LevelPose(pose2, height), K);
87  }
88 
90  static PinholeCamera Level(const Pose2& pose2, double height) {
91  return PinholeCamera::Level(Calibration(), pose2, height);
92  }
93 
103  static PinholeCamera Lookat(const Point3& eye, const Point3& target,
104  const Point3& upVector, const Calibration& K = Calibration()) {
105  return PinholeCamera(Base::LookatPose(eye, target, upVector), K);
106  }
107 
108  // Create PinholeCamera, with derivatives
109  static PinholeCamera Create(const Pose3& pose, const Calibration &K,
112  typedef Eigen::Matrix<double, DimK, 6> MatrixK6;
113  if (H1)
114  *H1 << I_6x6, MatrixK6::Zero();
115  typedef Eigen::Matrix<double, 6, DimK> Matrix6K;
116  typedef Eigen::Matrix<double, DimK, DimK> MatrixK;
117  if (H2)
118  *H2 << Matrix6K::Zero(), MatrixK::Identity();
119  return PinholeCamera(pose,K);
120  }
121 
125 
127  explicit PinholeCamera(const Vector &v) :
128  Base(v.head<6>()) {
129  if (v.size() > 6)
130  K_ = Calibration(v.tail<DimK>());
131  }
132 
134  PinholeCamera(const Vector &v, const Vector &K) :
135  Base(v), K_(K) {
136  }
137 
141 
143  bool equals(const Base &camera, double tol = 1e-9) const {
144  const PinholeCamera* e = dynamic_cast<const PinholeCamera*>(&camera);
145  return Base::equals(camera, tol) && K_.equals(e->calibration(), tol);
146  }
147 
149  void print(const std::string& s = "PinholeCamera") const override {
150  Base::print(s);
151  K_.print(s + ".calibration");
152  }
153 
157 
158  ~PinholeCamera() override {
159  }
160 
162  const Pose3& pose() const {
163  return Base::pose();
164  }
165 
168  if (H) {
169  H->setZero();
170  H->template block<6, 6>(0, 0) = I_6x6;
171  }
172  return Base::pose();
173  }
174 
176  const Calibration& calibration() const override {
177  return K_;
178  }
179 
183 
185  size_t dim() const {
186  return dimension;
187  }
188 
190  static size_t Dim() {
191  return dimension;
192  }
193 
195 
197  PinholeCamera retract(const Vector& d) const {
198  if ((size_t) d.size() == 6)
199  return PinholeCamera(this->pose().retract(d), calibration());
200  else
201  return PinholeCamera(this->pose().retract(d.head<6>()),
202  calibration().retract(d.tail(calibration().dim())));
203  }
204 
207  VectorK6 d;
208  d.template head<6>() = this->pose().localCoordinates(T2.pose());
209  d.template tail<DimK>() = calibration().localCoordinates(T2.calibration());
210  return d;
211  }
212 
215  return PinholeCamera(); // assumes that the default constructor is valid
216  }
217 
221 
223 
227  template<class POINT>
230  // We just call 3-derivative version in Base
231  if (Dcamera){
232  Matrix26 Dpose;
234  const Point2 pi = Base::project(pw, Dpose, Dpoint, Dcal);
235  *Dcamera << Dpose, Dcal;
236  return pi;
237  } else {
238  return Base::project(pw, {}, Dpoint, {});
239  }
240  }
241 
244  {}, OptionalJacobian<2, 3> Dpoint = {}) const {
245  return _project2(pw, Dcamera, Dpoint);
246  }
247 
250  {}, OptionalJacobian<2, 2> Dpoint = {}) const {
251  return _project2(pw, Dcamera, Dpoint);
252  }
253 
260  {}, OptionalJacobian<1, 3> Dpoint = {}) const {
261  Matrix16 Dpose_;
262  double result = this->pose().range(point, Dcamera ? &Dpose_ : 0, Dpoint);
263  if (Dcamera)
264  *Dcamera << Dpose_, Eigen::Matrix<double, 1, DimK>::Zero();
265  return result;
266  }
267 
274  {}, OptionalJacobian<1, 6> Dpose = {}) const {
275  Matrix16 Dpose_;
276  double result = this->pose().range(pose, Dcamera ? &Dpose_ : 0, Dpose);
277  if (Dcamera)
278  *Dcamera << Dpose_, Eigen::Matrix<double, 1, DimK>::Zero();
279  return result;
280  }
281 
287  template<class CalibrationB>
289  OptionalJacobian<1, dimension> Dcamera = {},
291  Matrix16 Dcamera_, Dother_;
292  double result = this->pose().range(camera.pose(), Dcamera ? &Dcamera_ : 0,
293  Dother ? &Dother_ : 0);
294  if (Dcamera) {
295  *Dcamera << Dcamera_, Eigen::Matrix<double, 1, DimK>::Zero();
296  }
297  if (Dother) {
298  Dother->setZero();
299  Dother->template block<1, 6>(0, 0) = Dother_;
300  }
301  return result;
302  }
303 
310  OptionalJacobian<1, dimension> Dcamera = {},
311  OptionalJacobian<1, 6> Dother = {}) const {
312  return range(camera.pose(), Dcamera, Dother);
313  }
314 
316  Matrix34 cameraProjectionMatrix() const {
317  return K_.K() * PinholeBase::pose().inverse().matrix().block(0, 0, 3, 4);
318  }
319 
322  return Eigen::Matrix<double,traits<Point2>::dimension,1>::Constant(2.0 * K_.fx());
323  }
324 
325 private:
326 
327 #if GTSAM_ENABLE_BOOST_SERIALIZATION
328 
329  friend class boost::serialization::access;
330  template<class Archive>
331  void serialize(Archive & ar, const unsigned int /*version*/) {
332  ar
333  & boost::serialization::make_nvp("PinholeBaseK",
334  boost::serialization::base_object<Base>(*this));
335  ar & BOOST_SERIALIZATION_NVP(K_);
336  }
337 #endif
338 
339 public:
341 };
342 
343 // manifold traits
344 
345 template <typename Calibration>
346 struct traits<PinholeCamera<Calibration> >
347  : public internal::Manifold<PinholeCamera<Calibration> > {};
348 
349 template <typename Calibration>
350 struct traits<const PinholeCamera<Calibration> >
351  : public internal::Manifold<PinholeCamera<Calibration> > {};
352 
353 // range traits, used in RangeFactor
354 template <typename Calibration, typename T>
355 struct Range<PinholeCamera<Calibration>, T> : HasRange<PinholeCamera<Calibration>, T, double> {};
356 
357 } // \ gtsam
gtsam::PinholeCamera::PinholeCamera
PinholeCamera()
Definition: PinholeCamera.h:60
gtsam::PinholeBaseK
Definition: PinholePose.h:33
gtsam::PinholeCamera::VectorK6
Eigen::Matrix< double, dimension, 1 > VectorK6
Definition: PinholeCamera.h:194
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:84
gtsam::PinholeCamera::_project2
Point2 _project2(const POINT &pw, OptionalJacobian< 2, dimension > Dcamera, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) const
Definition: PinholeCamera.h:228
gtsam::PinholeCamera::Matrix2K
Eigen::Matrix< double, 2, DimK > Matrix2K
Definition: PinholeCamera.h:222
gtsam::PinholeCamera::print
void print(const std::string &s="PinholeCamera") const override
print
Definition: PinholeCamera.h:149
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:127
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
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:288
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:249
gtsam::Pose3::matrix
Matrix4 matrix() const
Definition: Pose3.cpp:338
gtsam::PinholeCamera::Lookat
static PinholeCamera Lookat(const Point3 &eye, const Point3 &target, const Point3 &upVector, const Calibration &K=Calibration())
Definition: PinholeCamera.h:103
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:414
gtsam::PinholeCamera::calibration
const Calibration & calibration() const override
return calibration
Definition: PinholeCamera.h:176
gtsam::PinholeCamera::Identity
static PinholeCamera Identity()
for Canonical
Definition: PinholeCamera.h:214
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::dimension
constexpr static auto dimension
Dimension depends on calibration.
Definition: PinholeCamera.h:54
gtsam::PinholeCamera::PinholeCamera
PinholeCamera(const Pose3 &pose, const Calibration &K)
Definition: PinholeCamera.h:69
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Pose3::inverse
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:61
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::PinholeCamera::PinholeCamera
PinholeCamera(const Pose3 &pose)
Definition: PinholeCamera.h:64
gtsam::PinholeCamera::pose
const Pose3 & pose() const
return pose
Definition: PinholeCamera.h:162
gtsam::PinholeCamera::equals
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
Definition: PinholeCamera.h:143
gtsam::PinholeCamera::dim
size_t dim() const
Definition: PinholeCamera.h:185
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:158
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:109
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:321
gtsam::PinholeCamera::range
double range(const Pose3 &pose, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
Definition: PinholeCamera.h:273
gtsam::PinholeCamera::range
double range(const CalibratedCamera &camera, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
Definition: PinholeCamera.h:309
gtsam::PinholeCamera::Level
static PinholeCamera Level(const Pose2 &pose2, double height)
PinholeCamera::level with default calibration.
Definition: PinholeCamera.h:90
gtsam::PinholeCamera::range
double range(const Point3 &point, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
Definition: PinholeCamera.h:259
gtsam::PinholeCamera::getPose
const Pose3 & getPose(OptionalJacobian< 6, dimension > H) const
return pose, with derivative
Definition: PinholeCamera.h:167
gtsam
traits
Definition: SFMdata.h:40
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:134
gtsam::PinholeCamera::Dim
static size_t Dim()
Definition: PinholeCamera.h:190
gtsam::HasRange
Definition: BearingRange.h:195
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:243
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:206
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:197
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:316
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:03:29