PinholePose.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 
20 #pragma once
21 
23 #include <gtsam/geometry/Point2.h>
24 #include <boost/make_shared.hpp>
25 
26 namespace gtsam {
27 
33 template<typename CALIBRATION>
34 class PinholeBaseK: public PinholeBase {
35 
36 private:
37 
38  GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION);
39 
40  // Get dimensions of calibration type at compile time
42 
43 public:
44 
45  typedef CALIBRATION CalibrationType;
46 
49 
52  }
53 
55  explicit PinholeBaseK(const Pose3& pose) :
56  PinholeBase(pose) {
57  }
58 
62 
63  explicit PinholeBaseK(const Vector &v) :
64  PinholeBase(v) {
65  }
66 
70 
71  virtual ~PinholeBaseK() {
72  }
73 
75  virtual const CALIBRATION& calibration() const = 0;
76 
80 
82  std::pair<Point2, bool> projectSafe(const Point3& pw) const {
83  std::pair<Point2, bool> pn = PinholeBase::projectSafe(pw);
84  pn.first = calibration().uncalibrate(pn.first);
85  return pn;
86  }
87 
88 
95  template <class POINT>
98  OptionalJacobian<2, DimK> Dcal) const {
99 
100  // project to normalized coordinates
101  const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint);
102 
103  // uncalibrate to pixel coordinates
104  Matrix2 Dpi_pn;
105  const Point2 pi = calibration().uncalibrate(pn, Dcal,
106  Dpose || Dpoint ? &Dpi_pn : 0);
107 
108  // If needed, apply chain rule
109  if (Dpose)
110  *Dpose = Dpi_pn * *Dpose;
111  if (Dpoint)
112  *Dpoint = Dpi_pn * *Dpoint;
113 
114  return pi;
115  }
116 
119  OptionalJacobian<2, 3> Dpoint = boost::none,
120  OptionalJacobian<2, DimK> Dcal = boost::none) const {
121  return _project(pw, Dpose, Dpoint, Dcal);
122  }
123 
125  Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose = boost::none,
126  OptionalJacobian<2, 2> Dpoint = boost::none,
127  OptionalJacobian<2, DimK> Dcal = boost::none) const {
128  return _project(pw, Dpose, Dpoint, Dcal);
129  }
130 
132  Point3 backproject(const Point2& p, double depth,
133  OptionalJacobian<3, 6> Dresult_dpose = boost::none,
134  OptionalJacobian<3, 2> Dresult_dp = boost::none,
135  OptionalJacobian<3, 1> Dresult_ddepth = boost::none,
136  OptionalJacobian<3, DimK> Dresult_dcal = boost::none) const {
137  typedef Eigen::Matrix<double, 2, DimK> Matrix2K;
138  Matrix2K Dpn_dcal;
139  Matrix22 Dpn_dp;
140  const Point2 pn = calibration().calibrate(p, Dresult_dcal ? &Dpn_dcal : 0,
141  Dresult_dp ? &Dpn_dp : 0);
142  Matrix32 Dpoint_dpn;
143  Matrix31 Dpoint_ddepth;
144  const Point3 point = BackprojectFromCamera(pn, depth,
145  (Dresult_dp || Dresult_dcal) ? &Dpoint_dpn : 0,
146  Dresult_ddepth ? &Dpoint_ddepth : 0);
147  Matrix33 Dresult_dpoint;
148  const Point3 result = pose().transformFrom(point, Dresult_dpose,
149  (Dresult_ddepth ||
150  Dresult_dp ||
151  Dresult_dcal) ? &Dresult_dpoint : 0);
152  if (Dresult_dcal)
153  *Dresult_dcal = Dresult_dpoint * Dpoint_dpn * Dpn_dcal; // (3x3)*(3x2)*(2xDimK)
154  if (Dresult_dp)
155  *Dresult_dp = Dresult_dpoint * Dpoint_dpn * Dpn_dp; // (3x3)*(3x2)*(2x2)
156  if (Dresult_ddepth)
157  *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth; // (3x3)*(3x1)
158 
159  return result;
160  }
161 
162 
165  const Point2 pn = calibration().calibrate(p);
166  const Unit3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1
167  return pose().rotation().rotate(pc);
168  }
169 
175  double range(const Point3& point,
176  OptionalJacobian<1, 6> Dcamera = boost::none,
177  OptionalJacobian<1, 3> Dpoint = boost::none) const {
178  return pose().range(point, Dcamera, Dpoint);
179  }
180 
186  double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = boost::none,
187  OptionalJacobian<1, 6> Dpose = boost::none) const {
188  return this->pose().range(pose, Dcamera, Dpose);
189  }
190 
197  boost::none, OptionalJacobian<1, 6> Dother = boost::none) const {
198  return pose().range(camera.pose(), Dcamera, Dother);
199  }
200 
206  template<class CalibrationB>
208  OptionalJacobian<1, 6> Dcamera = boost::none,
209  OptionalJacobian<1, 6> Dother = boost::none) const {
210  return pose().range(camera.pose(), Dcamera, Dother);
211  }
212 
213 private:
214 
216  friend class boost::serialization::access;
217  template<class Archive>
218  void serialize(Archive & ar, const unsigned int /*version*/) {
219  ar
220  & boost::serialization::make_nvp("PinholeBase",
221  boost::serialization::base_object<PinholeBase>(*this));
222  }
223 
224 public:
226 };
227 // end of class PinholeBaseK
228 
236 template<typename CALIBRATION>
237 class PinholePose: public PinholeBaseK<CALIBRATION> {
238 
239 private:
240 
242  boost::shared_ptr<CALIBRATION> K_;
243 
244 public:
245 
246  enum {
247  dimension = 6
248  };
249 
252 
255  }
256 
258  explicit PinholePose(const Pose3& pose) :
259  Base(pose), K_(new CALIBRATION()) {
260  }
261 
263  PinholePose(const Pose3& pose, const boost::shared_ptr<CALIBRATION>& K) :
264  Base(pose), K_(K) {
265  }
266 
270 
278  static PinholePose Level(const boost::shared_ptr<CALIBRATION>& K,
279  const Pose2& pose2, double height) {
280  return PinholePose(Base::LevelPose(pose2, height), K);
281  }
282 
284  static PinholePose Level(const Pose2& pose2, double height) {
285  return PinholePose::Level(boost::make_shared<CALIBRATION>(), pose2, height);
286  }
287 
297  static PinholePose Lookat(const Point3& eye, const Point3& target,
298  const Point3& upVector, const boost::shared_ptr<CALIBRATION>& K =
299  boost::make_shared<CALIBRATION>()) {
300  return PinholePose(Base::LookatPose(eye, target, upVector), K);
301  }
302 
306 
308  explicit PinholePose(const Vector &v) :
309  Base(v), K_(new CALIBRATION()) {
310  }
311 
313  PinholePose(const Vector &v, const Vector &K) :
314  Base(v), K_(new CALIBRATION(K)) {
315  }
316 
317  // Init from Pose3 and calibration
318  PinholePose(const Pose3 &pose, const Vector &K) :
319  Base(pose), K_(new CALIBRATION(K)) {
320  }
321 
325 
327  bool equals(const Base &camera, double tol = 1e-9) const {
328  const PinholePose* e = dynamic_cast<const PinholePose*>(&camera);
329  return Base::equals(camera, tol) && K_->equals(e->calibration(), tol);
330  }
331 
333  friend std::ostream& operator<<(std::ostream &os, const PinholePose& camera) {
334  os << "{R: " << camera.pose().rotation().rpy().transpose();
335  os << ", t: " << camera.pose().translation().transpose();
336  if (!camera.K_) os << ", K: none";
337  else os << ", K: " << *camera.K_;
338  os << "}";
339  return os;
340  }
341 
343  void print(const std::string& s = "PinholePose") const override {
344  Base::print(s);
345  if (!K_)
346  std::cout << "s No calibration given" << std::endl;
347  else
348  K_->print(s + ".calibration");
349  }
350 
354 
355  ~PinholePose() override {
356  }
357 
359  const boost::shared_ptr<CALIBRATION>& sharedCalibration() const {
360  return K_;
361  }
362 
364  const CALIBRATION& calibration() const override {
365  return *K_;
366  }
367 
374  OptionalJacobian<2, 3> Dpoint = boost::none) const {
375  return Base::project(pw, Dpose, Dpoint);
376  }
377 
380  OptionalJacobian<2, 2> Dpoint = boost::none) const {
381  return Base::project(pw, Dpose, Dpoint);
382  }
383 
387 
389  size_t dim() const {
390  return 6;
391  }
392 
394  static size_t Dim() {
395  return 6;
396  }
397 
399  PinholePose retract(const Vector6& d) const {
400  return PinholePose(Base::pose().retract(d), K_);
401  }
402 
404  Vector6 localCoordinates(const PinholePose& p) const {
405  return Base::pose().localCoordinates(p.Base::pose());
406  }
407 
410  return PinholePose(); // assumes that the default constructor is valid
411  }
412 
414 
415 private:
416 
418  friend class boost::serialization::access;
419  template<class Archive>
420  void serialize(Archive & ar, const unsigned int /*version*/) {
421  ar
422  & boost::serialization::make_nvp("PinholeBaseK",
423  boost::serialization::base_object<Base>(*this));
424  ar & BOOST_SERIALIZATION_NVP(K_);
425  }
426 
427 public:
429 };
430 // end of class PinholePose
431 
432 template<typename CALIBRATION>
433 struct traits<PinholePose<CALIBRATION> > : public internal::Manifold<
434  PinholePose<CALIBRATION> > {
435 };
436 
437 template<typename CALIBRATION>
438 struct traits<const PinholePose<CALIBRATION> > : public internal::Manifold<
439  PinholePose<CALIBRATION> > {
440 };
441 
442 } // \ gtsam
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Definition: PinholePose.h:175
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
void serialize(Archive &ar, const unsigned int)
Definition: PinholePose.h:218
const CALIBRATION & calibration() const override
return calibration
Definition: PinholePose.h:364
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
std::pair< Point2, bool > projectSafe(const Point3 &pw) const
Project a point into the image and check depth.
Definition: PinholePose.h:82
size_t dim() const
Definition: PinholePose.h:389
Point2 project2(const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
project2 version for point at infinity
Definition: PinholePose.h:379
Point3 backproject(const Point2 &p, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none, OptionalJacobian< 3, DimK > Dresult_dcal=boost::none) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition: PinholePose.h:132
int RealScalar int RealScalar int RealScalar * pc
PinholePose(const Vector &v, const Vector &K)
Init from Vector and calibration.
Definition: PinholePose.h:313
Point2 project2(const Point3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
static PinholePose Level(const Pose2 &pose2, double height)
PinholePose::level with default calibration.
Definition: PinholePose.h:284
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
Point2 _project(const POINT &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint, OptionalJacobian< 2, DimK > Dcal) const
Definition: PinholePose.h:96
Point2 project2(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
Definition: PinholePose.h:373
PinholePose(const Pose3 &pose)
Definition: PinholePose.h:258
virtual const CALIBRATION & calibration() const =0
return calibration
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
virtual ~PinholeBaseK()
Definition: PinholePose.h:71
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: Rot3M.cpp:149
static const int DimK
Definition: PinholePose.h:41
const Pose3 & pose() const
return pose, constant version
void print(const std::string &s="PinholePose") const override
print
Definition: PinholePose.h:343
static PinholePose Lookat(const Point3 &eye, const Point3 &target, const Point3 &upVector, const boost::shared_ptr< CALIBRATION > &K=boost::make_shared< CALIBRATION >())
Definition: PinholePose.h:297
static PinholePose Level(const boost::shared_ptr< CALIBRATION > &K, const Pose2 &pose2, double height)
Definition: PinholePose.h:278
Point3 point(10, 0,-5)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:298
GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION)
PinholePose(const Pose3 &pose, const boost::shared_ptr< CALIBRATION > &K)
Definition: PinholePose.h:263
static size_t Dim()
Definition: PinholePose.h:394
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:334
void serialize(Archive &ar, const unsigned int)
Definition: PinholePose.h:420
static Point3 BackprojectFromCamera(const Point2 &p, const double depth, OptionalJacobian< 3, 2 > Dpoint=boost::none, OptionalJacobian< 3, 1 > Ddepth=boost::none)
backproject a 2-dimensional point to a 3-dimensional point at given depth
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
static Matrix23 Dpoint(const Point2 &pn, double d, const Matrix3 &Rt)
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
Definition: PinholePose.h:196
PinholeBaseK(const Pose3 &pose)
Definition: PinholePose.h:55
static Matrix26 Dpose(const Point2 &pn, double d)
Vector6 localCoordinates(const PinholePose &p) const
return canonical coordinate
Definition: PinholePose.h:404
PinholePose(const Vector &v)
Init from 6D vector.
Definition: PinholePose.h:308
Calibrated camera for which only pose is unknown.
PinholeBaseK< CALIBRATION > Base
base class has 3D pose as private member
Definition: PinholePose.h:241
traits
Definition: chartTesting.h:28
static PinholePose identity()
for Canonical
Definition: PinholePose.h:409
std::pair< Point2, bool > projectSafe(const Point3 &pw) const
Project a point into the image and check depth.
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
Definition: PinholePose.h:186
ofstream os("timeSchurFactors.csv")
const boost::shared_ptr< CALIBRATION > & sharedCalibration() const
return shared pointer to calibration
Definition: PinholePose.h:359
friend std::ostream & operator<<(std::ostream &os, const PinholePose &camera)
stream operator
Definition: PinholePose.h:333
boost::shared_ptr< CALIBRATION > K_
shared pointer to fixed calibration
Definition: PinholePose.h:242
PinholePose(const Pose3 &pose, const Vector &K)
Definition: PinholePose.h:318
float * p
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
Point2 project(const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a point at infinity from world coordinates into the image
Definition: PinholePose.h:125
~PinholePose() override
Definition: PinholePose.h:355
PinholePose retract(const Vector6 &d) const
move a cameras according to d
Definition: PinholePose.h:399
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
Vector3 rpy(OptionalJacobian< 3, 3 > H=boost::none) const
Definition: Rot3.cpp:192
const G double tol
Definition: Group.h:83
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
The matrix class, also used for vectors and row-vectors.
Unit3 backprojectPointAtInfinity(const Point2 &p) const
backproject a 2-dimensional point to a 3-dimensional point at infinity
Definition: PinholePose.h:164
static const CalibratedCamera camera(kDefaultPose)
PinholeBaseK(const Vector &v)
Definition: PinholePose.h:63
2D Point
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
Definition: PinholePose.h:327
CALIBRATION CalibrationType
Definition: PinholePose.h:45
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
double range(const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
Definition: PinholePose.h:207


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