gtsam 4.1.1
gtsam
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
24#include <gtsam/base/concepts.h>
25#include <gtsam/base/Manifold.h>
27#include <gtsam/dllexport.h>
28#include <boost/serialization/nvp.hpp>
29
30namespace gtsam {
31
32class GTSAM_EXPORT CheiralityException: public ThreadsafeException<CheiralityException> {
33public:
35 : CheiralityException(std::numeric_limits<Key>::max()) {}
36
38 : ThreadsafeException<CheiralityException>("CheiralityException"),
39 j_(j) {}
40
41 Key nearbyVariable() const {return j_;}
42
43private:
44 Key j_;
45};
46
52class GTSAM_EXPORT PinholeBase {
53
54public:
55
57 typedef Rot3 Rotation;
58 typedef Point3 Translation;
59
65 typedef Point2Vector MeasurementVector;
66
67private:
68
69 Pose3 pose_;
70
71protected:
72
75
81 static Matrix26 Dpose(const Point2& pn, double d);
82
89 static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt);
90
92
93public:
94
97
105 static Pose3 LevelPose(const Pose2& pose2, double height);
106
115 static Pose3 LookatPose(const Point3& eye, const Point3& target,
116 const Point3& upVector);
117
121
124
126 explicit PinholeBase(const Pose3& pose) : pose_(pose) {}
127
131
132 explicit PinholeBase(const Vector& v) : pose_(Pose3::Expmap(v)) {}
133
135 virtual ~PinholeBase() = default;
136
140
142 bool equals(const PinholeBase &camera, double tol = 1e-9) const;
143
145 virtual void print(const std::string& s = "PinholeBase") const;
146
150
152 const Pose3& pose() const {
153 return pose_;
154 }
155
157 const Rot3& rotation() const {
158 return pose_.rotation();
159 }
160
162 const Point3& translation() const {
163 return pose_.translation();
164 }
165
167 const Pose3& getPose(OptionalJacobian<6, 6> H) const;
168
172
178 static Point2 Project(const Point3& pc, //
179 OptionalJacobian<2, 3> Dpoint = boost::none);
180
186 static Point2 Project(const Unit3& pc, //
187 OptionalJacobian<2, 2> Dpoint = boost::none);
188
190 std::pair<Point2, bool> projectSafe(const Point3& pw) const;
191
197 Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose =
198 boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
199
205 Point2 project2(const Unit3& point,
206 OptionalJacobian<2, 6> Dpose = boost::none,
207 OptionalJacobian<2, 2> Dpoint = boost::none) const;
208
210 static Point3 BackprojectFromCamera(const Point2& p, const double depth,
211 OptionalJacobian<3, 2> Dpoint = boost::none,
212 OptionalJacobian<3, 1> Ddepth = boost::none);
213
217
223 inline static std::pair<size_t, size_t> translationInterval() {
224 return std::make_pair(3, 5);
225 }
226
228
229private:
230
232 friend class boost::serialization::access;
233 template<class Archive>
234 void serialize(Archive & ar, const unsigned int /*version*/) {
235 ar & BOOST_SERIALIZATION_NVP(pose_);
236 }
237};
238// end of class PinholeBase
239
247class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
248
249public:
250
251 enum {
252 dimension = 6
253 };
254
257
260 }
261
263 explicit CalibratedCamera(const Pose3& pose) :
264 PinholeBase(pose) {
265 }
266
270
271 // Create CalibratedCamera, with derivatives
272 static CalibratedCamera Create(const Pose3& pose,
273 OptionalJacobian<dimension, 6> H1 = boost::none) {
274 if (H1)
275 *H1 << I_6x6;
276 return CalibratedCamera(pose);
277 }
278
285 static CalibratedCamera Level(const Pose2& pose2, double height);
286
295 static CalibratedCamera Lookat(const Point3& eye, const Point3& target,
296 const Point3& upVector);
297
301
303 explicit CalibratedCamera(const Vector &v) :
304 PinholeBase(v) {
305 }
306
310
313 }
314
318
320 CalibratedCamera retract(const Vector& d) const;
321
323 Vector localCoordinates(const CalibratedCamera& T2) const;
324
326 void print(const std::string& s = "CalibratedCamera") const override {
328 }
329
331 inline size_t dim() const {
332 return dimension;
333 }
334
336 inline static size_t Dim() {
337 return dimension;
338 }
339
343
348 Point2 project(const Point3& point, OptionalJacobian<2, 6> Dcamera =
349 boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
350
352 Point3 backproject(const Point2& pn, double depth,
353 OptionalJacobian<3, 6> Dresult_dpose = boost::none,
354 OptionalJacobian<3, 2> Dresult_dp = boost::none,
355 OptionalJacobian<3, 1> Dresult_ddepth = boost::none) const {
356
357 Matrix32 Dpoint_dpn;
358 Matrix31 Dpoint_ddepth;
359 const Point3 point = BackprojectFromCamera(pn, depth,
360 Dresult_dp ? &Dpoint_dpn : 0,
361 Dresult_ddepth ? &Dpoint_ddepth : 0);
362
363 Matrix33 Dresult_dpoint;
364 const Point3 result = pose().transformFrom(point, Dresult_dpose,
365 (Dresult_ddepth ||
366 Dresult_dp) ? &Dresult_dpoint : 0);
367
368 if (Dresult_dp)
369 *Dresult_dp = Dresult_dpoint * Dpoint_dpn;
370 if (Dresult_ddepth)
371 *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth;
372
373 return result;
374 }
375
381 double range(const Point3& point,
382 OptionalJacobian<1, 6> Dcamera = boost::none,
383 OptionalJacobian<1, 3> Dpoint = boost::none) const {
384 return pose().range(point, Dcamera, Dpoint);
385 }
386
392 double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = boost::none,
393 OptionalJacobian<1, 6> Dpose = boost::none) const {
394 return this->pose().range(pose, Dcamera, Dpose);
395 }
396
402 double range(const CalibratedCamera& camera, //
403 OptionalJacobian<1, 6> H1 = boost::none, //
404 OptionalJacobian<1, 6> H2 = boost::none) const {
405 return pose().range(camera.pose(), H1, H2);
406 }
407
409
410private:
411
414
416 friend class boost::serialization::access;
417 template<class Archive>
418 void serialize(Archive & ar, const unsigned int /*version*/) {
419 ar
420 & boost::serialization::make_nvp("PinholeBase",
421 boost::serialization::base_object<PinholeBase>(*this));
422 }
423
425};
426
427// manifold traits
428template <>
429struct traits<CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
430
431template <>
432struct traits<const CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
433
434// range traits, used in RangeFactor
435template <typename T>
436struct Range<CalibratedCamera, T> : HasRange<CalibratedCamera, T, double> {};
437
438} // namespace gtsam
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
Base class and basic functions for Manifold types.
3D Pose
2D Point
Bearing-Range product.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
Definition: expressions.h:96
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Template to create a binary predicate.
Definition: Testable.h:111
Base exception type that uses tbb_allocator if GTSAM is compiled with TBB.
Definition: ThreadsafeException.h:42
Definition: BearingRange.h:39
Definition: BearingRange.h:193
Definition: CalibratedCamera.h:32
Definition: CalibratedCamera.h:52
PinholeBase()
Default constructor.
Definition: CalibratedCamera.h:123
virtual void print(const std::string &s="PinholeBase") const
print
Definition: CalibratedCamera.cpp:74
PinholeBase(const Pose3 &pose)
Constructor with pose.
Definition: CalibratedCamera.h:126
const Point3 & translation() const
get translation
Definition: CalibratedCamera.h:162
const Rot3 & rotation() const
get rotation
Definition: CalibratedCamera.h:157
Point2 Measurement
Some classes template on either PinholeCamera or StereoCamera, and this typedef informs those classes...
Definition: CalibratedCamera.h:64
const Pose3 & pose() const
return pose, constant version
Definition: CalibratedCamera.h:152
static std::pair< size_t, size_t > translationInterval()
Return the start and end indices (inclusive) of the translation component of the exponential map para...
Definition: CalibratedCamera.h:223
Rot3 Rotation
Pose Concept requirements.
Definition: CalibratedCamera.h:57
virtual ~PinholeBase()=default
Default destructor.
Definition: CalibratedCamera.h:247
Point3 backproject(const Point2 &pn, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition: CalibratedCamera.h:352
CalibratedCamera()
default constructor
Definition: CalibratedCamera.h:259
double range(const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
Calculate range to another pose.
Definition: CalibratedCamera.h:392
size_t dim() const
Definition: CalibratedCamera.h:331
CalibratedCamera(const Vector &v)
construct from vector
Definition: CalibratedCamera.h:303
virtual ~CalibratedCamera()
destructor
Definition: CalibratedCamera.h:312
static size_t Dim()
Definition: CalibratedCamera.h:336
double range(const CalibratedCamera &camera, OptionalJacobian< 1, 6 > H1=boost::none, OptionalJacobian< 1, 6 > H2=boost::none) const
Calculate range to another camera.
Definition: CalibratedCamera.h:402
void print(const std::string &s="CalibratedCamera") const override
print
Definition: CalibratedCamera.h:326
double range(const Point3 &point, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Calculate range to a landmark.
Definition: CalibratedCamera.h:381
CalibratedCamera(const Pose3 &pose)
construct with pose
Definition: CalibratedCamera.h:263
Definition: Pose2.h:36
Definition: Pose3.h:37
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:342
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Calculate range to a landmark.
Definition: Pose3.cpp:378
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:303
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:310
Definition: Rot3.h:59
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42