Functions for triangulation. More...
#include <gtsam/geometry/Point3.h>#include <gtsam/geometry/Cal3Bundler.h>#include <gtsam/geometry/Cal3Fisheye.h>#include <gtsam/geometry/Cal3Unified.h>#include <gtsam/geometry/Cal3_S2.h>#include <gtsam/geometry/Cal3DS2.h>#include <gtsam/geometry/CameraSet.h>#include <gtsam/geometry/PinholeCamera.h>#include <gtsam/geometry/SphericalCamera.h>#include <gtsam/geometry/Pose2.h>#include <gtsam/inference/Symbol.h>#include <gtsam/nonlinear/NonlinearFactorGraph.h>#include <gtsam/slam/TriangulationFactor.h>#include <optional>

Go to the source code of this file.
Classes | |
| 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 > > |
| using | gtsam::CameraSetCal3DS2 = CameraSet< PinholeCamera< Cal3DS2 > > |
| using | gtsam::CameraSetCal3Fisheye = CameraSet< PinholeCamera< Cal3Fisheye > > |
| using | gtsam::CameraSetCal3Unified = CameraSet< PinholeCamera< Cal3Unified > > |
| using | gtsam::CameraSetPinholePoseCal3_S2 = CameraSet< PinholePose< Cal3_S2 > > |
| using | gtsam::CameraSetPinholePoseCal3Bundler = CameraSet< PinholePose< Cal3Bundler > > |
| using | gtsam::CameraSetPinholePoseCal3DS2 = CameraSet< PinholePose< Cal3DS2 > > |
| using | gtsam::CameraSetPinholePoseCal3Fisheye = CameraSet< PinholePose< Cal3Fisheye > > |
| using | gtsam::CameraSetPinholePoseCal3Unified = CameraSet< PinholePose< Cal3Unified > > |
| using | gtsam::CameraSetSpherical = CameraSet< SphericalCamera > |
Functions | |
| template<class CAMERA > | |
| Point3Vector | gtsam::calibrateMeasurements (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements) |
| template<class CAMERA = SphericalCamera> | |
| Point3Vector | gtsam::calibrateMeasurements (const CameraSet< SphericalCamera > &cameras, const SphericalCamera::MeasurementVector &measurements) |
| template<class CALIBRATION > | |
| Point3Vector | gtsam::calibrateMeasurementsShared (const CALIBRATION &cal, const Point2Vector &measurements) |
| template<class CALIBRATION > | |
| Cal3_S2 | gtsam::createPinholeCalibration (const CALIBRATION &cal) |
| Point3 | gtsam::optimize (const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey) |
| template<class CAMERA > | |
| std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 > > | gtsam::projectionMatricesFromCameras (const CameraSet< CAMERA > &cameras) |
| template<class CALIBRATION > | |
| std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 > > | gtsam::projectionMatricesFromPoses (const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal) |
| Point3 | gtsam::triangulateDLT (const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol) |
| Point3 | gtsam::triangulateDLT (const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const std::vector< Unit3 > &measurements, double rank_tol) |
| Vector4 | gtsam::triangulateHomogeneousDLT (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 std::vector< Unit3 > &measurements, double rank_tol) |
| Point3 | gtsam::triangulateLOST (const std::vector< Pose3 > &poses, const Point3Vector &calibratedMeasurements, const SharedIsotropic &measurementNoise, double rank_tol=1e-9) |
| Triangulation using the LOST (Linear Optimal Sine Triangulation) algorithm proposed in https://arxiv.org/pdf/2205.12197.pdf by Sebastien Henry and John Christian. More... | |
| template<class CAMERA > | |
| Point3 | gtsam::triangulateNonlinear (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, const Point3 &initialEstimate, const SharedNoiseModel &model=nullptr) |
| template<class CALIBRATION > | |
| Point3 | gtsam::triangulateNonlinear (const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, const Point3 &initialEstimate, const SharedNoiseModel &model=nullptr) |
| template<class CAMERA > | |
| Point3 | gtsam::triangulatePoint3 (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, double rank_tol=1e-9, bool optimize=false, const SharedNoiseModel &model=nullptr, const bool useLOST=false) |
| template<class CALIBRATION > | |
| Point3 | gtsam::triangulatePoint3 (const CameraSet< PinholeCamera< CALIBRATION >> &cameras, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false, const SharedNoiseModel &model=nullptr, const bool useLOST=false) |
| Pinhole-specific version. More... | |
| template<class CALIBRATION > | |
| Point3 | gtsam::triangulatePoint3 (const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false, const SharedNoiseModel &model=nullptr, const bool useLOST=false) |
| template<class CAMERA > | |
| TriangulationResult | gtsam::triangulateSafe (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms) |
| triangulateSafe: extensive checking of the outcome More... | |
| template<class CAMERA > | |
| std::pair< NonlinearFactorGraph, Values > | gtsam::triangulationGraph (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements, Key landmarkKey, const Point3 &initialEstimate, const SharedNoiseModel &model=nullptr) |
| template<class CALIBRATION > | |
| std::pair< NonlinearFactorGraph, Values > | gtsam::triangulationGraph (const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, Key landmarkKey, const Point3 &initialEstimate, const SharedNoiseModel &model=noiseModel::Unit::Create(2)) |
| template<class CALIBRATION , class MEASUREMENT > | |
| MEASUREMENT | gtsam::undistortMeasurementInternal (const CALIBRATION &cal, const MEASUREMENT &measurement, std::optional< Cal3_S2 > pinholeCal={}) |
| template<> | |
| Point2Vector | gtsam::undistortMeasurements (const Cal3_S2 &cal, const Point2Vector &measurements) |
| template<class CALIBRATION > | |
| Point2Vector | gtsam::undistortMeasurements (const CALIBRATION &cal, const Point2Vector &measurements) |
| template<class CAMERA > | |
| CAMERA::MeasurementVector | gtsam::undistortMeasurements (const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements) |
| template<class CAMERA = PinholeCamera<Cal3_S2>> | |
| PinholeCamera< Cal3_S2 >::MeasurementVector | gtsam::undistortMeasurements (const CameraSet< PinholeCamera< Cal3_S2 >> &cameras, const PinholeCamera< Cal3_S2 >::MeasurementVector &measurements) |
| template<class CAMERA = SphericalCamera> | |
| SphericalCamera::MeasurementVector | gtsam::undistortMeasurements (const CameraSet< SphericalCamera > &cameras, const SphericalCamera::MeasurementVector &measurements) |
Functions for triangulation.
Definition in file triangulation.h.