Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Friends | List of all members
gtsam::GaussianConditional Class Reference

#include <GaussianConditional.h>

Inheritance diagram for gtsam::GaussianConditional:
Inheritance graph
[legend]

Public Types

typedef Conditional< BaseFactor, ThisBaseConditional
 Typedef to our conditional base class. More...
 
typedef JacobianFactor BaseFactor
 Typedef to our factor base class. More...
 
typedef boost::shared_ptr< Thisshared_ptr
 shared_ptr to this class More...
 
typedef GaussianConditional This
 Typedef to this class. More...
 
- 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...
 
- Public Types inherited from gtsam::Conditional< JacobianFactor, GaussianConditional >
typedef boost::iterator_range< typename JacobianFactor::const_iteratorFrontals
 
typedef boost::iterator_range< typename JacobianFactor::const_iteratorParents
 

Public Member Functions

const constBVector d () const
 
bool equals (const GaussianFactor &cg, double tol=1e-9) const override
 
 GaussianConditional ()
 
 GaussianConditional (Key key, const Vector &d, const Matrix &R, const SharedDiagonal &sigmas=SharedDiagonal())
 
 GaussianConditional (Key key, const Vector &d, const Matrix &R, Key name1, const Matrix &S, const SharedDiagonal &sigmas=SharedDiagonal())
 
 GaussianConditional (Key key, const Vector &d, const Matrix &R, Key name1, const Matrix &S, Key name2, const Matrix &T, const SharedDiagonal &sigmas=SharedDiagonal())
 
template<typename TERMS >
 GaussianConditional (const TERMS &terms, size_t nrFrontals, const Vector &d, const SharedDiagonal &sigmas=SharedDiagonal())
 
template<typename KEYS >
 GaussianConditional (const KEYS &keys, size_t nrFrontals, const VerticalBlockMatrix &augmentedMatrix, const SharedDiagonal &sigmas=SharedDiagonal())
 
void print (const std::string &="GaussianConditional", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 
constABlock R () const
 
constABlock S () const
 
constABlock S (const_iterator it) const
 
void scaleFrontalsBySigma (VectorValues &gy) const
 
VectorValues solve (const VectorValues &parents) const
 
VectorValues solveOtherRHS (const VectorValues &parents, const VectorValues &rhs) const
 
void solveTransposeInPlace (VectorValues &gy) const
 
- 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...
 
VectorValues gradientAtZero () const override
 A'*b for Jacobian. More...
 
void gradientAtZero (double *d) const override
 A'*b for Jacobian (raw memory version) More...
 
std::map< Key, MatrixhessianBlockDiagonal () const override
 Return the block diagonal of the Hessian for this factor. More...
 
void hessianDiagonal (double *d) const override
 Raw memory access version of hessianDiagonal. 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 VectorValues &x, VectorValues &y) const override
 
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 ()
 
- Public Member Functions inherited from gtsam::Conditional< JacobianFactor, GaussianConditional >
void print (const std::string &s="Conditional", const KeyFormatter &formatter=DefaultKeyFormatter) const
 
bool equals (const This &c, double tol=1e-9) const
 
size_t nrFrontals () const
 
size_t nrParents () const
 
Key firstFrontalKey () const
 
Frontals frontals () const
 
Parents parents () const
 
JacobianFactor::const_iterator beginFrontals () const
 
JacobianFactor::const_iterator endFrontals () const
 
JacobianFactor::const_iterator beginParents () const
 
JacobianFactor::const_iterator endParents () const
 
size_tnrFrontals ()
 
JacobianFactor::iterator beginFrontals ()
 
JacobianFactor::iterator endFrontals ()
 
JacobianFactor::iterator beginParents ()
 
JacobianFactor::iterator endParents ()
 

Static Public Member Functions

template<typename ITERATOR >
static shared_ptr Combine (ITERATOR firstConditional, ITERATOR lastConditional)
 
- Static Public Member Functions inherited from gtsam::GaussianFactor
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::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...
 
- Protected Member Functions inherited from gtsam::Conditional< JacobianFactor, GaussianConditional >
 Conditional ()
 
 Conditional (size_t nrFrontals)
 
- 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...
 
- Protected Attributes inherited from gtsam::Conditional< JacobianFactor, GaussianConditional >
size_t nrFrontals_
 

Detailed Description

A conditional Gaussian functions as the node in a Bayes network It has a set of parents y,z, etc. and implements a probability density on x. The negative log-probability is given by $ \frac{1}{2} |Rx - (d - Sy - Tz - ...)|^2 $

Definition at line 36 of file GaussianConditional.h.

Member Typedef Documentation

Typedef to our conditional base class.

Definition at line 44 of file GaussianConditional.h.

Typedef to our factor base class.

Definition at line 43 of file GaussianConditional.h.

typedef boost::shared_ptr<This> gtsam::GaussianConditional::shared_ptr

shared_ptr to this class

Definition at line 42 of file GaussianConditional.h.

Typedef to this class.

Definition at line 41 of file GaussianConditional.h.

Constructor & Destructor Documentation

gtsam::GaussianConditional::GaussianConditional ( )
inline

default constructor needed for serialization

Definition at line 47 of file GaussianConditional.h.

gtsam::GaussianConditional::GaussianConditional ( Key  key,
const Vector d,
const Matrix R,
const SharedDiagonal sigmas = SharedDiagonal() 
)

constructor with no parents |Rx-d|

Definition at line 42 of file GaussianConditional.cpp.

gtsam::GaussianConditional::GaussianConditional ( Key  key,
const Vector d,
const Matrix R,
Key  name1,
const Matrix S,
const SharedDiagonal sigmas = SharedDiagonal() 
)

constructor with only one parent |Rx+Sy-d|

Definition at line 47 of file GaussianConditional.cpp.

gtsam::GaussianConditional::GaussianConditional ( Key  key,
const Vector d,
const Matrix R,
Key  name1,
const Matrix S,
Key  name2,
const Matrix T,
const SharedDiagonal sigmas = SharedDiagonal() 
)

constructor with two parents |Rx+Sy+Tz-d|

Definition at line 53 of file GaussianConditional.cpp.

template<typename TERMS >
gtsam::GaussianConditional::GaussianConditional ( const TERMS &  terms,
size_t  nrFrontals,
const Vector d,
const SharedDiagonal sigmas = SharedDiagonal() 
)

Constructor with arbitrary number of frontals and parents.

Template Parameters
TERMSA container whose value type is std::pair<Key, Matrix>, specifying the collection of keys and matrices making up the conditional.

Definition at line 26 of file GaussianConditional-inl.h.

template<typename KEYS >
gtsam::GaussianConditional::GaussianConditional ( const KEYS &  keys,
size_t  nrFrontals,
const VerticalBlockMatrix augmentedMatrix,
const SharedDiagonal sigmas = SharedDiagonal() 
)

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.

Definition at line 32 of file GaussianConditional-inl.h.

Member Function Documentation

template<typename ITERATOR >
static shared_ptr gtsam::GaussianConditional::Combine ( ITERATOR  firstConditional,
ITERATOR  lastConditional 
)
static

Combine several GaussianConditional into a single dense GC. The conditionals enumerated by first and last must be in increasing order, meaning that the parents of any conditional may not include a conditional coming before it.

Parameters
firstConditionalIterator to the first conditional to combine, must dereference to a shared_ptr<GaussianConditional>.
lastConditionalIterator to after the last conditional to combine, must dereference to a shared_ptr<GaussianConditional>.
const constBVector gtsam::GaussianConditional::d ( ) const
inline

Get a view of the r.h.s. vector d

Definition at line 106 of file GaussianConditional.h.

bool gtsam::GaussianConditional::equals ( const GaussianFactor cg,
double  tol = 1e-9 
) const
overridevirtual

equals function

Implements gtsam::GaussianFactor.

Definition at line 78 of file GaussianConditional.cpp.

void gtsam::GaussianConditional::print ( const std::string &  s = "GaussianConditional",
const KeyFormatter formatter = DefaultKeyFormatter 
) const
overridevirtual

print

Implements gtsam::GaussianFactor.

Reimplemented in gtsam::GaussianDensity.

Definition at line 59 of file GaussianConditional.cpp.

constABlock gtsam::GaussianConditional::R ( ) const
inline

Return a view of the upper-triangular R block of the conditional

Definition at line 97 of file GaussianConditional.h.

constABlock gtsam::GaussianConditional::S ( ) const
inline

Get a view of the parent blocks.

Definition at line 100 of file GaussianConditional.h.

constABlock gtsam::GaussianConditional::S ( const_iterator  it) const
inline

Get a view of the S matrix for the variable pointed to by the given key iterator

Definition at line 103 of file GaussianConditional.h.

void gtsam::GaussianConditional::scaleFrontalsBySigma ( VectorValues gy) const

Scale the values in gy according to the sigmas for the frontal variables in this conditional.

Definition at line 196 of file GaussianConditional.cpp.

template<class Archive >
void gtsam::GaussianConditional::serialize ( Archive &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 139 of file GaussianConditional.h.

VectorValues gtsam::GaussianConditional::solve ( const VectorValues parents) const

Solves a conditional Gaussian and writes the solution into the entries of x for each frontal variable of the conditional. The parents are assumed to have already been solved in and their values are read from x. This function works for multiple frontal variables.

Given the Gaussian conditional with log likelihood $ |R x_f - (d - S x_s)|^2 $, where $ f $ are the frontal variables and $ s $ are the separator variables of this conditional, this solve function computes $ x_f = R^{-1} (d - S x_s) $ using back-substitution.

Parameters
parentsVectorValues containing solved parents $ x_s $.

Definition at line 118 of file GaussianConditional.cpp.

VectorValues gtsam::GaussianConditional::solveOtherRHS ( const VectorValues parents,
const VectorValues rhs 
) const

Definition at line 145 of file GaussianConditional.cpp.

void gtsam::GaussianConditional::solveTransposeInPlace ( VectorValues gy) const

Performs transpose backsubstition in place on values

Definition at line 173 of file GaussianConditional.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 137 of file GaussianConditional.h.


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


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