#include <GaussianFactor.h>
Public Types | |
typedef Factor | Base |
Our base class. More... | |
typedef boost::shared_ptr< This > | shared_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 Member Functions | |
virtual Matrix | augmentedInformation () const =0 |
virtual Matrix | augmentedJacobian () const =0 |
virtual GaussianFactor::shared_ptr | clone () const =0 |
virtual bool | empty () const =0 |
virtual bool | equals (const GaussianFactor &lf, double tol=1e-9) const =0 |
virtual double | error (const VectorValues &c) const =0 |
GaussianFactor () | |
template<typename CONTAINER > | |
GaussianFactor (const CONTAINER &keys) | |
virtual DenseIndex | getDim (const_iterator variable) const =0 |
virtual Vector | gradient (Key key, const VectorValues &x) const =0 |
Gradient wrt a key at any values. More... | |
virtual VectorValues | gradientAtZero () const =0 |
A'*b for Jacobian, eta for Hessian. More... | |
virtual void | gradientAtZero (double *d) const =0 |
Raw memory access version of gradientAtZero. More... | |
virtual std::map< Key, Matrix > | hessianBlockDiagonal () const =0 |
Return the block diagonal of the Hessian for this factor. More... | |
VectorValues | hessianDiagonal () const |
Return the diagonal of the Hessian for this factor. More... | |
virtual void | hessianDiagonal (double *d) const =0 |
Raw memory access version of hessianDiagonal. More... | |
virtual void | hessianDiagonalAdd (VectorValues &d) const =0 |
Add the current diagonal to a VectorValues instance. More... | |
virtual Matrix | information () const =0 |
virtual std::pair< Matrix, Vector > | jacobian () const =0 |
virtual void | multiplyHessianAdd (double alpha, const VectorValues &x, VectorValues &y) const =0 |
y += alpha * A'*A*x More... | |
virtual GaussianFactor::shared_ptr | negate () const =0 |
void | print (const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override=0 |
print More... | |
virtual void | updateHessian (const KeyVector &keys, SymmetricBlockMatrix *info) const =0 |
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 KeyVector & | keys () 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... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Static Public Member Functions | |
template<typename CONTAINER > | |
static DenseIndex | Slot (const CONTAINER &keys, Key key) |
Private Member Functions | |
template<class ARCHIVE > | |
void | serialize (ARCHIVE &ar, const unsigned int) |
Friends | |
class | boost::serialization::access |
Additional Inherited Members | |
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::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
An abstract virtual base class for JacobianFactor and HessianFactor. A GaussianFactor has a quadratic error function. GaussianFactor is non-mutable (all methods const!). The factor value is exp(-0.5*||Ax-b||^2)
Definition at line 38 of file GaussianFactor.h.
typedef Factor gtsam::GaussianFactor::Base |
Our base class.
Definition at line 43 of file GaussianFactor.h.
typedef boost::shared_ptr<This> gtsam::GaussianFactor::shared_ptr |
shared_ptr to this class
Definition at line 42 of file GaussianFactor.h.
This class.
Definition at line 41 of file GaussianFactor.h.
|
inline |
Default constructor creates empty factor
Definition at line 46 of file GaussianFactor.h.
|
inline |
Construct from container of keys. This constructor is used internally from derived factor constructors, either from a container of keys or from a boost::assign::list_of.
Definition at line 51 of file GaussianFactor.h.
|
inlinevirtual |
Destructor
Definition at line 54 of file GaussianFactor.h.
|
pure virtual |
Return the augmented information matrix represented by this GaussianFactor. The augmented information matrix contains the information matrix with an additional column holding the information vector, and an additional row holding the transpose of the information vector. The lower-right entry contains the constant error term (when ). The augmented information matrix is described in more detail in HessianFactor, which in fact stores an augmented information matrix.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
|
pure virtual |
Return a dense Jacobian matrix, augmented with b with the noise models baked into A and b. The negative log-likelihood is . See also GaussianFactorGraph::jacobian and GaussianFactorGraph::sparseJacobian.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
|
pure virtual |
Clone a factor (make a deep copy)
Implemented in gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::HessianFactor, gtsam::JacobianFactor, gtsam::LinearInequality, gtsam::LinearEquality, gtsam::LinearCost, and gtsam::DummyFactor< CAMERA >.
|
pure virtual |
Test whether the factor is empty
Implemented in gtsam::JacobianFactor, gtsam::RegularImplicitSchurFactor< CAMERA >, and gtsam::HessianFactor.
|
pure virtual |
Equals for testable
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, gtsam::LinearInequality, gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::GaussianConditional, gtsam::LinearEquality, and gtsam::LinearCost.
|
pure virtual |
Print for testable
Implemented in gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::HessianFactor, gtsam::JacobianFactor, gtsam::LinearInequality, gtsam::LinearEquality, and gtsam::LinearCost.
|
pure virtual |
0.5*(A*x-b)'D(A*x-b) Return the dimension of the variable pointed to by the given key iterator
Implemented in gtsam::JacobianFactor, gtsam::HessianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
|
pure virtual |
Gradient wrt a key at any values.
Implemented in gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::JacobianFactor, and gtsam::HessianFactor.
|
pure virtual |
A'*b for Jacobian, eta for Hessian.
Implemented in gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::JacobianFactor, gtsam::HessianFactor, and gtsam::RegularJacobianFactor< D >.
|
pure virtual |
Raw memory access version of gradientAtZero.
Implemented in gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::JacobianFactor, gtsam::HessianFactor, gtsam::RegularHessianFactor< D >, and gtsam::RegularJacobianFactor< D >.
Return the block diagonal of the Hessian for this factor.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
VectorValues gtsam::GaussianFactor::hessianDiagonal | ( | ) | const |
Return the diagonal of the Hessian for this factor.
Definition at line 27 of file GaussianFactor.cpp.
|
pure virtual |
Raw memory access version of hessianDiagonal.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, gtsam::RegularHessianFactor< D >, gtsam::RegularImplicitSchurFactor< CAMERA >, and gtsam::RegularJacobianFactor< D >.
|
pure virtual |
Add the current diagonal to a VectorValues instance.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
|
pure virtual |
Return the non-augmented information matrix represented by this GaussianFactor.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
Return the dense Jacobian and right-hand-side , with the noise models baked into A and b. The negative log-likelihood is . See also GaussianFactorGraph::augmentedJacobian and GaussianFactorGraph::sparseJacobian.
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, and gtsam::RegularImplicitSchurFactor< CAMERA >.
|
pure virtual |
y += alpha * A'*A*x
Implemented in gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::HessianFactor, gtsam::JacobianFactor, gtsam::RegularHessianFactor< D >, and gtsam::RegularJacobianFactor< D >.
|
pure virtual |
Construct the corresponding anti-factor to negate information stored stored in this factor.
Implemented in gtsam::JacobianFactor, gtsam::RegularImplicitSchurFactor< CAMERA >, and gtsam::HessianFactor.
|
overridepure virtual |
Reimplemented from gtsam::Factor.
Implemented in gtsam::JacobianFactor, gtsam::HessianFactor, gtsam::LinearInequality, gtsam::LinearEquality, gtsam::LinearCost, gtsam::GaussianConditional, gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::GaussianDensity, and gtsam::DummyFactor< CAMERA >.
|
inlineprivate |
Definition at line 160 of file GaussianFactor.h.
|
inlinestatic |
Definition at line 152 of file GaussianFactor.h.
|
pure virtual |
Update an information matrix by adding the information corresponding to this factor (used internally during elimination).
scatter | A mapping from variable index to slot index in this HessianFactor |
info | The information matrix to be updated |
Implemented in gtsam::HessianFactor, gtsam::JacobianFactor, gtsam::RegularImplicitSchurFactor< CAMERA >, and gtsam::BinaryJacobianFactor< M, N1, N2 >.
|
friend |
Serialization function
Definition at line 158 of file GaussianFactor.h.