GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gtsam::GaussianConditional Class Reference

#include <GaussianConditional.h>

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

Public Types

typedef GaussianConditional This
 Typedef to this class.
 
typedef std::shared_ptr< Thisshared_ptr
 shared_ptr to this class
 
typedef JacobianFactor BaseFactor
 Typedef to our factor base class.
 
typedef Conditional< BaseFactor, ThisBaseConditional
 Typedef to our conditional base class.
 
typedef GaussianFactor Base
 Typedef to base class.
 
typedef VerticalBlockMatrix::Block ABlock
 
typedef VerticalBlockMatrix::constBlock constABlock
 
typedef ABlock::ColXpr BVector
 
typedef constABlock::ConstColXpr constBVector
 
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 
typedef std::pair< typename JacobianFactor ::const_iterator, typename JacobianFactor ::const_iteratorConstFactorRange
 
typedef ConstFactorRangeIterator Frontals
 
typedef ConstFactorRangeIterator Parents
 

Public Member Functions

GaussianFactor::shared_ptr clone () const override
 
Vector unweighted_error (const VectorValues &c) const
 
Vector error_vector (const VectorValues &c) const
 
double error (const VectorValues &c) const override
 
Matrix augmentedInformation () const override
 
Matrix information () const override
 
void hessianDiagonalAdd (VectorValues &d) const override
 Add the current diagonal to a VectorValues instance.
 
void hessianDiagonal (double *d) const override
 Raw memory access version of hessianDiagonal.
 
std::map< Key, Matrix > hessianBlockDiagonal () const override
 Return the block diagonal of the Hessian for this factor.
 
std::pair< Matrix, Vector > jacobian () const override
 Returns (dense) A,b pair associated with factor, bakes in the weights.
 
std::pair< Matrix, Vector > jacobianUnweighted () const
 Returns (dense) A,b pair associated with factor, does not bake in weights.
 
Matrix augmentedJacobian () const override
 
Matrix augmentedJacobianUnweighted () const
 
const VerticalBlockMatrixmatrixObject () const
 
VerticalBlockMatrixmatrixObject ()
 
GaussianFactor::shared_ptr negate () const override
 
bool isConstrained () const
 
DenseIndex getDim (const_iterator variable) const override
 
size_t rows () const
 
size_t cols () const
 
const SharedDiagonal & get_model () const
 
SharedDiagonal & get_model ()
 
const constBVector getb () const
 
BVector getb ()
 
constABlock getA (const_iterator variable) const
 
constABlock getA () const
 
ABlock getA (iterator variable)
 
ABlock getA ()
 
void updateHessian (const KeyVector &keys, SymmetricBlockMatrix *info) const override
 
Vector operator* (const VectorValues &x) const
 
void transposeMultiplyAdd (double alpha, const Vector &e, VectorValues &x) const
 
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
 
VectorValues gradientAtZero () const override
 A'*b for Jacobian.
 
void gradientAtZero (double *d) const override
 A'*b for Jacobian (raw memory version)
 
Vector gradient (Key key, const VectorValues &x) const override
 Compute the gradient wrt a key at any values.
 
JacobianFactor whiten () const
 
std::pair< std::shared_ptr< GaussianConditional >, shared_ptreliminate (const Ordering &keys)
 
void setModel (bool anyConstrained, const Vector &sigmas)
 
std::shared_ptr< GaussianConditionalsplitConditional (size_t nrFrontals)
 
Testable
void print (const std::string &="GaussianConditional", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 
bool equals (const GaussianFactor &cg, double tol=1e-9) const override
 
Standard Interface
double logNormalizationConstant () const override
 
double logProbability (const VectorValues &x) const
 
double evaluate (const VectorValues &x) const
 
double operator() (const VectorValues &x) const
 Evaluate probability density, sugar.
 
VectorValues solve (const VectorValues &parents) const
 
VectorValues solveOtherRHS (const VectorValues &parents, const VectorValues &rhs) const
 
void solveTransposeInPlace (VectorValues &gy) const
 
JacobianFactor::shared_ptr likelihood (const VectorValues &frontalValues) const
 
JacobianFactor::shared_ptr likelihood (const Vector &frontal) const
 
VectorValues sample (std::mt19937_64 *rng) const
 
VectorValues sample (const VectorValues &parentsValues, std::mt19937_64 *rng) const
 
VectorValues sample () const
 Sample, use default rng.
 
VectorValues sample (const VectorValues &parentsValues) const
 Sample with given values, use default rng.
 
Linear algebra.
constABlock R () const
 
constABlock S () const
 
constABlock S (const_iterator it) const
 
const constBVector d () const
 
double determinant () const
 Compute the determinant of the R matrix. More...
 
double logDeterminant () const
 Compute the log determinant of the R matrix. More...
 
HybridValues methods.
double logProbability (const HybridValues &x) const override
 
double evaluate (const HybridValues &x) const override
 
Testable
bool equals (const This &other, double tol=1e-9) const
 check equality
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
Standard Interface
double error (const HybridValues &c) const override
 
VectorValues hessianDiagonal () const
 Return the diagonal of the Hessian for this factor.
 
Standard Interface
bool empty () const
 Whether the factor is empty (involves zero variables).
 
Key front () const
 First key.
 
Key back () const
 Last key.
 
const_iterator find (Key key) const
 find
 
const KeyVectorkeys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
Advanced Interface
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 
Testable
bool equals (const This &c, double tol=1e-9) const
 
Standard Interface
size_t nrFrontals () const
 
size_t nrParents () const
 
Key firstFrontalKey () const
 
Frontals frontals () const
 
Parents parents () const
 
double operator() (const HybridValues &x) const
 Evaluate probability density, sugar.
 
double normalizationConstant () const
 

Static Public Member Functions

Advanced Interface
template<typename CONTAINER >
static DenseIndex Slot (const CONTAINER &keys, Key key)
 

Protected Member Functions

template<typename TERMS >
void fillTerms (const TERMS &terms, const Vector &b, const SharedDiagonal &noiseModel)
 Internal function to fill blocks and set dimensions.
 

Static Protected Member Functions

Standard Constructors
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 

Protected Attributes

VerticalBlockMatrix Ab_
 
noiseModel::Diagonal::shared_ptr model_
 
KeyVector keys_
 The keys involved in this factor.
 
size_t nrFrontals_
 

Advanced Interface

size_t & nrFrontals ()
 
JacobianFactor ::const_iterator beginFrontals () const
 
JacobianFactor ::iterator beginFrontals ()
 
JacobianFactor ::const_iterator endFrontals () const
 
JacobianFactor ::iterator endFrontals ()
 
JacobianFactor ::const_iterator beginParents () const
 
JacobianFactor ::iterator beginParents ()
 
JacobianFactor ::const_iterator endParents () const
 
JacobianFactor ::iterator endParents ()
 
static bool CheckInvariants (const GaussianConditional &conditional, const VALUES &x)
 

Constructors

 GaussianConditional ()
 
 GaussianConditional (Key key, const Vector &d, const Matrix &R, const SharedDiagonal &sigmas=SharedDiagonal())
 
 GaussianConditional (Key key, const Vector &d, const Matrix &R, Key parent1, const Matrix &S, const SharedDiagonal &sigmas=SharedDiagonal())
 
 GaussianConditional (Key key, const Vector &d, const Matrix &R, Key parent1, const Matrix &S, Key parent2, 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())
 
static GaussianConditional FromMeanAndStddev (Key key, const Vector &mu, double sigma)
 Construct from mean mu and standard deviation sigma.
 
static GaussianConditional FromMeanAndStddev (Key key, const Matrix &A, Key parent, const Vector &b, double sigma)
 Construct from conditional mean A1 p1 + b and standard deviation.
 
static GaussianConditional FromMeanAndStddev (Key key, const Matrix &A1, Key parent1, const Matrix &A2, Key parent2, const Vector &b, double sigma)
 
template<typename... Args>
static shared_ptr sharedMeanAndStddev (Args &&... args)
 Create shared pointer by forwarding arguments to fromMeanAndStddev.
 
template<typename ITERATOR >
static shared_ptr Combine (ITERATOR firstConditional, ITERATOR lastConditional)
 

Detailed Description

A GaussianConditional 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-density is given by \( \frac{1}{2} |Rx - (d - Sy - Tz - ...)|^2 \)

This is the base class for all conditional distributions/densities, which are implemented as specialized factors. This class does not store any data other than its keys. Derived classes store data such as matrices and probability tables.

The evaluate method is used to evaluate the factor, and together with logProbability is the main methods that need to be implemented in derived classes. These two methods relate to the error method in the factor by: probability(x) = k exp(-error(x)) where k is a normalization constant making probability(x) == 1.0, and logProbability(x) = K - error(x) i.e., K = log(K). The normalization constant K is assumed to not depend on any argument, only (possibly) on the conditional parameters. This class provides a default logNormalizationConstant() == 0.0.

There are four broad classes of conditionals that derive from Conditional:

Member Typedef Documentation

◆ ConstFactorRange

A mini implementation of an iterator range, to share const views of frontals and parents.

◆ Frontals

typedef ConstFactorRangeIterator gtsam::Conditional< JacobianFactor , GaussianConditional >::Frontals
inherited

View of the frontal keys (call frontals())

◆ Parents

typedef ConstFactorRangeIterator gtsam::Conditional< JacobianFactor , GaussianConditional >::Parents
inherited

View of the separator keys (call parents())

Constructor & Destructor Documentation

◆ GaussianConditional() [1/6]

gtsam::GaussianConditional::GaussianConditional ( )
inline

default constructor needed for serialization

◆ GaussianConditional() [2/6]

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

constructor with no parents |Rx-d|

◆ GaussianConditional() [3/6]

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

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

◆ GaussianConditional() [4/6]

gtsam::GaussianConditional::GaussianConditional ( Key  key,
const Vector &  d,
const Matrix &  R,
Key  parent1,
const Matrix &  S,
Key  parent2,
const Matrix &  T,
const SharedDiagonal &  sigmas = SharedDiagonal() 
)

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

◆ GaussianConditional() [5/6]

template<typename TERMS >
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.

◆ GaussianConditional() [6/6]

template<typename KEYS >
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.

Member Function Documentation

◆ augmentedInformation()

Matrix gtsam::JacobianFactor::augmentedInformation ( ) const
overridevirtualinherited

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 \( \delta x = 0 \)). The augmented information matrix is described in more detail in HessianFactor, which in fact stores an augmented information matrix.

Implements gtsam::GaussianFactor.

◆ augmentedJacobian()

Matrix gtsam::JacobianFactor::augmentedJacobian ( ) const
overridevirtualinherited

Return (dense) matrix associated with factor. The returned system is an augmented matrix: [A b] weights are baked in

Implements gtsam::GaussianFactor.

◆ augmentedJacobianUnweighted()

Matrix gtsam::JacobianFactor::augmentedJacobianUnweighted ( ) const
inherited

Return (dense) matrix associated with factor. The returned system is an augmented matrix: [A b] weights are not baked in

◆ begin() [1/2]

const_iterator gtsam::Factor::begin ( ) const
inlineinherited

Iterator at beginning of involved variable keys

◆ begin() [2/2]

iterator gtsam::Factor::begin ( )
inlineinherited

Iterator at beginning of involved variable keys

◆ beginFrontals() [1/2]

JacobianFactor ::const_iterator gtsam::Conditional< JacobianFactor , GaussianConditional >::beginFrontals ( ) const
inlineinherited

Iterator pointing to first frontal key.

◆ beginFrontals() [2/2]

Mutable iterator pointing to first frontal key.

◆ beginParents() [1/2]

JacobianFactor ::const_iterator gtsam::Conditional< JacobianFactor , GaussianConditional >::beginParents ( ) const
inlineinherited

Iterator pointing to the first parent key.

◆ beginParents() [2/2]

Mutable iterator pointing to the first parent key.

◆ CheckInvariants()

bool gtsam::Conditional< JacobianFactor , GaussianConditional >::CheckInvariants ( const GaussianConditional< JacobianFactor, GaussianConditional > &  conditional,
const VALUES &  x 
)
staticinherited

Check invariants of this conditional, given the values x. It tests:

Parameters
conditionalThe conditional to test, as a reference to the derived type.
Template Parameters
VALUESHybridValues, or a more narrow type like DiscreteValues.

◆ clone()

GaussianFactor::shared_ptr gtsam::JacobianFactor::clone ( ) const
inlineoverridevirtualinherited

◆ cols()

size_t gtsam::JacobianFactor::cols ( ) const
inlineinherited

return the number of columns in the corresponding linear system

◆ Combine()

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>.

◆ d()

const constBVector gtsam::GaussianConditional::d ( ) const
inline

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

◆ determinant()

double gtsam::GaussianConditional::determinant ( ) const
inline

Compute the determinant of the R matrix.

The determinant is computed in log form using logDeterminant for numerical stability and then exponentiated.

Note, the covariance matrix \( \Sigma = (R^T R)^{-1} \), and hence \( \det(\Sigma) = 1 / \det(R^T R) = 1 / determinant()^ 2 \).

Returns
double

◆ eliminate()

std::pair<std::shared_ptr<GaussianConditional>, shared_ptr> gtsam::JacobianFactor::eliminate ( const Ordering keys)
inherited

Eliminate the requested variables.

◆ end() [1/2]

const_iterator gtsam::Factor::end ( ) const
inlineinherited

Iterator at end of involved variable keys

◆ end() [2/2]

iterator gtsam::Factor::end ( )
inlineinherited

Iterator at end of involved variable keys

◆ endFrontals() [1/2]

Iterator pointing past the last frontal key.

◆ endFrontals() [2/2]

Mutable iterator pointing past the last frontal key.

◆ endParents() [1/2]

Iterator pointing past the last parent key.

◆ endParents() [2/2]

Mutable iterator pointing past the last parent key.

◆ equals() [1/2]

bool gtsam::Conditional< JacobianFactor , GaussianConditional >::equals ( const This c,
double  tol = 1e-9 
) const
inherited

check equality

◆ equals() [2/2]

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

equals function

Implements gtsam::GaussianFactor.

◆ error()

double gtsam::GaussianFactor::error ( const HybridValues c) const
overridevirtualinherited

All factor types need to implement an error function. In factor graphs, this is the negative log-likelihood.

Reimplemented from gtsam::Factor.

◆ error_vector()

Vector gtsam::JacobianFactor::error_vector ( const VectorValues c) const
inherited

(A*x-b)

◆ evaluate() [1/2]

double gtsam::GaussianConditional::evaluate ( const VectorValues x) const

Calculate probability density for given values x: exp(logProbability(x)) == exp(-GaussianFactor::error(x)) / sqrt((2*pi)^n*det(Sigma)) where x is the vector of values, and Sigma is the covariance matrix.

◆ evaluate() [2/2]

double gtsam::GaussianConditional::evaluate ( const HybridValues x) const
overridevirtual

Calculate probability for HybridValues x. Simply dispatches to VectorValues version.

Reimplemented from gtsam::Conditional< JacobianFactor, GaussianConditional >.

◆ firstFrontalKey()

Key gtsam::Conditional< JacobianFactor , GaussianConditional >::firstFrontalKey ( ) const
inlineinherited

Convenience function to get the first frontal key

◆ FromIterators()

template<typename ITERATOR >
static Factor gtsam::Factor::FromIterators ( ITERATOR  first,
ITERATOR  last 
)
inlinestaticprotectedinherited

Construct factor from iterator keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ FromKeys()

template<typename CONTAINER >
static Factor gtsam::Factor::FromKeys ( const CONTAINER &  keys)
inlinestaticprotectedinherited

Construct factor from container of keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ FromMeanAndStddev()

static GaussianConditional gtsam::GaussianConditional::FromMeanAndStddev ( Key  key,
const Matrix &  A1,
Key  parent1,
const Matrix &  A2,
Key  parent2,
const Vector &  b,
double  sigma 
)
static

Construct from conditional mean A1 p1 + A2 p2 + b and standard deviation sigma.

◆ frontals()

Frontals gtsam::Conditional< JacobianFactor , GaussianConditional >::frontals ( ) const
inlineinherited

return a view of the frontal keys

◆ get_model() [1/2]

const SharedDiagonal& gtsam::JacobianFactor::get_model ( ) const
inlineinherited

get a copy of model

◆ get_model() [2/2]

SharedDiagonal& gtsam::JacobianFactor::get_model ( )
inlineinherited

get a copy of model (non-const version)

◆ getA() [1/4]

constABlock gtsam::JacobianFactor::getA ( const_iterator  variable) const
inlineinherited

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

◆ getA() [2/4]

constABlock gtsam::JacobianFactor::getA ( ) const
inlineinherited

Get a view of the A matrix, not weighted by noise

◆ getA() [3/4]

ABlock gtsam::JacobianFactor::getA ( iterator  variable)
inlineinherited

Get a view of the A matrix for the variable pointed to by the given key iterator (non-const version)

◆ getA() [4/4]

ABlock gtsam::JacobianFactor::getA ( )
inlineinherited

Get a view of the A matrix

◆ getb() [1/2]

const constBVector gtsam::JacobianFactor::getb ( ) const
inlineinherited

Get a view of the r.h.s. vector b, not weighted by noise

◆ getb() [2/2]

BVector gtsam::JacobianFactor::getb ( )
inlineinherited

Get a view of the r.h.s. vector b (non-const version)

◆ getDim()

DenseIndex gtsam::JacobianFactor::getDim ( const_iterator  variable) const
inlineoverridevirtualinherited

Return the dimension of the variable pointed to by the given key iterator todo: Remove this in favor of keeping track of dimensions with variables?

Implements gtsam::GaussianFactor.

◆ information()

Matrix gtsam::JacobianFactor::information ( ) const
overridevirtualinherited

Return the non-augmented information matrix represented by this GaussianFactor.

Implements gtsam::GaussianFactor.

◆ isConstrained()

bool gtsam::JacobianFactor::isConstrained ( ) const
inlineinherited

is noise model constrained ?

◆ keys()

KeyVector& gtsam::Factor::keys ( )
inlineinherited
Returns
keys involved in this factor

◆ likelihood() [1/2]

JacobianFactor::shared_ptr gtsam::GaussianConditional::likelihood ( const VectorValues frontalValues) const

Convert to a likelihood factor by providing value before bar.

◆ likelihood() [2/2]

JacobianFactor::shared_ptr gtsam::GaussianConditional::likelihood ( const Vector &  frontal) const

Single variable version of likelihood.

◆ logDeterminant()

double gtsam::GaussianConditional::logDeterminant ( ) const

Compute the log determinant of the R matrix.

For numerical stability, the determinant is computed in log form, so it is a summation rather than a multiplication.

Note, the covariance matrix \( \Sigma = (R^T R)^{-1} \), and hence \( \log \det(\Sigma) = - \log \det(R^T R) = - 2 logDeterminant() \).

Returns
double

◆ logNormalizationConstant()

double gtsam::GaussianConditional::logNormalizationConstant ( ) const
overridevirtual

normalization constant = 1.0 / sqrt((2*pi)^n*det(Sigma)) log = - 0.5 * n*log(2*pi) - 0.5 * log det(Sigma)

Reimplemented from gtsam::Conditional< JacobianFactor, GaussianConditional >.

◆ logProbability() [1/2]

double gtsam::GaussianConditional::logProbability ( const VectorValues x) const

Calculate log-probability log(evaluate(x)) for given values x: -error(x) - 0.5 * n*log(2*pi) - 0.5 * log det(Sigma) where x is the vector of values, and Sigma is the covariance matrix. This differs from error as it is log, not negative log, and it includes the normalization constant.

◆ logProbability() [2/2]

double gtsam::GaussianConditional::logProbability ( const HybridValues x) const
overridevirtual

Calculate log-probability log(evaluate(x)) for HybridValues x. Simply dispatches to VectorValues version.

Reimplemented from gtsam::Conditional< JacobianFactor, GaussianConditional >.

◆ matrixObject() [1/2]

const VerticalBlockMatrix& gtsam::JacobianFactor::matrixObject ( ) const
inlineinherited

Return the full augmented Jacobian matrix of this factor as a VerticalBlockMatrix object.

◆ matrixObject() [2/2]

VerticalBlockMatrix& gtsam::JacobianFactor::matrixObject ( )
inlineinherited

Mutable access to the full augmented Jacobian matrix of this factor as a VerticalBlockMatrix object.

◆ multiplyHessianAdd() [1/2]

void gtsam::JacobianFactor::multiplyHessianAdd ( double  alpha,
const VectorValues x,
VectorValues y 
) const
overridevirtualinherited

y += alpha * A'*A*x

Implements gtsam::GaussianFactor.

Reimplemented in gtsam::RegularJacobianFactor< D >.

◆ multiplyHessianAdd() [2/2]

void gtsam::JacobianFactor::multiplyHessianAdd ( double  alpha,
const double *  x,
double *  y,
const std::vector< size_t > &  accumulatedDims 
) const
inherited

Raw memory access version of multiplyHessianAdd y += alpha * A'*A*x Requires the vector accumulatedDims to tell the dimension of each variable: e.g.: x0 has dim 3, x2 has dim 6, x3 has dim 2, then accumulatedDims is [0 3 9 11 13] NOTE: size of accumulatedDims is size of keys + 1!! TODO(frank): we should probably kill this if no longer needed

◆ negate()

GaussianFactor::shared_ptr gtsam::JacobianFactor::negate ( ) const
overridevirtualinherited

Construct the corresponding anti-factor to negate information stored stored in this factor.

Returns
a HessianFactor with negated Hessian matrices

Implements gtsam::GaussianFactor.

◆ normalizationConstant()

double gtsam::Conditional< JacobianFactor , GaussianConditional >::normalizationConstant ( ) const
inherited

Non-virtual, exponentiate logNormalizationConstant.

◆ nrFrontals() [1/2]

size_t gtsam::Conditional< JacobianFactor , GaussianConditional >::nrFrontals ( ) const
inlineinherited

return the number of frontals

◆ nrFrontals() [2/2]

size_t& gtsam::Conditional< JacobianFactor , GaussianConditional >::nrFrontals ( )
inlineinherited

Mutable version of nrFrontals

◆ nrParents()

size_t gtsam::Conditional< JacobianFactor , GaussianConditional >::nrParents ( ) const
inlineinherited

return the number of parents

◆ operator*()

Vector gtsam::JacobianFactor::operator* ( const VectorValues x) const
inherited

Return A*x

◆ parents()

Parents gtsam::Conditional< JacobianFactor , GaussianConditional >::parents ( ) const
inlineinherited

return a view of the parent keys

◆ print()

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

print

Implements gtsam::GaussianFactor.

Reimplemented in gtsam::GaussianDensity.

◆ R()

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

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

◆ rows()

size_t gtsam::JacobianFactor::rows ( ) const
inlineinherited

return the number of rows in the corresponding linear system

◆ S() [1/2]

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

Get a view of the parent blocks.

◆ S() [2/2]

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

◆ sample() [1/2]

VectorValues gtsam::GaussianConditional::sample ( std::mt19937_64 *  rng) const

Sample from conditional, zero parent version Example: std::mt19937_64 rng(42); auto sample = gbn.sample(&rng);

◆ sample() [2/2]

VectorValues gtsam::GaussianConditional::sample ( const VectorValues parentsValues,
std::mt19937_64 *  rng 
) const

Sample from conditional, given missing variables Example: std::mt19937_64 rng(42); VectorValues given = ...; auto sample = gbn.sample(given, &rng);

◆ setModel()

void gtsam::JacobianFactor::setModel ( bool  anyConstrained,
const Vector &  sigmas 
)
inherited

set noiseModel correctly

◆ size()

size_t gtsam::Factor::size ( ) const
inlineinherited
Returns
the number of variables involved in this factor

◆ solve()

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 \).

◆ solveTransposeInPlace()

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

Performs transpose backsubstition in place on values

◆ splitConditional()

std::shared_ptr<GaussianConditional> gtsam::JacobianFactor::splitConditional ( size_t  nrFrontals)
inherited

splits a pre-factorized factor into a conditional, and changes the current factor to be the remaining component. Performs same operation as eliminate(), but without running QR. NOTE: looks at dimension of noise model to determine how many rows to keep.

Parameters
nrFrontalsnumber of keys to eliminate

◆ transposeMultiplyAdd()

void gtsam::JacobianFactor::transposeMultiplyAdd ( double  alpha,
const Vector &  e,
VectorValues x 
) const
inherited

x += alpha * A'*e. If x is initially missing any values, they are created and assumed to start as zero vectors.

◆ updateHessian()

void gtsam::JacobianFactor::updateHessian ( const KeyVector keys,
SymmetricBlockMatrix info 
) const
overridevirtualinherited

Update an information matrix by adding the information corresponding to this factor (used internally during elimination).

Parameters
scatterA mapping from variable index to slot index in this HessianFactor
infoThe information matrix to be updated

Implements gtsam::GaussianFactor.

◆ whiten()

JacobianFactor gtsam::JacobianFactor::whiten ( ) const
inherited

Return a whitened version of the factor, i.e. with unit diagonal noise model.

Member Data Documentation

◆ nrFrontals_

size_t gtsam::Conditional< JacobianFactor , GaussianConditional >::nrFrontals_
protectedinherited

The first nrFrontal variables are frontal and the rest are parents.


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