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 {
55  dimension = 6 + DimK
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,
112  OptionalJacobian<dimension, 6> H1 = boost::none, //
113  OptionalJacobian<dimension, DimK> H2 = boost::none) {
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 
208  VectorK6 localCoordinates(const PinholeCamera& T2) const {
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  Matrix26 Dpose;
235  Point2 pi = Base::project(pw, Dcamera ? &Dpose : 0, Dpoint,
236  Dcamera ? &Dcal : 0);
237  if (Dcamera)
238  *Dcamera << Dpose, Dcal;
239  return pi;
240  }
241 
244  boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const {
245  return _project2(pw, Dcamera, Dpoint);
246  }
247 
250  boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const {
251  return _project2(pw, Dcamera, Dpoint);
252  }
253 
260  boost::none, OptionalJacobian<1, 3> Dpoint = boost::none) 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  boost::none, OptionalJacobian<1, 6> Dpose = boost::none) 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 = boost::none,
290  OptionalJacobian<1, 6 + CalibrationB::dimension> Dother = boost::none) const {
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 = boost::none,
311  OptionalJacobian<1, 6> Dother = boost::none) const {
312  return range(camera.pose(), Dcamera, Dother);
313  }
314 
315 private:
316 
318  friend class boost::serialization::access;
319  template<class Archive>
320  void serialize(Archive & ar, const unsigned int /*version*/) {
321  ar
322  & boost::serialization::make_nvp("PinholeBaseK",
323  boost::serialization::base_object<Base>(*this));
324  ar & BOOST_SERIALIZATION_NVP(K_);
325  }
326 
327 public:
329 };
330 
331 // manifold traits
332 
333 template <typename Calibration>
334 struct traits<PinholeCamera<Calibration> >
335  : public internal::Manifold<PinholeCamera<Calibration> > {};
336 
337 template <typename Calibration>
338 struct traits<const PinholeCamera<Calibration> >
339  : public internal::Manifold<PinholeCamera<Calibration> > {};
340 
341 // range traits, used in RangeFactor
342 template <typename Calibration, typename T>
343 struct Range<PinholeCamera<Calibration>, T> : HasRange<PinholeCamera<Calibration>, T, double> {};
344 
345 } // \ gtsam
Pinhole camera with known calibration.
static PinholeCamera Level(const Calibration &K, const Pose2 &pose2, double height)
Definition: PinholeCamera.h:86
Point2 _project2(const POINT &pw, OptionalJacobian< 2, dimension > Dcamera, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) const
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Point2 project2(const Point3 &pw, OptionalJacobian< 2, dimension > Dcamera=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
project a 3D point from world coordinates into the image
static PinholeCamera Lookat(const Point3 &eye, const Point3 &target, const Point3 &upVector, const Calibration &K=Calibration())
const Pose3 & pose() const
return pose
virtual void print(const std::string &s="PinholeBase") const
print
PinholeBaseK< Calibration > Base
base class has 3D pose as private member
Definition: PinholeCamera.h:46
Eigen::Matrix< double, dimension, 1 > VectorK6
PinholeCamera(const Pose3 &pose, const Calibration &K)
Definition: PinholeCamera.h:71
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
static Pose3 LookatPose(const Point3 &eye, const Point3 &target, const Point3 &upVector)
static Pose3 LevelPose(const Pose2 &pose2, double height)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
PinholeCamera retract(const Vector &d) const
move a cameras according to d
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 Calibration & calibration() const override
return calibration
const Pose3 & pose() const
return pose, constant version
double range(const Point3 &point, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Point3 point(10, 0,-5)
Eigen::Matrix< double, 2, DimK > Matrix2K
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
double range(const CalibratedCamera &camera, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
double range(const PinholeCamera< CalibrationB > &camera, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6+CalibrationB::dimension > Dother=boost::none) const
PinholeCamera(const Vector &v)
Init from vector, can be 6D (default calibration) or dim.
static PinholeCamera identity()
for Canonical
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:42
bool equals(const PinholeBase &camera, double tol=1e-9) const
assert equality up to a tolerance
PinholeCamera(const Pose3 &pose)
Definition: PinholeCamera.h:66
~PinholeCamera() override
VectorK6 localCoordinates(const PinholeCamera &T2) const
return canonical coordinate
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:334
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
static Matrix23 Dpoint(const Point2 &pn, double d, const Matrix3 &Rt)
static Matrix26 Dpose(const Point2 &pn, double d)
traits
Definition: chartTesting.h:28
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
static PinholeCamera Create(const Pose3 &pose, const Calibration &K, OptionalJacobian< dimension, 6 > H1=boost::none, OptionalJacobian< dimension, DimK > H2=boost::none)
double range(const Pose3 &pose, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
static size_t Dim()
EIGEN_DEVICE_FUNC SegmentReturnType head(Index n)
This is the const version of head(Index).
Definition: BlockMethods.h:919
Bearing-Range product.
void serialize(Archive &ar, const unsigned int)
Calibration K_
Calibration, part of class now.
Definition: PinholeCamera.h:47
static const int DimK
Definition: PinholeCamera.h:50
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
Point2Vector MeasurementVector
Definition: PinholeCamera.h:42
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
size_t dim() const
const G double tol
Definition: Group.h:83
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
Point2 project2(const Unit3 &pw, OptionalJacobian< 2, dimension > Dcamera=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
project a point at infinity from world coordinates into the image
The matrix class, also used for vectors and row-vectors.
static const CalibratedCamera camera(kDefaultPose)
static PinholeCamera Level(const Pose2 &pose2, double height)
PinholeCamera::level with default calibration.
Definition: PinholeCamera.h:92
PinholeCamera(const Vector &v, const Vector &K)
Init from Vector and calibration.
const Pose3 & getPose(OptionalJacobian< 6, dimension > H) const
return pose, with derivative
void print(const std::string &s="PinholeCamera") const override
print
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:135


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:26