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

#include <RegularJacobianFactor.h>

Inheritance diagram for gtsam::RegularJacobianFactor< D >:
Inheritance graph
[legend]

Public Member Functions

VectorValues gradientAtZero () const override
 Expose base class gradientAtZero. More...
 
void gradientAtZero (double *d) const override
 Raw memory access version of gradientAtZero. More...
 
void hessianDiagonal (double *d) const override
 Raw memory access version of hessianDiagonal. More...
 
void multiplyHessianAdd (double alpha, const VectorValues &x, VectorValues &y) const override
 
void multiplyHessianAdd (double alpha, const double *x, double *y) const
 double* Hessian-vector multiply, i.e. y += A'*(A*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...
 
Vector operator* (const double *x) const
 double* Matrix-vector multiply, i.e. y = A*x RAW memory access! Assumes keys start at 0 and go to M-1, and x is laid out that way More...
 
 RegularJacobianFactor ()
 Default constructor. More...
 
template<typename TERMS >
 RegularJacobianFactor (const TERMS &terms, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
 
template<typename KEYS >
 RegularJacobianFactor (const KEYS &keys, const VerticalBlockMatrix &augmentedMatrix, const SharedDiagonal &sigmas=SharedDiagonal())
 
void transposeMultiplyAdd (double alpha, const Vector &e, double *x) const
 double* Transpose Matrix-vector multiply, i.e. x += A'*e RAW memory access! Assumes keys start at 0 and go to M-1, and y is laid out that way More...
 
- Public Member Functions inherited from gtsam::JacobianFactor
Matrix augmentedInformation () const override
 
Matrix augmentedJacobian () const override
 
Matrix augmentedJacobianUnweighted () const
 
GaussianFactor::shared_ptr clone () const override
 
size_t cols () const
 
std::pair< boost::shared_ptr< GaussianConditional >, shared_ptreliminate (const Ordering &keys)
 
bool empty () const override
 
bool equals (const GaussianFactor &lf, double tol=1e-9) const override
 
double error (const VectorValues &c) const override
 
Vector error_vector (const VectorValues &c) const
 
const SharedDiagonalget_model () const
 
SharedDiagonalget_model ()
 
constABlock getA (const_iterator variable) const
 
constABlock getA () const
 
ABlock getA (iterator variable)
 
ABlock getA ()
 
const constBVector getb () const
 
BVector getb ()
 
DenseIndex getDim (const_iterator variable) const override
 
Vector gradient (Key key, const VectorValues &x) const override
 Compute the gradient wrt a key at any values. More...
 
std::map< Key, MatrixhessianBlockDiagonal () const override
 Return the block diagonal of the Hessian for this factor. More...
 
void hessianDiagonalAdd (VectorValues &d) const override
 Add the current diagonal to a VectorValues instance. More...
 
Matrix information () const override
 
bool isConstrained () const
 
std::pair< Matrix, Vectorjacobian () const override
 Returns (dense) A,b pair associated with factor, bakes in the weights. More...
 
 JacobianFactor (const GaussianFactor &gf)
 
 JacobianFactor (const JacobianFactor &jf)
 
 JacobianFactor (const HessianFactor &hf)
 
 JacobianFactor ()
 
 JacobianFactor (const Vector &b_in)
 
 JacobianFactor (Key i1, const Matrix &A1, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
 
 JacobianFactor (Key i1, const Matrix &A1, Key i2, const Matrix &A2, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
 
 JacobianFactor (Key i1, const Matrix &A1, Key i2, const Matrix &A2, Key i3, const Matrix &A3, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
 
template<typename TERMS >
 JacobianFactor (const TERMS &terms, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
 
template<typename KEYS >
 JacobianFactor (const KEYS &keys, const VerticalBlockMatrix &augmentedMatrix, const SharedDiagonal &sigmas=SharedDiagonal())
 
 JacobianFactor (const GaussianFactorGraph &graph)
 
 JacobianFactor (const GaussianFactorGraph &graph, const VariableSlots &p_variableSlots)
 
 JacobianFactor (const GaussianFactorGraph &graph, const Ordering &ordering)
 
 JacobianFactor (const GaussianFactorGraph &graph, const Ordering &ordering, const VariableSlots &p_variableSlots)
 
std::pair< Matrix, VectorjacobianUnweighted () const
 Returns (dense) A,b pair associated with factor, does not bake in weights. More...
 
const VerticalBlockMatrixmatrixObject () const
 
VerticalBlockMatrixmatrixObject ()
 
void multiplyHessianAdd (double alpha, const double *x, double *y, const std::vector< size_t > &accumulatedDims) const
 
GaussianFactor::shared_ptr negate () const override
 
Vector operator* (const VectorValues &x) const
 
void print (const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 print More...
 
size_t rows () const
 
void setModel (bool anyConstrained, const Vector &sigmas)
 
boost::shared_ptr< GaussianConditionalsplitConditional (size_t nrFrontals)
 
void transposeMultiplyAdd (double alpha, const Vector &e, VectorValues &x) const
 
Vector unweighted_error (const VectorValues &c) const
 
void updateHessian (const KeyVector &keys, SymmetricBlockMatrix *info) const override
 
JacobianFactor whiten () const
 
 ~JacobianFactor () override
 
- 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...
 
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
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Private Types

typedef Eigen::Map< const DVectorConstDMap
 
typedef Eigen::Map< DVectorDMap
 
typedef Eigen::Matrix< double, D, 1 > DVector
 

Additional Inherited Members

- Public Types inherited from gtsam::JacobianFactor
typedef VerticalBlockMatrix::Block ABlock
 
typedef GaussianFactor Base
 Typedef to base class. More...
 
typedef ABlock::ColXpr BVector
 
typedef VerticalBlockMatrix::constBlock constABlock
 
typedef constABlock::ConstColXpr constBVector
 
typedef boost::shared_ptr< Thisshared_ptr
 shared_ptr to this class More...
 
typedef JacobianFactor 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...
 
- Static Public Member Functions inherited from gtsam::GaussianFactor
template<typename CONTAINER >
static DenseIndex Slot (const CONTAINER &keys, Key key)
 
- Protected Member Functions inherited from gtsam::JacobianFactor
template<typename TERMS >
void fillTerms (const TERMS &terms, const Vector &b, const SharedDiagonal &noiseModel)
 Internal function to fill blocks and set dimensions. More...
 
- 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)
 
- Protected Attributes inherited from gtsam::JacobianFactor
VerticalBlockMatrix Ab_
 
noiseModel::Diagonal::shared_ptr model_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

template<size_t D>
class gtsam::RegularJacobianFactor< D >

JacobianFactor with constant sized blocks Provides raw memory access versions of linear operator. Is base class for JacobianQFactor, JacobianFactorQR, and JacobianFactorSVD

Definition at line 32 of file RegularJacobianFactor.h.

Member Typedef Documentation

template<size_t D>
typedef Eigen::Map<const DVector> gtsam::RegularJacobianFactor< D >::ConstDMap
private

Definition at line 39 of file RegularJacobianFactor.h.

template<size_t D>
typedef Eigen::Map<DVector> gtsam::RegularJacobianFactor< D >::DMap
private

Definition at line 38 of file RegularJacobianFactor.h.

template<size_t D>
typedef Eigen::Matrix<double, D, 1> gtsam::RegularJacobianFactor< D >::DVector
private

Definition at line 37 of file RegularJacobianFactor.h.

Constructor & Destructor Documentation

template<size_t D>
gtsam::RegularJacobianFactor< D >::RegularJacobianFactor ( )
inline

Default constructor.

Definition at line 44 of file RegularJacobianFactor.h.

template<size_t D>
template<typename TERMS >
gtsam::RegularJacobianFactor< D >::RegularJacobianFactor ( const TERMS &  terms,
const Vector b,
const SharedDiagonal model = SharedDiagonal() 
)
inline

Construct an n-ary factor

Template Parameters
TERMSA container whose value type is std::pair<Key, Matrix>, specifying the collection of keys and matrices making up the factor. TODO Verify terms are regular

Definition at line 52 of file RegularJacobianFactor.h.

template<size_t D>
template<typename KEYS >
gtsam::RegularJacobianFactor< D >::RegularJacobianFactor ( const KEYS &  keys,
const VerticalBlockMatrix augmentedMatrix,
const SharedDiagonal sigmas = SharedDiagonal() 
)
inline

Constructor with arbitrary number keys, and where the augmented matrix is given all together instead of in block terms. Note that only the active view of the provided augmented matrix is used, and that the matrix data is copied into a newly-allocated matrix in the constructed factor. TODO Verify complies to regular

Definition at line 64 of file RegularJacobianFactor.h.

Member Function Documentation

template<size_t D>
VectorValues gtsam::RegularJacobianFactor< D >::gradientAtZero ( ) const
inlineoverridevirtual

Expose base class gradientAtZero.

Reimplemented from gtsam::JacobianFactor.

Definition at line 128 of file RegularJacobianFactor.h.

template<size_t D>
void gtsam::RegularJacobianFactor< D >::gradientAtZero ( double *  d) const
inlineoverridevirtual

Raw memory access version of gradientAtZero.

Reimplemented from gtsam::JacobianFactor.

Definition at line 133 of file RegularJacobianFactor.h.

template<size_t D>
void gtsam::RegularJacobianFactor< D >::hessianDiagonal ( double *  d) const
inlineoverridevirtual

Raw memory access version of hessianDiagonal.

Reimplemented from gtsam::JacobianFactor.

Definition at line 109 of file RegularJacobianFactor.h.

template<size_t D>
void gtsam::RegularJacobianFactor< D >::multiplyHessianAdd ( double  alpha,
const VectorValues x,
VectorValues y 
) const
inlineoverridevirtual

y += alpha * A'*A*x

Reimplemented from gtsam::JacobianFactor.

Definition at line 73 of file RegularJacobianFactor.h.

template<size_t D>
void gtsam::RegularJacobianFactor< D >::multiplyHessianAdd ( double  alpha,
const double *  x,
double *  y 
) const
inline

double* Hessian-vector multiply, i.e. y += A'*(A*x) RAW memory access! Assumes keys start at 0 and go to M-1, and x and and y are laid out that way

Definition at line 82 of file RegularJacobianFactor.h.

template<size_t D>
Vector gtsam::RegularJacobianFactor< D >::operator* ( const double *  x) const
inline

double* Matrix-vector multiply, i.e. y = A*x RAW memory access! Assumes keys start at 0 and go to M-1, and x is laid out that way

Definition at line 172 of file RegularJacobianFactor.h.

template<size_t D>
void gtsam::RegularJacobianFactor< D >::transposeMultiplyAdd ( double  alpha,
const Vector e,
double *  x 
) const
inline

double* Transpose Matrix-vector multiply, i.e. x += A'*e RAW memory access! Assumes keys start at 0 and go to M-1, and y is laid out that way

Definition at line 161 of file RegularJacobianFactor.h.


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


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