gtsam 4.1.1
gtsam
triangulation.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
30#include <gtsam/slam/TriangulationFactor.h>
31
32namespace gtsam {
33
35class GTSAM_EXPORT TriangulationUnderconstrainedException: public std::runtime_error {
36public:
38 std::runtime_error("Triangulation Underconstrained Exception.") {
39 }
40};
41
43class GTSAM_EXPORT TriangulationCheiralityException: public std::runtime_error {
44public:
46 std::runtime_error(
47 "Triangulation Cheirality Exception: The resulting landmark is behind one or more cameras.") {
48 }
49};
50
58GTSAM_EXPORT Vector4 triangulateHomogeneousDLT(
59 const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
60 const Point2Vector& measurements, double rank_tol = 1e-9);
61
69GTSAM_EXPORT Point3 triangulateDLT(
70 const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
71 const Point2Vector& measurements,
72 double rank_tol = 1e-9);
73
83template<class CALIBRATION>
84std::pair<NonlinearFactorGraph, Values> triangulationGraph(
85 const std::vector<Pose3>& poses, boost::shared_ptr<CALIBRATION> sharedCal,
86 const Point2Vector& measurements, Key landmarkKey,
87 const Point3& initialEstimate) {
88 Values values;
89 values.insert(landmarkKey, initialEstimate); // Initial landmark value
92 static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6));
93 for (size_t i = 0; i < measurements.size(); i++) {
94 const Pose3& pose_i = poses[i];
95 typedef PinholePose<CALIBRATION> Camera;
96 Camera camera_i(pose_i, sharedCal);
97 graph.emplace_shared<TriangulationFactor<Camera> > //
98 (camera_i, measurements[i], unit2, landmarkKey);
99 }
100 return std::make_pair(graph, values);
101}
102
112template<class CAMERA>
113std::pair<NonlinearFactorGraph, Values> triangulationGraph(
114 const CameraSet<CAMERA>& cameras,
115 const typename CAMERA::MeasurementVector& measurements, Key landmarkKey,
116 const Point3& initialEstimate) {
117 Values values;
118 values.insert(landmarkKey, initialEstimate); // Initial landmark value
122 for (size_t i = 0; i < measurements.size(); i++) {
123 const CAMERA& camera_i = cameras[i];
124 graph.emplace_shared<TriangulationFactor<CAMERA> > //
125 (camera_i, measurements[i], unit, landmarkKey);
126 }
127 return std::make_pair(graph, values);
128}
129
137GTSAM_EXPORT Point3 optimize(const NonlinearFactorGraph& graph,
138 const Values& values, Key landmarkKey);
139
148template<class CALIBRATION>
149Point3 triangulateNonlinear(const std::vector<Pose3>& poses,
150 boost::shared_ptr<CALIBRATION> sharedCal,
151 const Point2Vector& measurements, const Point3& initialEstimate) {
152
153 // Create a factor graph and initial values
154 Values values;
156 boost::tie(graph, values) = triangulationGraph<CALIBRATION> //
157 (poses, sharedCal, measurements, Symbol('p', 0), initialEstimate);
158
159 return optimize(graph, values, Symbol('p', 0));
160}
161
169template<class CAMERA>
171 const CameraSet<CAMERA>& cameras,
172 const typename CAMERA::MeasurementVector& measurements, const Point3& initialEstimate) {
173
174 // Create a factor graph and initial values
175 Values values;
177 boost::tie(graph, values) = triangulationGraph<CAMERA> //
178 (cameras, measurements, Symbol('p', 0), initialEstimate);
179
180 return optimize(graph, values, Symbol('p', 0));
181}
182
190template<class CALIBRATION>
192 CameraProjectionMatrix(const CALIBRATION& calibration) :
193 K_(calibration.K()) {
194 }
195 Matrix34 operator()(const Pose3& pose) const {
196 return K_ * (pose.inverse().matrix()).block<3, 4>(0, 0);
197 }
198private:
199 const Matrix3 K_;
200public:
202};
203
216template<class CALIBRATION>
217Point3 triangulatePoint3(const std::vector<Pose3>& poses,
218 boost::shared_ptr<CALIBRATION> sharedCal,
219 const Point2Vector& measurements, double rank_tol = 1e-9,
220 bool optimize = false) {
221
222 assert(poses.size() == measurements.size());
223 if (poses.size() < 2)
225
226 // construct projection matrices from poses & calibration
227 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
228 CameraProjectionMatrix<CALIBRATION> createP(*sharedCal); // partially apply
229 for(const Pose3& pose: poses)
230 projection_matrices.push_back(createP(pose));
231
232 // Triangulate linearly
233 Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol);
234
235 // Then refine using non-linear optimization
236 if (optimize)
237 point = triangulateNonlinear<CALIBRATION> //
238 (poses, sharedCal, measurements, point);
239
240#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
241 // verify that the triangulated point lies in front of all cameras
242 for(const Pose3& pose: poses) {
243 const Point3& p_local = pose.transformTo(point);
244 if (p_local.z() <= 0)
246 }
247#endif
248
249 return point;
250}
251
264template<class CAMERA>
266 const CameraSet<CAMERA>& cameras,
267 const typename CAMERA::MeasurementVector& measurements, double rank_tol = 1e-9,
268 bool optimize = false) {
269
270 size_t m = cameras.size();
271 assert(measurements.size() == m);
272
273 if (m < 2)
275
276 // construct projection matrices from poses & calibration
277 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
278 for(const CAMERA& camera: cameras)
279 projection_matrices.push_back(
281 camera.pose()));
282 Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol);
283
284 // The n refine using non-linear optimization
285 if (optimize)
286 point = triangulateNonlinear<CAMERA>(cameras, measurements, point);
287
288#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
289 // verify that the triangulated point lies in front of all cameras
290 for(const CAMERA& camera: cameras) {
291 const Point3& p_local = camera.pose().transformTo(point);
292 if (p_local.z() <= 0)
294 }
295#endif
296
297 return point;
298}
299
301template<class CALIBRATION>
303 const CameraSet<PinholeCamera<CALIBRATION> >& cameras,
304 const Point2Vector& measurements, double rank_tol = 1e-9,
305 bool optimize = false) {
306 return triangulatePoint3<PinholeCamera<CALIBRATION> > //
307 (cameras, measurements, rank_tol, optimize);
308}
309
310struct GTSAM_EXPORT TriangulationParameters {
311
315
321
328
337 TriangulationParameters(const double _rankTolerance = 1.0,
338 const bool _enableEPI = false, double _landmarkDistanceThreshold = -1,
339 double _dynamicOutlierRejectionThreshold = -1) :
340 rankTolerance(_rankTolerance), enableEPI(_enableEPI), //
341 landmarkDistanceThreshold(_landmarkDistanceThreshold), //
342 dynamicOutlierRejectionThreshold(_dynamicOutlierRejectionThreshold) {
343 }
344
345 // stream to output
346 friend std::ostream &operator<<(std::ostream &os,
347 const TriangulationParameters& p) {
348 os << "rankTolerance = " << p.rankTolerance << std::endl;
349 os << "enableEPI = " << p.enableEPI << std::endl;
350 os << "landmarkDistanceThreshold = " << p.landmarkDistanceThreshold
351 << std::endl;
352 os << "dynamicOutlierRejectionThreshold = "
353 << p.dynamicOutlierRejectionThreshold << std::endl;
354 return os;
355 }
356
357private:
358
360 friend class boost::serialization::access;
361 template<class ARCHIVE>
362 void serialize(ARCHIVE & ar, const unsigned int version) {
363 ar & BOOST_SERIALIZATION_NVP(rankTolerance);
364 ar & BOOST_SERIALIZATION_NVP(enableEPI);
365 ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold);
366 ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold);
367 }
368};
369
373class TriangulationResult: public boost::optional<Point3> {
374 enum Status {
375 VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT
376 };
377 Status status_;
378 TriangulationResult(Status s) :
379 status_(s) {
380 }
381public:
382
387
392 status_(VALID) {
393 reset(p);
394 }
395 static TriangulationResult Degenerate() {
396 return TriangulationResult(DEGENERATE);
397 }
398 static TriangulationResult Outlier() {
399 return TriangulationResult(OUTLIER);
400 }
401 static TriangulationResult FarPoint() {
402 return TriangulationResult(FAR_POINT);
403 }
404 static TriangulationResult BehindCamera() {
405 return TriangulationResult(BEHIND_CAMERA);
406 }
407 bool valid() const {
408 return status_ == VALID;
409 }
410 bool degenerate() const {
411 return status_ == DEGENERATE;
412 }
413 bool outlier() const {
414 return status_ == OUTLIER;
415 }
416 bool farPoint() const {
417 return status_ == FAR_POINT;
418 }
419 bool behindCamera() const {
420 return status_ == BEHIND_CAMERA;
421 }
422 // stream to output
423 friend std::ostream &operator<<(std::ostream &os,
424 const TriangulationResult& result) {
425 if (result)
426 os << "point = " << *result << std::endl;
427 else
428 os << "no point, status = " << result.status_ << std::endl;
429 return os;
430 }
431
432private:
433
436 template<class ARCHIVE>
437 void serialize(ARCHIVE & ar, const unsigned int version) {
438 ar & BOOST_SERIALIZATION_NVP(status_);
439 }
440};
441
443template<class CAMERA>
445 const typename CAMERA::MeasurementVector& measured,
446 const TriangulationParameters& params) {
447
448 size_t m = cameras.size();
449
450 // if we have a single pose the corresponding factor is uninformative
451 if (m < 2)
452 return TriangulationResult::Degenerate();
453 else
454 // We triangulate the 3D position of the landmark
455 try {
456 Point3 point = triangulatePoint3<CAMERA>(cameras, measured,
457 params.rankTolerance, params.enableEPI);
458
459 // Check landmark distance and re-projection errors to avoid outliers
460 size_t i = 0;
461 double maxReprojError = 0.0;
462 for(const CAMERA& camera: cameras) {
463 const Pose3& pose = camera.pose();
464 if (params.landmarkDistanceThreshold > 0
465 && distance3(pose.translation(), point)
467 return TriangulationResult::FarPoint();
468#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
469 // verify that the triangulated point lies in front of all cameras
470 // Only needed if this was not yet handled by exception
471 const Point3& p_local = pose.transformTo(point);
472 if (p_local.z() <= 0)
473 return TriangulationResult::BehindCamera();
474#endif
475 // Check reprojection error
476 if (params.dynamicOutlierRejectionThreshold > 0) {
477 const Point2& zi = measured.at(i);
478 Point2 reprojectionError(camera.project(point) - zi);
479 maxReprojError = std::max(maxReprojError, reprojectionError.norm());
480 }
481 i += 1;
482 }
483 // Flag as degenerate if average reprojection error is too large
485 && maxReprojError > params.dynamicOutlierRejectionThreshold)
486 return TriangulationResult::Outlier();
487
488 // all good!
489 return TriangulationResult(point);
491 // This exception is thrown if
492 // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before
493 // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark)
494 return TriangulationResult::Degenerate();
496 // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers
497 return TriangulationResult::BehindCamera();
498 }
499}
500
501// Vector of Cameras - used by the Python/MATLAB wrapper
502using CameraSetCal3Bundler = CameraSet<PinholeCamera<Cal3Bundler>>;
503using CameraSetCal3_S2 = CameraSet<PinholeCamera<Cal3_S2>>;
504using CameraSetCal3Fisheye = CameraSet<PinholeCamera<Cal3Fisheye>>;
505using CameraSetCal3Unified = CameraSet<PinholeCamera<Cal3Unified>>;
506
507} // \namespace gtsam
508
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
This marks a GTSAM object to require alignment.
Definition: types.h:277
The most common 5DOF 3D->2D calibration.
Unified Calibration Model, see Mei07icra for details.
Base class to create smart factors on poses or cameras.
Base class for all pinhole cameras.
Calibration used by Bundler.
2D Pose
Calibration of a fisheye camera.
Factor Graph consisting of non-linear factors.
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
std::pair< NonlinearFactorGraph, Values > triangulationGraph(const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, Key landmarkKey, const Point3 &initialEstimate)
Create a factor graph with projection factors from poses and one calibration.
Definition: triangulation.h:84
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Optimize for triangulation.
Definition: triangulation.cpp:73
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
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters &params)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:444
double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian< 1, 3 > H1, OptionalJacobian< 1, 3 > H2)
distance between two points
Definition: Point3.cpp:26
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
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
Point3 triangulatePoint3(const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false)
Function to triangulate 3D landmark point from an arbitrary number of poses (at least 2) using the DL...
Definition: triangulation.h:217
Point3 triangulateDLT(const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 > > &projection_matrices, const Point2Vector &measurements, double rank_tol)
DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312.
Definition: triangulation.cpp:56
Vector4 triangulateHomogeneousDLT(const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 > > &projection_matrices, const Point2Vector &measurements, double rank_tol)
DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312.
Definition: triangulation.cpp:26
Point3 triangulateNonlinear(const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, const Point3 &initialEstimate)
Given an initial estimate , refine a point using measurements in several cameras.
Definition: triangulation.h:149
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
Definition: PinholeCamera.h:33
Definition: PinholePose.h:237
Definition: Pose3.h:37
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:358
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:303
Matrix4 matrix() const
convert to 4*4 matrix
Definition: Pose3.cpp:318
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:50
Exception thrown by triangulateDLT when SVD returns rank < 3.
Definition: triangulation.h:35
Exception thrown by triangulateDLT when landmark is behind one or more of the cameras.
Definition: triangulation.h:43
Create a 3*4 camera projection matrix from calibration and pose.
Definition: triangulation.h:191
Definition: triangulation.h:310
double dynamicOutlierRejectionThreshold
If this is nonnegative the we will check if the average reprojection error is smaller than this thres...
Definition: triangulation.h:327
TriangulationParameters(const double _rankTolerance=1.0, const bool _enableEPI=false, double _landmarkDistanceThreshold=-1, double _dynamicOutlierRejectionThreshold=-1)
Constructor.
Definition: triangulation.h:337
double rankTolerance
threshold to decide whether triangulation is result.degenerate
Definition: triangulation.h:312
double landmarkDistanceThreshold
if the landmark is triangulated at distance larger than this, result is flagged as degenerate.
Definition: triangulation.h:320
bool enableEPI
if set to true, will refine triangulation using LM
Definition: triangulation.h:314
TriangulationResult is an optional point, along with the reasons why it is invalid.
Definition: triangulation.h:373
TriangulationResult()
Default constructor, only for serialization.
Definition: triangulation.h:386
TriangulationResult(const Point3 &p)
Constructor.
Definition: triangulation.h:391
friend class boost::serialization::access
Serialization function.
Definition: triangulation.h:435
Character and index key used to refer to variables.
Definition: Symbol.h:35
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:567
static shared_ptr Create(size_t dim)
Create a unit covariance noise model.
Definition: NoiseModel.h:611
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:78
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
void insert(Key j, const Value &val)
Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present.
Definition: Values.cpp:132
Definition: TriangulationFactor.h:31