gtsam  4.0.0
gtsam
triangulation.h File Reference

Functions for triangulation. More...

Go to the source code of this file.

Classes

class  gtsam::TriangulationUnderconstrainedException
 Exception thrown by triangulateDLT when SVD returns rank < 3. More...
 
class  gtsam::TriangulationCheiralityException
 Exception thrown by triangulateDLT when landmark is behind one or more of the cameras. More...
 
struct  gtsam::CameraProjectionMatrix< CALIBRATION >
 Create a 3*4 camera projection matrix from calibration and pose. More...
 
struct  gtsam::TriangulationParameters
 
class  gtsam::TriangulationResult
 TriangulationResult is an optional point, along with the reasons why it is invalid. More...
 

Namespaces

 gtsam
 Global functions in a separate testing namespace.
 

Functions

Vector4 gtsam::triangulateHomogeneousDLT (const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol=1e-9)
 DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312. More...
 
Point3 gtsam::triangulateDLT (const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol=1e-9)
 DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312. More...
 
template<class CALIBRATION >
std::pair< NonlinearFactorGraph, Values > gtsam::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. More...
 
template<class CAMERA >
std::pair< NonlinearFactorGraph, Values > gtsam::triangulationGraph (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, Key landmarkKey, const Point3 &initialEstimate)
 Create a factor graph with projection factors from pinhole cameras (each camera has a pose and calibration) More...
 
template<class CALIBRATION >
std::pair< NonlinearFactorGraph, Values > gtsam::triangulationGraph (const CameraSet< PinholeCamera< CALIBRATION > > &cameras, const Point2Vector &measurements, Key landmarkKey, const Point3 &initialEstimate)
 PinholeCamera specific version // TODO: (chris) why does this exist?
 
Point3 gtsam::optimize (const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
 Optimize for triangulation. More...
 
template<class CALIBRATION >
Point3 gtsam::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. More...
 
template<class CAMERA >
Point3 gtsam::triangulateNonlinear (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, const Point3 &initialEstimate)
 Given an initial estimate , refine a point using measurements in several cameras. More...
 
template<class CALIBRATION >
Point3 gtsam::triangulateNonlinear (const CameraSet< PinholeCamera< CALIBRATION > > &cameras, const Point2Vector &measurements, const Point3 &initialEstimate)
 PinholeCamera specific version // TODO: (chris) why does this exist?
 
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)
 Function to triangulate 3D landmark point from an arbitrary number of poses (at least 2) using the DLT. More...
 
template<class CAMERA >
Point3 gtsam::triangulatePoint3 (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &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 DLT. More...
 
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.
 
template<class CAMERA >
TriangulationResult gtsam::triangulateSafe (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters &params)
 triangulateSafe: extensive checking of the outcome
 

Detailed Description

Functions for triangulation.

Date
July 31, 2013
Author
Chris Beall