Public Member Functions | Private Types | Private Member Functions | Friends | 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, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
 
template<class POINT >
Vector reprojectionError (const POINT &point, const ZVector &measured, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
 Calculate vector [project2(point)-z] of re-projection errors. More...
 

Private Types

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

Private Member Functions

template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int version)
 

Friends

class boost::serialization::access
 Serialization function. More...
 

Additional Inherited Members

- Public Types inherited from gtsam::CameraSet< CAMERA >
typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
 
typedef Eigen::Matrix< double, ZDim, DMatrixZD
 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>
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>
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 >
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 30 of file PinholeSet.h.

Member Typedef Documentation

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

Definition at line 33 of file PinholeSet.h.

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

Definition at line 34 of file PinholeSet.h.

Constructor & Destructor Documentation

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

Virtual destructor

Definition at line 41 of file PinholeSet.h.

Member Function Documentation

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

equals

Definition at line 53 of file PinholeSet.h.

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

print

Reimplemented from gtsam::CameraSet< CAMERA >.

Definition at line 48 of file PinholeSet.h.

template<class CAMERA>
template<class ARCHIVE >
void gtsam::PinholeSet< CAMERA >::serialize ( ARCHIVE &  ar,
const unsigned int  version 
)
inlineprivate

Definition at line 71 of file PinholeSet.h.

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

triangulateSafe

Definition at line 60 of file PinholeSet.h.

Friends And Related Function Documentation

template<class CAMERA>
friend class boost::serialization::access
friend

Serialization function.

Definition at line 69 of file PinholeSet.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:23