Public Member Functions | Private Types | List of all members
gtsam::PinholeSet< CAMERA > Class Template Reference

#include <PinholeSet.h>

Inheritance diagram for gtsam::PinholeSet< CAMERA >:
Inheritance graph
[legend]

Public Member Functions

TriangulationResult triangulateSafe (const typename CAMERA::MeasurementVector &measured, const TriangulationParameters &params) const
 triangulateSafe More...
 
virtual ~PinholeSet ()
 
Testable
void print (const std::string &s="") const override
 print More...
 
bool equals (const PinholeSet &p, double tol=1e-9) const
 equals More...
 
- Public Member Functions inherited from gtsam::CameraSet< CAMERA >
bool equals (const CameraSet &p, double tol=1e-9) const
 equals More...
 
template<class POINT >
ZVector project2 (const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
 
template<class POINT , class... OptArgs>
ZVector project2 (const POINT &point, OptArgs &... args) const
 
template<class POINT >
Vector reprojectionError (const POINT &point, const ZVector &measured, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
 Calculate vector [project2(point)-z] of re-projection errors. More...
 
template<class POINT , class... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
Vector reprojectionError (const POINT &point, const ZVector &measured, OptArgs &... args) const
 
virtual ~CameraSet ()=default
 Destructor. More...
 

Private Types

typedef CameraSet< CAMERA > Base
 
typedef PinholeSet< CAMERA > This
 

Additional Inherited Members

- Public Types inherited from gtsam::CameraSet< CAMERA >
using FBlocks = std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > >
 
using MatrixZD = Eigen::Matrix< double, ZDim, D >
 Definitions for blocks of F. More...
 
- Static Public Member Functions inherited from gtsam::CameraSet< CAMERA >
template<int N>
static void ComputePointCovariance (Eigen::Matrix< double, N, N > &P, const Matrix &E, double lambda, bool diagonalDamping=false)
 Computes Point Covariance P, with lambda parameter. More...
 
static Matrix PointCov (const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
 Computes Point Covariance P, with lambda parameter, dynamic version. More...
 
template<int N, int ND>
static SymmetricBlockMatrix SchurComplement (const std::vector< Eigen::Matrix< double, ZDim, ND >, Eigen::aligned_allocator< Eigen::Matrix< double, ZDim, ND >>> &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
 
template<int N>
static SymmetricBlockMatrix SchurComplement (const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
 
static SymmetricBlockMatrix SchurComplement (const FBlocks &Fblocks, const Matrix &E, const Vector &b, const double lambda=0.0, bool diagonalDamping=false)
 
template<int N, int ND, int NDD>
static SymmetricBlockMatrix SchurComplementAndRearrangeBlocks (const std::vector< Eigen::Matrix< double, ZDim, ND >, Eigen::aligned_allocator< Eigen::Matrix< double, ZDim, ND >>> &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &jacobianKeys, const KeyVector &hessianKeys)
 
template<int N>
static void UpdateSchurComplement (const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &allKeys, const KeyVector &keys, SymmetricBlockMatrix &augmentedHessian)
 
- Protected Types inherited from gtsam::CameraSet< CAMERA >
using Base = std::vector< CAMERA, typename Eigen::aligned_allocator< CAMERA > >
 
typedef CAMERA::Measurement Z
 
typedef CAMERA::MeasurementVector ZVector
 
- Static Protected Member Functions inherited from gtsam::CameraSet< CAMERA >
static Vector ErrorVector (const ZVector &predicted, const ZVector &measured)
 Make a vector of re-projection errors. More...
 
- Static Protected Attributes inherited from gtsam::CameraSet< CAMERA >
static const int D = traits<CAMERA>::dimension
 Camera dimension. More...
 
static const int ZDim = traits<Z>::dimension
 Measurement dimension. More...
 

Detailed Description

template<class CAMERA>
class gtsam::PinholeSet< CAMERA >

PinholeSet: triangulates point and keeps an estimate of it around.

Definition at line 29 of file PinholeSet.h.

Member Typedef Documentation

◆ Base

template<class CAMERA>
typedef CameraSet<CAMERA> gtsam::PinholeSet< CAMERA >::Base
private

Definition at line 32 of file PinholeSet.h.

◆ This

template<class CAMERA>
typedef PinholeSet<CAMERA> gtsam::PinholeSet< CAMERA >::This
private

Definition at line 33 of file PinholeSet.h.

Constructor & Destructor Documentation

◆ ~PinholeSet()

template<class CAMERA>
virtual gtsam::PinholeSet< CAMERA >::~PinholeSet ( )
inlinevirtual

Virtual destructor

Definition at line 40 of file PinholeSet.h.

Member Function Documentation

◆ equals()

template<class CAMERA>
bool gtsam::PinholeSet< CAMERA >::equals ( const PinholeSet< CAMERA > &  p,
double  tol = 1e-9 
) const
inline

equals

Definition at line 52 of file PinholeSet.h.

◆ print()

template<class CAMERA>
void gtsam::PinholeSet< CAMERA >::print ( const std::string &  s = "") const
inlineoverridevirtual

print

Reimplemented from gtsam::CameraSet< CAMERA >.

Definition at line 47 of file PinholeSet.h.

◆ triangulateSafe()

template<class CAMERA>
TriangulationResult gtsam::PinholeSet< CAMERA >::triangulateSafe ( const typename CAMERA::MeasurementVector &  measured,
const TriangulationParameters params 
) const
inline

triangulateSafe

Definition at line 59 of file PinholeSet.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:06