Public Types | Public Member Functions | Static Public Member Functions | List of all members
gtsam::GaussianDensity Class Reference

#include <GaussianDensity.h>

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

Public Types

typedef std::shared_ptr< GaussianDensityshared_ptr
 
- Public Types inherited from gtsam::GaussianConditional
typedef Conditional< BaseFactor, ThisBaseConditional
 Typedef to our conditional base class. More...
 
typedef JacobianFactor BaseFactor
 Typedef to our factor base class. More...
 
typedef std::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 std::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 std::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 std::pair< typename JacobianFactor ::const_iterator, typename JacobianFactor ::const_iterator > ConstFactorRange
 
typedef ConstFactorRangeIterator Frontals
 
typedef ConstFactorRangeIterator Parents
 

Public Member Functions

Matrix covariance () const
 Covariance matrix $ \Sigma = (R^T R)^{-1} $. More...
 
 GaussianDensity ()
 default constructor needed for serialization More...
 
 GaussianDensity (const GaussianConditional &conditional)
 Copy constructor from GaussianConditional. More...
 
 GaussianDensity (Key key, const Vector &d, const Matrix &R, const SharedDiagonal &noiseModel=SharedDiagonal())
 constructor using d, R More...
 
Vector mean () const
 Mean $ \mu = R^{-1} d $. More...
 
void print (const std::string &="GaussianDensity", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 print More...
 
- Public Member Functions inherited from gtsam::GaussianConditional
bool equals (const GaussianFactor &cg, double tol=1e-9) const override
 
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. More...
 
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. More...
 
VectorValues sample (const VectorValues &parentsValues) const
 Sample with given values, use default rng. More...
 
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...
 
double logProbability (const HybridValues &x) const override
 
double evaluate (const HybridValues &x) 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 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())
 
- 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_ptreliminate (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 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 with optional string More...
 
size_t rows () const
 
void setModel (bool anyConstrained, const Vector &sigmas)
 
std::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)
 
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 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...
 
bool equals (const This &other, double tol=1e-9) const
 check equality 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
 
virtual ~Conditional ()
 
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. More...
 
double normalizationConstant () const
 
size_tnrFrontals ()
 
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 Public Member Functions

static GaussianDensity FromMeanAndStddev (Key key, const Vector &mean, double sigma)
 Construct using a mean and standard deviation. More...
 
- Static Public Member Functions inherited from gtsam::GaussianConditional
static GaussianConditional FromMeanAndStddev (Key key, const Vector &mu, double sigma)
 Construct from mean mu and standard deviation sigma. More...
 
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. More...
 
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. More...
 
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)
 
- Static Public Member Functions inherited from gtsam::Conditional< JacobianFactor, GaussianConditional >
static bool CheckInvariants (const GaussianConditional &conditional, const VALUES &x)
 

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)
 
- 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 GaussianDensity is a GaussianConditional without parents. The negative log-probability is given by $ |Rx - d|^2 $ with $ \Lambda = \Sigma^{-1} = R^T R $ and $ \mu = R^{-1} d $

Definition at line 32 of file GaussianDensity.h.

Member Typedef Documentation

◆ shared_ptr

Definition at line 36 of file GaussianDensity.h.

Constructor & Destructor Documentation

◆ GaussianDensity() [1/3]

gtsam::GaussianDensity::GaussianDensity ( )
inline

default constructor needed for serialization

Definition at line 39 of file GaussianDensity.h.

◆ GaussianDensity() [2/3]

gtsam::GaussianDensity::GaussianDensity ( const GaussianConditional conditional)
inline

Copy constructor from GaussianConditional.

Definition at line 44 of file GaussianDensity.h.

◆ GaussianDensity() [3/3]

gtsam::GaussianDensity::GaussianDensity ( Key  key,
const Vector d,
const Matrix R,
const SharedDiagonal noiseModel = SharedDiagonal() 
)
inline

constructor using d, R

Definition at line 51 of file GaussianDensity.h.

Member Function Documentation

◆ covariance()

Matrix gtsam::GaussianDensity::covariance ( ) const

Covariance matrix $ \Sigma = (R^T R)^{-1} $.

Definition at line 55 of file GaussianDensity.cpp.

◆ FromMeanAndStddev()

GaussianDensity gtsam::GaussianDensity::FromMeanAndStddev ( Key  key,
const Vector mean,
double  sigma 
)
static

Construct using a mean and standard deviation.

Definition at line 29 of file GaussianDensity.cpp.

◆ mean()

Vector gtsam::GaussianDensity::mean ( ) const

Mean $ \mu = R^{-1} d $.

Definition at line 49 of file GaussianDensity.cpp.

◆ print()

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

print

Reimplemented from gtsam::GaussianConditional.

Definition at line 36 of file GaussianDensity.cpp.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:19