Public Types | Public Member Functions | Protected Attributes | List of all members
gtsam::DummyFactor< CAMERA > Class Template Reference

#include <DummyFactor.h>

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

Public Types

typedef std::pair< Key, Matrix2DKeyMatrix2D
 
typedef Eigen::Matrix< double, 2, CAMERA::dimension > Matrix2D
 
- Public Types inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
typedef std::vector< Vector2, Eigen::aligned_allocator< Vector2 > > Error2s
 
typedef boost::shared_ptr< Thisshared_ptr
 shared_ptr to this class More...
 
typedef RegularImplicitSchurFactor This
 Typedef to this class. More...
 
- Public Types inherited from gtsam::GaussianFactor
typedef Factor Base
 Our base class. More...
 
typedef boost::shared_ptr< Thisshared_ptr
 shared_ptr to this class More...
 
typedef GaussianFactor This
 This class. More...
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys. More...
 
typedef KeyVector::iterator iterator
 Iterator over keys. More...
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 

Public Member Functions

NonlinearFactor::shared_ptr clone () const override
 
size_t dim () const override
 
const std::vector< size_t > & dims () const
 
 DummyFactor ()
 
 DummyFactor ()
 
 DummyFactor (const std::vector< KeyMatrix2D > &Fblocks, const Matrix &E, const Matrix3 &P, const Vector &b)
 
 DummyFactor (const Key &key1, size_t dim1, const Key &key2, size_t dim2)
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const Values &c) const override
 
boost::shared_ptr< GaussianFactorlinearize (const Values &c) const override
 
void multiplyHessian (double alpha, const VectorValues &x, VectorValues &y) const
 Dummy version to measure overhead of key access. More...
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
 ~DummyFactor () override
 
virtual ~DummyFactor ()
 
- Public Member Functions inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
Matrix augmentedInformation () const override
 Compute full augmented information matrix More...
 
Matrix augmentedJacobian () const override
 
const Vectorb () const
 
const MatrixE () const
 
bool empty () const override
 
bool equals (const GaussianFactor &lf, double tol) const override
 equals More...
 
double error (const VectorValues &x) const override
 
double errorJF (const VectorValues &x) const
 
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > & FBlocks () const
 
DenseIndex getDim (const_iterator variable) const override
 Degrees of freedom of camera. More...
 
const MatrixgetPointCovariance () const
 
Vector gradient (Key key, const VectorValues &x) const override
 Gradient wrt a key at any values. More...
 
VectorValues gradientAtZero () const override
 
void gradientAtZero (double *d) const override
 
std::map< Key, MatrixhessianBlockDiagonal () const override
 Return the block diagonal of the Hessian for this factor. More...
 
void hessianDiagonal (double *d) const override
 add the contribution of this factor to the diagonal of the hessian d(output) = d(input) + deltaHessianFactor More...
 
void hessianDiagonalAdd (VectorValues &d) const override
 Add the diagonal of the Hessian for this factor to existing VectorValues. More...
 
Matrix information () const override
 Compute full information matrix More...
 
std::pair< Matrix, Vectorjacobian () const override
 
void multiplyHessianAdd (double alpha, const double *x, double *y) const
 double* Hessian-vector multiply, i.e. y += F'alpha(I - E*P*E')*F*x RAW memory access! Assumes keys start at 0 and go to M-1, and x and and y are laid out that way More...
 
void multiplyHessianAdd (double alpha, const double *x, double *y, std::vector< size_t > keys) const
 
void multiplyHessianAdd (double alpha, const VectorValues &x, VectorValues &y) const override
 Hessian-vector multiply, i.e. y += F'alpha(I - E*P*E')*F*x. More...
 
void multiplyHessianDummy (double alpha, const VectorValues &x, VectorValues &y) const
 Dummy version to measure overhead of key access. More...
 
GaussianFactor::shared_ptr negate () const override
 
void projectError (const Error2s &e1, Error2s &e2) const
 Calculate corrected error Q*e = (I - E*P*E')*e. More...
 
void projectError2 (const Error2s &e1, Error2s &e2) const
 Calculate corrected error Q*(e-ZDim*b) = (I - E*P*E')*(e-ZDim*b) More...
 
 RegularImplicitSchurFactor ()
 Constructor. More...
 
 RegularImplicitSchurFactor (const KeyVector &keys, const std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > &FBlocks, const Matrix &E, const Matrix &P, const Vector &b)
 Construct from blocks of F, E, inv(E'*E), and RHS vector b. More...
 
void updateHessian (const KeyVector &keys, SymmetricBlockMatrix *info) const override
 
 ~RegularImplicitSchurFactor () override
 Destructor. More...
 
- Public Member Functions inherited from gtsam::GaussianFactor
 GaussianFactor ()
 
template<typename CONTAINER >
 GaussianFactor (const CONTAINER &keys)
 
VectorValues hessianDiagonal () const
 Return the diagonal of the Hessian for this factor. More...
 
virtual ~GaussianFactor ()
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
Key front () const
 First key. More...
 
Key back () const
 Last key. More...
 
const_iterator find (Key key) const
 find More...
 
const KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 
virtual ~NonlinearFactor ()
 
virtual bool active (const Values &) const
 
shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
shared_ptr rekey (const KeyVector &new_keys) const
 

Protected Attributes

std::vector< size_tdims_
 
size_t rowDim_
 choose dimension for the rows More...
 
- Protected Attributes inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
const Vector b_
 2m-dimensional RHS vector More...
 
const Matrix E_
 The 2m*3 E Jacobian with respect to the point. More...
 
const std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks_
 All ZDim*D F blocks (one for each camera) More...
 
const Matrix PointCovariance_
 the 3*3 matrix P = inv(E'E) (2*2 if degenerate) More...
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
static void multiplyHessianAdd (const Matrix &F, const Matrix &E, const Matrix &PointCovariance, double alpha, const Vector &x, Vector &y)
 
- Static Public Member Functions inherited from gtsam::GaussianFactor
template<typename CONTAINER >
static DenseIndex Slot (const CONTAINER &keys, Key key)
 
- Public Attributes inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
Error2s e1
 Scratch space for multiplyHessianAdd. More...
 
Error2s e2
 
- Protected Types inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
typedef Eigen::Matrix< double, D, DMatrixDD
 camera hessian More...
 
typedef Eigen::Matrix< double, ZDim, DMatrixZD
 type of an F block More...
 
typedef CameraSet< CAMERA > Set
 
typedef CAMERA::Measurement Z
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 
- Static Protected Attributes inherited from gtsam::RegularImplicitSchurFactor< CAMERA >
static const int D = traits<CAMERA>::dimension
 Camera dimension. More...
 
static const int ZDim = traits<Z>::dimension
 Measurement dimension. More...
 

Detailed Description

template<typename CAMERA>
class gtsam::DummyFactor< CAMERA >

DummyFactor

Definition at line 17 of file gtsam_unstable/slam/DummyFactor.h.

Member Typedef Documentation

template<typename CAMERA >
typedef std::pair<Key, Matrix2D> gtsam::DummyFactor< CAMERA >::KeyMatrix2D

Definition at line 22 of file timing/DummyFactor.h.

template<typename CAMERA >
typedef Eigen::Matrix<double, 2, CAMERA::dimension> gtsam::DummyFactor< CAMERA >::Matrix2D

Definition at line 21 of file timing/DummyFactor.h.

Constructor & Destructor Documentation

template<typename CAMERA >
gtsam::DummyFactor< CAMERA >::DummyFactor ( )
inline

Default constructor: don't use directly

Definition at line 27 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
gtsam::DummyFactor< CAMERA >::DummyFactor ( const Key key1,
size_t  dim1,
const Key key2,
size_t  dim2 
)

standard binary constructor

Definition at line 17 of file DummyFactor.cpp.

template<typename CAMERA >
gtsam::DummyFactor< CAMERA >::~DummyFactor ( )
inlineoverride

Definition at line 32 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
gtsam::DummyFactor< CAMERA >::DummyFactor ( )
inline

Definition at line 24 of file timing/DummyFactor.h.

template<typename CAMERA >
gtsam::DummyFactor< CAMERA >::DummyFactor ( const std::vector< KeyMatrix2D > &  Fblocks,
const Matrix E,
const Matrix3 &  P,
const Vector b 
)
inline

Definition at line 27 of file timing/DummyFactor.h.

template<typename CAMERA >
virtual gtsam::DummyFactor< CAMERA >::~DummyFactor ( )
inlinevirtual

Definition at line 32 of file timing/DummyFactor.h.

Member Function Documentation

template<typename CAMERA >
NonlinearFactor::shared_ptr gtsam::DummyFactor< CAMERA >::clone ( ) const
inlineoverridevirtual

Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses

By default, throws exception if subclass does not implement the function.

Reimplemented from gtsam::NonlinearFactor.

Definition at line 65 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
size_t gtsam::DummyFactor< CAMERA >::dim ( ) const
inlineoverridevirtual

get the dimension of the factor (number of rows on linearization)

Implements gtsam::NonlinearFactor.

Definition at line 54 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
const std::vector<size_t>& gtsam::DummyFactor< CAMERA >::dims ( ) const
inline

Definition at line 44 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
bool gtsam::DummyFactor< CAMERA >::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
overridevirtual

Check if two factors are equal

Reimplemented from gtsam::NonlinearFactor.

Definition at line 36 of file DummyFactor.cpp.

template<typename CAMERA >
double gtsam::DummyFactor< CAMERA >::error ( const Values c) const
inlineoverridevirtual

Calculate the error of the factor - zero for dummy factors

Implements gtsam::NonlinearFactor.

Definition at line 51 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
boost::shared_ptr< GaussianFactor > gtsam::DummyFactor< CAMERA >::linearize ( const Values c) const
overridevirtual

linearize to a GaussianFactor

Implements gtsam::NonlinearFactor.

Definition at line 43 of file DummyFactor.cpp.

template<typename CAMERA >
void gtsam::DummyFactor< CAMERA >::multiplyHessian ( double  alpha,
const VectorValues x,
VectorValues y 
) const
inline

Dummy version to measure overhead of key access.

Definition at line 40 of file timing/DummyFactor.h.

template<typename CAMERA >
void gtsam::DummyFactor< CAMERA >::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtual

print

Reimplemented from gtsam::NonlinearFactor.

Definition at line 29 of file DummyFactor.cpp.

Member Data Documentation

template<typename CAMERA >
std::vector<size_t> gtsam::DummyFactor< CAMERA >::dims_
protected

Definition at line 21 of file gtsam_unstable/slam/DummyFactor.h.

template<typename CAMERA >
size_t gtsam::DummyFactor< CAMERA >::rowDim_
protected

choose dimension for the rows

Definition at line 22 of file gtsam_unstable/slam/DummyFactor.h.


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


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