Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Static Protected Member Functions | Static Protected Attributes | Private Member Functions | Friends | List of all members
gtsam::CameraSet< CAMERA > Class Template Reference

A set of cameras, all with their own calibration. More...

#include <CameraSet.h>

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

Public Types

typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
 
typedef Eigen::Matrix< double, ZDim, DMatrixZD
 Definitions for blocks of F. More...
 

Public Member Functions

bool equals (const CameraSet &p, double tol=1e-9) const
 equals More...
 
virtual void print (const std::string &s="") const
 
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...
 

Static Public Member Functions

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

typedef CAMERA::Measurement Z
 
typedef CAMERA::MeasurementVector ZVector
 

Static Protected Member Functions

static Vector ErrorVector (const ZVector &predicted, const ZVector &measured)
 Make a vector of re-projection errors. More...
 

Static Protected Attributes

static const int D = traits<CAMERA>::dimension
 Camera dimension. More...
 
static const int ZDim = traits<Z>::dimension
 Measurement dimension. More...
 

Private Member Functions

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

Friends

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

Detailed Description

template<class CAMERA>
class gtsam::CameraSet< CAMERA >

A set of cameras, all with their own calibration.

Definition at line 35 of file CameraSet.h.

Member Typedef Documentation

template<class CAMERA>
typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > gtsam::CameraSet< CAMERA >::FBlocks

Definition at line 74 of file CameraSet.h.

template<class CAMERA>
typedef Eigen::Matrix<double, ZDim, D> gtsam::CameraSet< CAMERA >::MatrixZD

Definitions for blocks of F.

Definition at line 73 of file CameraSet.h.

template<class CAMERA>
typedef CAMERA::Measurement gtsam::CameraSet< CAMERA >::Z
protected

2D measurement and noise model for each of the m views The order is kept the same as the keys that we use to create the factor.

Definition at line 43 of file CameraSet.h.

template<class CAMERA>
typedef CAMERA::MeasurementVector gtsam::CameraSet< CAMERA >::ZVector
protected

Definition at line 44 of file CameraSet.h.

Member Function Documentation

template<class CAMERA>
template<int N>
static void gtsam::CameraSet< CAMERA >::ComputePointCovariance ( Eigen::Matrix< double, N, N > &  P,
const Matrix E,
double  lambda,
bool  diagonalDamping = false 
)
inlinestatic

Computes Point Covariance P, with lambda parameter.

Definition at line 194 of file CameraSet.h.

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

equals

Definition at line 88 of file CameraSet.h.

template<class CAMERA>
static Vector gtsam::CameraSet< CAMERA >::ErrorVector ( const ZVector predicted,
const ZVector measured 
)
inlinestaticprotected

Make a vector of re-projection errors.

Definition at line 50 of file CameraSet.h.

template<class CAMERA>
static Matrix gtsam::CameraSet< CAMERA >::PointCov ( const Matrix E,
const double  lambda = 0.0,
bool  diagonalDamping = false 
)
inlinestatic

Computes Point Covariance P, with lambda parameter, dynamic version.

Definition at line 210 of file CameraSet.h.

template<class CAMERA>
virtual void gtsam::CameraSet< CAMERA >::print ( const std::string &  s = "") const
inlinevirtual

print

Parameters
soptional string naming the factor
keyFormatteroptional formatter useful for printing Symbols

Reimplemented in gtsam::PinholeSet< CAMERA >.

Definition at line 81 of file CameraSet.h.

template<class CAMERA>
template<class POINT >
ZVector gtsam::CameraSet< CAMERA >::project2 ( const POINT &  point,
boost::optional< FBlocks & >  Fs = boost::none,
boost::optional< Matrix & >  E = boost::none 
) const
inline

Project a point (possibly Unit3 at infinity), with derivatives Note that F is a sparse block-diagonal matrix, so instead of a large dense matrix this function returns the diagonal blocks. throws CheiralityException

Definition at line 107 of file CameraSet.h.

template<class CAMERA>
template<class POINT >
Vector gtsam::CameraSet< CAMERA >::reprojectionError ( const POINT &  point,
const ZVector measured,
boost::optional< FBlocks & >  Fs = boost::none,
boost::optional< Matrix & >  E = boost::none 
) const
inline

Calculate vector [project2(point)-z] of re-projection errors.

Definition at line 136 of file CameraSet.h.

template<class CAMERA>
template<int N>
static SymmetricBlockMatrix gtsam::CameraSet< CAMERA >::SchurComplement ( const FBlocks Fs,
const Matrix E,
const Eigen::Matrix< double, N, N > &  P,
const Vector b 
)
inlinestatic

Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * E' * F g = F' * (b - E * P * E' * b) Fixed size version

Definition at line 149 of file CameraSet.h.

template<class CAMERA>
static SymmetricBlockMatrix gtsam::CameraSet< CAMERA >::SchurComplement ( const FBlocks Fblocks,
const Matrix E,
const Vector b,
const double  lambda = 0.0,
bool  diagonalDamping = false 
)
inlinestatic

Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix Dynamic version

Definition at line 227 of file CameraSet.h.

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

Definition at line 317 of file CameraSet.h.

template<class CAMERA>
template<int N>
static void gtsam::CameraSet< CAMERA >::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 
)
inlinestatic

Applies Schur complement (exploiting block structure) to get a smart factor on cameras, and adds the contribution of the smart factor to a pre-allocated augmented Hessian.

Definition at line 246 of file CameraSet.h.

Friends And Related Function Documentation

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

Serialization function.

Definition at line 315 of file CameraSet.h.

Member Data Documentation

template<class CAMERA>
const int gtsam::CameraSet< CAMERA >::D = traits<CAMERA>::dimension
staticprotected

Camera dimension.

Definition at line 46 of file CameraSet.h.

template<class CAMERA>
const int gtsam::CameraSet< CAMERA >::ZDim = traits<Z>::dimension
staticprotected

Measurement dimension.

Definition at line 47 of file CameraSet.h.


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


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