#include <RegularJacobianFactor.h>
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< std::shared_ptr< GaussianConditional >, shared_ptr > | eliminate (const Ordering &keys) |
bool | equals (const GaussianFactor &lf, double tol=1e-9) const override |
assert equality up to a tolerance More... | |
double | error (const VectorValues &c) const override |
Vector | error_vector (const VectorValues &c) const |
const SharedDiagonal & | get_model () const |
SharedDiagonal & | get_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, Matrix > | hessianBlockDiagonal () 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, Vector > | jacobian () 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, Vector > | jacobianUnweighted () const |
Returns (dense) A,b pair associated with factor, does not bake in weights. More... | |
const VerticalBlockMatrix & | matrixObject () const |
VerticalBlockMatrix & | matrixObject () |
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 with optional string More... | |
size_t | rows () const |
void | setModel (bool anyConstrained, const Vector &sigmas) |
std::shared_ptr< GaussianConditional > | splitConditional (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) | |
double | error (const HybridValues &c) const override |
VectorValues | hessianDiagonal () const |
Return the diagonal of the Hessian for this factor. More... | |
Public Member Functions inherited from gtsam::Factor | |
virtual | ~Factor ()=default |
Default destructor. More... | |
bool | empty () const |
Whether the factor is empty (involves zero variables). 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... | |
bool | equals (const This &other, double tol=1e-9) const |
check equality More... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Private Types | |
typedef Eigen::Map< const DVector > | ConstDMap |
typedef Eigen::Map< DVector > | DMap |
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 std::shared_ptr< This > | shared_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 std::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... | |
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) | |
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... | |
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.
|
private |
Definition at line 39 of file RegularJacobianFactor.h.
|
private |
Definition at line 38 of file RegularJacobianFactor.h.
|
private |
Definition at line 37 of file RegularJacobianFactor.h.
|
inline |
Default constructor.
Definition at line 44 of file RegularJacobianFactor.h.
|
inline |
Construct an n-ary factor
TERMS | A 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.
|
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.
|
inlineoverridevirtual |
Expose base class gradientAtZero.
Reimplemented from gtsam::JacobianFactor.
Definition at line 128 of file RegularJacobianFactor.h.
|
inlineoverridevirtual |
Raw memory access version of gradientAtZero.
Reimplemented from gtsam::JacobianFactor.
Definition at line 133 of file RegularJacobianFactor.h.
|
inlineoverridevirtual |
Raw memory access version of hessianDiagonal.
Reimplemented from gtsam::JacobianFactor.
Definition at line 109 of file RegularJacobianFactor.h.
|
inlineoverridevirtual |
y += alpha * A'*A*x
Reimplemented from gtsam::JacobianFactor.
Definition at line 73 of file RegularJacobianFactor.h.
|
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.
|
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.
|
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.