gtsam  4.0.0
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 
23 #include <gtsam/geometry/Pose2.h>
24 #include <gtsam/slam/TriangulationFactor.h>
25 #include <gtsam/slam/PriorFactor.h>
27 #include <gtsam/inference/Symbol.h>
28 
29 namespace gtsam {
30 
32 class GTSAM_EXPORT TriangulationUnderconstrainedException: public std::runtime_error {
33 public:
35  std::runtime_error("Triangulation Underconstrained Exception.") {
36  }
37 };
38 
40 class GTSAM_EXPORT TriangulationCheiralityException: public std::runtime_error {
41 public:
43  std::runtime_error(
44  "Triangulation Cheirality Exception: The resulting landmark is behind one or more cameras.") {
45  }
46 };
47 
55 GTSAM_EXPORT Vector4 triangulateHomogeneousDLT(
56  const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
57  const Point2Vector& measurements, double rank_tol = 1e-9);
58 
66 GTSAM_EXPORT Point3 triangulateDLT(
67  const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
68  const Point2Vector& measurements,
69  double rank_tol = 1e-9);
70 
80 template<class CALIBRATION>
81 std::pair<NonlinearFactorGraph, Values> triangulationGraph(
82  const std::vector<Pose3>& poses, boost::shared_ptr<CALIBRATION> sharedCal,
83  const Point2Vector& measurements, Key landmarkKey,
84  const Point3& initialEstimate) {
85  Values values;
86  values.insert(landmarkKey, initialEstimate); // Initial landmark value
89  static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6));
90  for (size_t i = 0; i < measurements.size(); i++) {
91  const Pose3& pose_i = poses[i];
92  typedef PinholePose<CALIBRATION> Camera;
93  Camera camera_i(pose_i, sharedCal);
94  graph.emplace_shared<TriangulationFactor<Camera> > //
95  (camera_i, measurements[i], unit2, landmarkKey);
96  }
97  return std::make_pair(graph, values);
98 }
99 
109 template<class CAMERA>
110 std::pair<NonlinearFactorGraph, Values> triangulationGraph(
111  const CameraSet<CAMERA>& cameras,
112  const typename CAMERA::MeasurementVector& measurements, Key landmarkKey,
113  const Point3& initialEstimate) {
114  Values values;
115  values.insert(landmarkKey, initialEstimate); // Initial landmark value
116  NonlinearFactorGraph graph;
119  for (size_t i = 0; i < measurements.size(); i++) {
120  const CAMERA& camera_i = cameras[i];
121  graph.emplace_shared<TriangulationFactor<CAMERA> > //
122  (camera_i, measurements[i], unit, landmarkKey);
123  }
124  return std::make_pair(graph, values);
125 }
126 
128 template<class CALIBRATION>
129 std::pair<NonlinearFactorGraph, Values> triangulationGraph(
130  const CameraSet<PinholeCamera<CALIBRATION> >& cameras,
131  const Point2Vector& measurements, Key landmarkKey,
132  const Point3& initialEstimate) {
133  return triangulationGraph<PinholeCamera<CALIBRATION> > //
134  (cameras, measurements, landmarkKey, initialEstimate);
135 }
136 
144 GTSAM_EXPORT Point3 optimize(const NonlinearFactorGraph& graph,
145  const Values& values, Key landmarkKey);
146 
155 template<class CALIBRATION>
156 Point3 triangulateNonlinear(const std::vector<Pose3>& poses,
157  boost::shared_ptr<CALIBRATION> sharedCal,
158  const Point2Vector& measurements, const Point3& initialEstimate) {
159 
160  // Create a factor graph and initial values
161  Values values;
162  NonlinearFactorGraph graph;
163  boost::tie(graph, values) = triangulationGraph<CALIBRATION> //
164  (poses, sharedCal, measurements, Symbol('p', 0), initialEstimate);
165 
166  return optimize(graph, values, Symbol('p', 0));
167 }
168 
176 template<class CAMERA>
178  const CameraSet<CAMERA>& cameras,
179  const typename CAMERA::MeasurementVector& measurements, const Point3& initialEstimate) {
180 
181  // Create a factor graph and initial values
182  Values values;
183  NonlinearFactorGraph graph;
184  boost::tie(graph, values) = triangulationGraph<CAMERA> //
185  (cameras, measurements, Symbol('p', 0), initialEstimate);
186 
187  return optimize(graph, values, Symbol('p', 0));
188 }
189 
191 template<class CALIBRATION>
193  const CameraSet<PinholeCamera<CALIBRATION> >& cameras,
194  const Point2Vector& measurements, const Point3& initialEstimate) {
195  return triangulateNonlinear<PinholeCamera<CALIBRATION> > //
196  (cameras, measurements, initialEstimate);
197 }
198 
206 template<class CALIBRATION>
208  CameraProjectionMatrix(const CALIBRATION& calibration) :
209  K_(calibration.K()) {
210  }
211  Matrix34 operator()(const Pose3& pose) const {
212  return K_ * (pose.inverse().matrix()).block<3, 4>(0, 0);
213  }
214 private:
215  const Matrix3 K_;
216 public:
217  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
218 };
219 
232 template<class CALIBRATION>
233 Point3 triangulatePoint3(const std::vector<Pose3>& poses,
234  boost::shared_ptr<CALIBRATION> sharedCal,
235  const Point2Vector& measurements, double rank_tol = 1e-9,
236  bool optimize = false) {
237 
238  assert(poses.size() == measurements.size());
239  if (poses.size() < 2)
241 
242  // construct projection matrices from poses & calibration
243  std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
244  CameraProjectionMatrix<CALIBRATION> createP(*sharedCal); // partially apply
245  for(const Pose3& pose: poses)
246  projection_matrices.push_back(createP(pose));
247 
248  // Triangulate linearly
249  Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol);
250 
251  // Then refine using non-linear optimization
252  if (optimize)
253  point = triangulateNonlinear<CALIBRATION> //
254  (poses, sharedCal, measurements, point);
255 
256 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
257  // verify that the triangulated point lies in front of all cameras
258  for(const Pose3& pose: poses) {
259  const Point3& p_local = pose.transformTo(point);
260  if (p_local.z() <= 0)
262  }
263 #endif
264 
265  return point;
266 }
267 
280 template<class CAMERA>
282  const CameraSet<CAMERA>& cameras,
283  const typename CAMERA::MeasurementVector& measurements, double rank_tol = 1e-9,
284  bool optimize = false) {
285 
286  size_t m = cameras.size();
287  assert(measurements.size() == m);
288 
289  if (m < 2)
291 
292  // construct projection matrices from poses & calibration
293  std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
294  for(const CAMERA& camera: cameras)
295  projection_matrices.push_back(
297  camera.pose()));
298  Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol);
299 
300  // The n refine using non-linear optimization
301  if (optimize)
302  point = triangulateNonlinear<CAMERA>(cameras, measurements, point);
303 
304 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
305  // verify that the triangulated point lies in front of all cameras
306  for(const CAMERA& camera: cameras) {
307  const Point3& p_local = camera.pose().transformTo(point);
308  if (p_local.z() <= 0)
310  }
311 #endif
312 
313  return point;
314 }
315 
317 template<class CALIBRATION>
319  const CameraSet<PinholeCamera<CALIBRATION> >& cameras,
320  const Point2Vector& measurements, double rank_tol = 1e-9,
321  bool optimize = false) {
322  return triangulatePoint3<PinholeCamera<CALIBRATION> > //
323  (cameras, measurements, rank_tol, optimize);
324 }
325 
326 struct GTSAM_EXPORT TriangulationParameters {
327 
328  double rankTolerance;
329  bool enableEPI;
331 
337 
344 
353  TriangulationParameters(const double _rankTolerance = 1.0,
354  const bool _enableEPI = false, double _landmarkDistanceThreshold = -1,
355  double _dynamicOutlierRejectionThreshold = -1) :
356  rankTolerance(_rankTolerance), enableEPI(_enableEPI), //
357  landmarkDistanceThreshold(_landmarkDistanceThreshold), //
358  dynamicOutlierRejectionThreshold(_dynamicOutlierRejectionThreshold) {
359  }
360 
361  // stream to output
362  friend std::ostream &operator<<(std::ostream &os,
363  const TriangulationParameters& p) {
364  os << "rankTolerance = " << p.rankTolerance << std::endl;
365  os << "enableEPI = " << p.enableEPI << std::endl;
366  os << "landmarkDistanceThreshold = " << p.landmarkDistanceThreshold
367  << std::endl;
368  os << "dynamicOutlierRejectionThreshold = "
369  << p.dynamicOutlierRejectionThreshold << std::endl;
370  return os;
371  }
372 
373 private:
374 
376  friend class boost::serialization::access;
377  template<class ARCHIVE>
378  void serialize(ARCHIVE & ar, const unsigned int version) {
379  ar & BOOST_SERIALIZATION_NVP(rankTolerance);
380  ar & BOOST_SERIALIZATION_NVP(enableEPI);
381  ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold);
382  ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold);
383  }
384 };
385 
389 class GTSAM_EXPORT TriangulationResult: public boost::optional<Point3> {
390  enum Status {
391  VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT
392  };
393  Status status_;
394  TriangulationResult(Status s) :
395  status_(s) {
396  }
397 public:
398 
403 
408  status_(VALID) {
409  reset(p);
410  }
411  static TriangulationResult Degenerate() {
412  return TriangulationResult(DEGENERATE);
413  }
414  static TriangulationResult Outlier() {
415  return TriangulationResult(OUTLIER);
416  }
417  static TriangulationResult FarPoint() {
418  return TriangulationResult(FAR_POINT);
419  }
420  static TriangulationResult BehindCamera() {
421  return TriangulationResult(BEHIND_CAMERA);
422  }
423  bool valid() const {
424  return status_ == VALID;
425  }
426  bool degenerate() const {
427  return status_ == DEGENERATE;
428  }
429  bool outlier() const {
430  return status_ == OUTLIER;
431  }
432  bool farPoint() const {
433  return status_ == FAR_POINT;
434  }
435  bool behindCamera() const {
436  return status_ == BEHIND_CAMERA;
437  }
438  // stream to output
439  friend std::ostream &operator<<(std::ostream &os,
440  const TriangulationResult& result) {
441  if (result)
442  os << "point = " << *result << std::endl;
443  else
444  os << "no point, status = " << result.status_ << std::endl;
445  return os;
446  }
447 
448 private:
449 
451  friend class boost::serialization::access;
452  template<class ARCHIVE>
453  void serialize(ARCHIVE & ar, const unsigned int version) {
454  ar & BOOST_SERIALIZATION_NVP(status_);
455  }
456 };
457 
459 template<class CAMERA>
461  const typename CAMERA::MeasurementVector& measured,
462  const TriangulationParameters& params) {
463 
464  size_t m = cameras.size();
465 
466  // if we have a single pose the corresponding factor is uninformative
467  if (m < 2)
468  return TriangulationResult::Degenerate();
469  else
470  // We triangulate the 3D position of the landmark
471  try {
472  Point3 point = triangulatePoint3<CAMERA>(cameras, measured,
473  params.rankTolerance, params.enableEPI);
474 
475  // Check landmark distance and re-projection errors to avoid outliers
476  size_t i = 0;
477  double maxReprojError = 0.0;
478  for(const CAMERA& camera: cameras) {
479  const Pose3& pose = camera.pose();
480  if (params.landmarkDistanceThreshold > 0
481  && distance3(pose.translation(), point)
482  > params.landmarkDistanceThreshold)
483  return TriangulationResult::FarPoint();
484 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
485  // verify that the triangulated point lies in front of all cameras
486  // Only needed if this was not yet handled by exception
487  const Point3& p_local = pose.transformTo(point);
488  if (p_local.z() <= 0)
489  return TriangulationResult::BehindCamera();
490 #endif
491  // Check reprojection error
492  if (params.dynamicOutlierRejectionThreshold > 0) {
493  const Point2& zi = measured.at(i);
494  Point2 reprojectionError(camera.project(point) - zi);
495  maxReprojError = std::max(maxReprojError, reprojectionError.norm());
496  }
497  i += 1;
498  }
499  // Flag as degenerate if average reprojection error is too large
500  if (params.dynamicOutlierRejectionThreshold > 0
501  && maxReprojError > params.dynamicOutlierRejectionThreshold)
502  return TriangulationResult::Outlier();
503 
504  // all good!
505  return TriangulationResult(point);
507  // This exception is thrown if
508  // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before
509  // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark)
510  return TriangulationResult::Degenerate();
512  // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers
513  return TriangulationResult::BehindCamera();
514  }
515 }
516 
517 } // \namespace gtsam
518 
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:133
Exception thrown by triangulateDLT when landmark is behind one or more of the cameras.
Definition: triangulation.h:40
Point3 transformTo(const Point3 &p, OptionalJacobian< 3, 6 > Dpose=boost::none, OptionalJacobian< 3, 3 > Dpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:328
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Optimize for triangulation.
Definition: triangulation.cpp:73
Definition: PinholeCamera.h:33
Character and index key used to refer to variables.
Definition: Symbol.h:33
Definition: Point3.h:45
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
const Point3 & translation(OptionalJacobian< 3, 6 > H=boost::none) const
get translation
Definition: Pose3.cpp:265
double dynamicOutlierRejectionThreshold
If this is nonnegative the we will check if the average reprojection error is smaller than this thres...
Definition: triangulation.h:343
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Definition: TriangulationFactor.h:31
Definition: PinholePose.h:237
double landmarkDistanceThreshold
if the landmark is triangulated at distance larger than this, result is flagged as degenerate.
Definition: triangulation.h:336
TriangulationResult(const Point3 &p)
Constructor.
Definition: triangulation.h:407
Definition: triangulation.h:326
Exception thrown by triangulateDLT when SVD returns rank < 3.
Definition: triangulation.h:32
Base class for all pinhole cameras.
Factor Graph Constsiting of non-linear factors.
bool enableEPI
if set to true, will refine triangulation using LM
Definition: triangulation.h:330
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters &params)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:460
static shared_ptr Create(size_t dim)
Create a unit covariance noise model.
Definition: NoiseModel.h:601
Create a 3*4 camera projection matrix from calibration and pose.
Definition: triangulation.h:207
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
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
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:233
TriangulationResult is an optional point, along with the reasons why it is invalid.
Definition: triangulation.h:389
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:77
Definition: Point2.h:40
TriangulationParameters(const double _rankTolerance=1.0, const bool _enableEPI=false, double _landmarkDistanceThreshold=-1, double _dynamicOutlierRejectionThreshold=-1)
Constructor.
Definition: triangulation.h:353
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:47
Base class to create smart factors on poses or cameras.
Matrix4 matrix() const
convert to 4*4 matrix
Definition: Pose3.cpp:280
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
2D Pose
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
TriangulationResult()
Default constructor, only for serialization.
Definition: triangulation.h:402
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:561
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:156
Definition: Pose3.h:37
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:81
double rankTolerance
threshold to decide whether triangulation is result.degenerate
Definition: triangulation.h:328
double z() const
get z
Definition: Point3.h:114
double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian< 1, 3 > H1, OptionalJacobian< 1, 3 > H2)
distance between two points
Definition: Point3.cpp:84