Classes | Namespaces | Typedefs | Functions
triangulation.h File Reference

Functions for triangulation. More...

#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/CameraSet.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/slam/TriangulationFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/inference/Symbol.h>
Include dependency graph for triangulation.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  gtsam::CameraProjectionMatrix< CALIBRATION >
 
class  gtsam::TriangulationCheiralityException
 Exception thrown by triangulateDLT when landmark is behind one or more of the cameras. More...
 
struct  gtsam::TriangulationParameters
 
class  gtsam::TriangulationResult
 
class  gtsam::TriangulationUnderconstrainedException
 Exception thrown by triangulateDLT when SVD returns rank < 3. More...
 

Namespaces

 gtsam
 traits
 

Typedefs

using gtsam::CameraSetCal3_S2 = CameraSet< PinholeCamera< Cal3_S2 >>
 
using gtsam::CameraSetCal3Bundler = CameraSet< PinholeCamera< Cal3Bundler >>
 

Functions

Point3 gtsam::optimize (const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
 
Point3 gtsam::triangulateDLT (const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol)
 
Vector4 gtsam::triangulateHomogeneousDLT (const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol)
 
template<class CALIBRATION >
Point3 gtsam::triangulateNonlinear (const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, const Point3 &initialEstimate)
 
template<class CAMERA >
Point3 gtsam::triangulateNonlinear (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, const Point3 &initialEstimate)
 
template<class CALIBRATION >
Point3 gtsam::triangulatePoint3 (const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false)
 
template<class CAMERA >
Point3 gtsam::triangulatePoint3 (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, double rank_tol=1e-9, bool optimize=false)
 
template<class CALIBRATION >
Point3 gtsam::triangulatePoint3 (const CameraSet< PinholeCamera< CALIBRATION > > &cameras, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false)
 Pinhole-specific version. More...
 
template<class CAMERA >
TriangulationResult gtsam::triangulateSafe (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters &params)
 triangulateSafe: extensive checking of the outcome More...
 
template<class CALIBRATION >
std::pair< NonlinearFactorGraph, Valuesgtsam::triangulationGraph (const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, Key landmarkKey, const Point3 &initialEstimate)
 
template<class CAMERA >
std::pair< NonlinearFactorGraph, Valuesgtsam::triangulationGraph (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, Key landmarkKey, const Point3 &initialEstimate)
 

Detailed Description

Functions for triangulation.

Date
July 31, 2013
Author
Chris Beall

Definition in file triangulation.h.



gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:42