Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Static Protected Member Functions | Static Protected Attributes | 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

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

Public Member Functions

 Base ()=default
 
 Base (const Base &)=delete
 
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, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
 
template<class POINT , class... OptArgs>
std::enable_if<(sizeof...(OptArgs) !=0), ZVector >::type 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...
 

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...
 
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>
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, 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

using Base = std::vector< CAMERA, typename Eigen::aligned_allocator< CAMERA > >
 
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...
 

Detailed Description

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

A set of cameras, all with their own calibration.

Definition at line 36 of file CameraSet.h.

Member Typedef Documentation

◆ Base

template<class CAMERA >
using gtsam::CameraSet< CAMERA >::Base = std::vector<CAMERA, typename Eigen::aligned_allocator<CAMERA> >
protected

Definition at line 38 of file CameraSet.h.

◆ FBlocks

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

Definition at line 78 of file CameraSet.h.

◆ MatrixZD

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

Definitions for blocks of F.

Definition at line 77 of file CameraSet.h.

◆ Z

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 44 of file CameraSet.h.

◆ ZVector

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

Definition at line 45 of file CameraSet.h.

Constructor & Destructor Documentation

◆ ~CameraSet()

template<class CAMERA >
virtual gtsam::CameraSet< CAMERA >::~CameraSet ( )
virtualdefault

Destructor.

Member Function Documentation

◆ Base() [1/2]

template<class CAMERA >
Base::Base
default

◆ Base() [2/2]

template<class CAMERA >
Base::Base
delete

◆ ComputePointCovariance()

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.

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 343 of file CameraSet.h.

◆ equals()

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

equals

Definition at line 91 of file CameraSet.h.

◆ ErrorVector()

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 51 of file CameraSet.h.

◆ PointCov()

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 359 of file CameraSet.h.

◆ print()

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 85 of file CameraSet.h.

◆ project2() [1/2]

template<class CAMERA >
template<class POINT >
ZVector gtsam::CameraSet< CAMERA >::project2 ( const POINT &  point,
FBlocks Fs = nullptr,
Matrix E = nullptr 
) 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 108 of file CameraSet.h.

◆ project2() [2/2]

template<class CAMERA >
template<class POINT , class... OptArgs>
std::enable_if<(sizeof...(OptArgs) != 0), ZVector>::type gtsam::CameraSet< CAMERA >::project2 ( const POINT &  point,
OptArgs &...  args 
) const
inline

An overload of the project2 function to accept full matrices and vectors and pass it to the pointer version of the function.

Use SFINAE to resolve overload ambiguity.

Definition at line 141 of file CameraSet.h.

◆ reprojectionError() [1/2]

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

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

Definition at line 149 of file CameraSet.h.

◆ reprojectionError() [2/2]

template<class CAMERA >
template<class POINT , class... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
Vector gtsam::CameraSet< CAMERA >::reprojectionError ( const POINT &  point,
const ZVector measured,
OptArgs &...  args 
) const
inline

An overload o the reprojectionError function to accept full matrices and vectors and pass it to the pointer version of the function

Definition at line 160 of file CameraSet.h.

◆ SchurComplement() [1/2]

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 376 of file CameraSet.h.

◆ SchurComplement() [2/2]

template<class CAMERA >
template<int N, int ND>
static SymmetricBlockMatrix gtsam::CameraSet< CAMERA >::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 
)
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 174 of file CameraSet.h.

◆ SchurComplementAndRearrangeBlocks()

template<class CAMERA >
template<int N, int ND, int NDD>
static SymmetricBlockMatrix gtsam::CameraSet< CAMERA >::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 
)
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) In this version, we allow for the case where the keys in the Jacobian are organized differently from the keys in the output SymmetricBlockMatrix In particular: each diagonal block of the Jacobian F captures 2 poses (useful for rolling shutter and extrinsic calibration) such that F keeps the block structure that makes the Schur complement trick fast.

N = 2 or 3 (point dimension), ND is the Jacobian block dimension, NDD is the Hessian block dimension

Definition at line 242 of file CameraSet.h.

◆ UpdateSchurComplement()

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 397 of file CameraSet.h.

Member Data Documentation

◆ D

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

Camera dimension.

Definition at line 47 of file CameraSet.h.

◆ ZDim

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

Measurement dimension.

Definition at line 48 of file CameraSet.h.


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


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:17:03