#include <GaussianBayesNet.h>
Public Types | |
typedef BayesNet< GaussianConditional > | Base |
typedef GaussianConditional | ConditionalType |
typedef std::shared_ptr< This > | shared_ptr |
typedef std::shared_ptr< ConditionalType > | sharedConditional |
typedef GaussianBayesNet | This |
Public Types inherited from gtsam::BayesNet< GaussianConditional > | |
typedef std::shared_ptr< GaussianConditional > | sharedConditional |
A shared pointer to a conditional. More... | |
Public Types inherited from gtsam::FactorGraph< GaussianConditional > | |
typedef FastVector< sharedFactor >::const_iterator | const_iterator |
typedef GaussianConditional | FactorType |
factor type More... | |
typedef FastVector< sharedFactor >::iterator | iterator |
typedef std::shared_ptr< GaussianConditional > | sharedFactor |
Shared pointer to a factor. More... | |
typedef sharedFactor | value_type |
Public Member Functions | |
Standard Constructors | |
GaussianBayesNet () | |
template<typename ITERATOR > | |
GaussianBayesNet (ITERATOR firstConditional, ITERATOR lastConditional) | |
template<class CONTAINER > | |
GaussianBayesNet (const CONTAINER &conditionals) | |
template<class DERIVEDCONDITIONAL > | |
GaussianBayesNet (const FactorGraph< DERIVEDCONDITIONAL > &graph) | |
template<class DERIVEDCONDITIONAL > | |
GaussianBayesNet (std::initializer_list< std::shared_ptr< DERIVEDCONDITIONAL > > conditionals) | |
Testable | |
bool | equals (const This &bn, double tol=1e-9) const |
void | print (const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print graph More... | |
Standard Interface | |
double | error (const VectorValues &x) const |
Sum error over all variables. More... | |
double | logProbability (const VectorValues &x) const |
Sum logProbability over all variables. More... | |
double | evaluate (const VectorValues &x) const |
double | operator() (const VectorValues &x) const |
Evaluate probability density, sugar. More... | |
VectorValues | optimize () const |
VectorValues | optimize (const VectorValues &given) const |
Version of optimize for incomplete BayesNet, given missing variables. More... | |
VectorValues | sample (std::mt19937_64 *rng) const |
VectorValues | sample (const VectorValues &given, std::mt19937_64 *rng) const |
VectorValues | sample () const |
Sample using ancestral sampling, use default rng. More... | |
VectorValues | sample (const VectorValues &given) const |
Sample from an incomplete BayesNet, use default rng. More... | |
Ordering | ordering () const |
Linear Algebra | |
std::pair< Matrix, Vector > | matrix (const Ordering &ordering) const |
std::pair< Matrix, Vector > | matrix () const |
VectorValues | optimizeGradientSearch () const |
VectorValues | gradient (const VectorValues &x0) const |
VectorValues | gradientAtZero () const |
double | determinant () const |
double | logDeterminant () const |
VectorValues | backSubstitute (const VectorValues &gx) const |
VectorValues | backSubstituteTranspose (const VectorValues &gx) const |
Public Member Functions inherited from gtsam::BayesNet< GaussianConditional > | |
void | print (const std::string &s="BayesNet", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
void | dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const |
Output to graphviz format, stream version. More... | |
std::string | dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const |
Output to graphviz format string. More... | |
void | saveGraph (const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const |
output to file with graphviz format. More... | |
double | logProbability (const HybridValues &x) const |
double | evaluate (const HybridValues &c) const |
Public Member Functions inherited from gtsam::FactorGraph< GaussianConditional > | |
FactorGraph (std::initializer_list< std::shared_ptr< DERIVEDFACTOR >> sharedFactors) | |
virtual | ~FactorGraph ()=default |
void | reserve (size_t size) |
IsDerived< DERIVEDFACTOR > | push_back (std::shared_ptr< DERIVEDFACTOR > factor) |
Add a factor directly using a shared_ptr. More... | |
IsDerived< DERIVEDFACTOR > | push_back (const DERIVEDFACTOR &factor) |
IsDerived< DERIVEDFACTOR > | emplace_shared (Args &&... args) |
Emplace a shared pointer to factor of given type. More... | |
IsDerived< DERIVEDFACTOR > | add (std::shared_ptr< DERIVEDFACTOR > factor) |
add is a synonym for push_back. More... | |
HasDerivedElementType< ITERATOR > | push_back (ITERATOR firstFactor, ITERATOR lastFactor) |
HasDerivedValueType< ITERATOR > | push_back (ITERATOR firstFactor, ITERATOR lastFactor) |
Push back many factors with an iterator (factors are copied) More... | |
HasDerivedElementType< CONTAINER > | push_back (const CONTAINER &container) |
HasDerivedValueType< CONTAINER > | push_back (const CONTAINER &container) |
Push back non-pointer objects in a container (factors are copied). More... | |
void | add (const FACTOR_OR_CONTAINER &factorOrContainer) |
std::enable_if< std::is_base_of< This, typename CLIQUE::FactorGraphType >::value >::type | push_back (const BayesTree< CLIQUE > &bayesTree) |
FactorIndices | add_factors (const CONTAINER &factors, bool useEmptySlots=false) |
bool | equals (const This &fg, double tol=1e-9) const |
Check equality up to tolerance. More... | |
size_t | size () const |
bool | empty () const |
const sharedFactor | at (size_t i) const |
sharedFactor & | at (size_t i) |
const sharedFactor | operator[] (size_t i) const |
sharedFactor & | operator[] (size_t i) |
const_iterator | begin () const |
const_iterator | end () const |
sharedFactor | front () const |
sharedFactor | back () const |
double | error (const HybridValues &values) const |
iterator | begin () |
iterator | end () |
virtual void | resize (size_t size) |
void | remove (size_t i) |
void | replace (size_t index, sharedFactor factor) |
iterator | erase (iterator item) |
iterator | erase (iterator first, iterator last) |
void | dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const |
Output to graphviz format, stream version. More... | |
std::string | dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const |
Output to graphviz format string. More... | |
void | saveGraph (const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const |
output to file with graphviz format. More... | |
size_t | nrFactors () const |
KeySet | keys () const |
KeyVector | keyVector () const |
bool | exists (size_t idx) const |
Additional Inherited Members | |
Protected Member Functions inherited from gtsam::BayesNet< GaussianConditional > | |
BayesNet () | |
BayesNet (ITERATOR firstConditional, ITERATOR lastConditional) | |
BayesNet (std::initializer_list< sharedConditional > conditionals) | |
Protected Member Functions inherited from gtsam::FactorGraph< GaussianConditional > | |
bool | isEqual (const FactorGraph &other) const |
Check exact equality of the factor pointers. Useful for derived ==. More... | |
FactorGraph () | |
FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
FactorGraph (const CONTAINER &factors) | |
Protected Attributes inherited from gtsam::FactorGraph< GaussianConditional > | |
FastVector< sharedFactor > | factors_ |
GaussianBayesNet is a Bayes net made from linear-Gaussian conditionals.
Definition at line 35 of file GaussianBayesNet.h.
Definition at line 39 of file GaussianBayesNet.h.
Definition at line 41 of file GaussianBayesNet.h.
typedef std::shared_ptr<This> gtsam::GaussianBayesNet::shared_ptr |
Definition at line 42 of file GaussianBayesNet.h.
typedef std::shared_ptr<ConditionalType> gtsam::GaussianBayesNet::sharedConditional |
Definition at line 43 of file GaussianBayesNet.h.
Definition at line 40 of file GaussianBayesNet.h.
|
inline |
Construct empty bayes net
Definition at line 49 of file GaussianBayesNet.h.
|
inline |
Construct from iterator over conditionals
Definition at line 53 of file GaussianBayesNet.h.
|
inlineexplicit |
Construct from container of factors (shared_ptr or plain objects)
Definition at line 58 of file GaussianBayesNet.h.
|
inlineexplicit |
Implicit copy/downcast constructor to override explicit template container constructor
Definition at line 65 of file GaussianBayesNet.h.
|
inline |
Constructor that takes an initializer list of shared pointers. BayesNet bn = {make_shared<Conditional>(), ...};
Definition at line 73 of file GaussianBayesNet.h.
VectorValues gtsam::GaussianBayesNet::backSubstitute | ( | const VectorValues & | gx | ) | const |
Backsubstitute with a different RHS vector than the one stored in this BayesNet. gy=inv(R*inv(Sigma))*gx
Definition at line 129 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::backSubstituteTranspose | ( | const VectorValues & | gx | ) | const |
Transpose backsubstitute with a different RHS vector than the one stored in this BayesNet. gy=inv(L)*gx by solving L*gy=gx. gy=inv(R'*inv(Sigma))*gx gz'*R'=gx', gy = gz.*sigmas
Definition at line 145 of file GaussianBayesNet.cpp.
double gtsam::GaussianBayesNet::determinant | ( | ) | const |
Computes the determinant of a GassianBayesNet. A GaussianBayesNet is an upper triangular matrix and for an upper triangular matrix determinant is the product of the diagonal elements. Instead of actually multiplying we add the logarithms of the diagonal elements and take the exponent at the end because this is more numerically stable.
bayesNet | The input GaussianBayesNet |
Definition at line 231 of file GaussianBayesNet.cpp.
bool gtsam::GaussianBayesNet::equals | ( | const This & | bn, |
double | tol = 1e-9 |
||
) | const |
Check equality
Definition at line 38 of file GaussianBayesNet.cpp.
double gtsam::GaussianBayesNet::error | ( | const VectorValues & | x | ) | const |
Sum error over all variables.
Definition at line 106 of file GaussianBayesNet.cpp.
double gtsam::GaussianBayesNet::evaluate | ( | const VectorValues & | x | ) | const |
Calculate probability density for given values x
: exp(logProbability) where x is the vector of values.
Definition at line 124 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::gradient | ( | const VectorValues & | x0 | ) | const |
Compute the gradient of the energy function, , centered around . The gradient is .
x0 | The center about which to compute the gradient |
Definition at line 96 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::gradientAtZero | ( | ) | const |
Compute the gradient of the energy function, , centered around zero. The gradient about zero is . See also gradient(const GaussianBayesNet&, const VectorValues&).
[output] | g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues |
Definition at line 101 of file GaussianBayesNet.cpp.
double gtsam::GaussianBayesNet::logDeterminant | ( | ) | const |
Computes the log of the determinant of a GassianBayesNet. A GaussianBayesNet is an upper triangular matrix and for an upper triangular matrix determinant is the product of the diagonal elements.
bayesNet | The input GaussianBayesNet |
Definition at line 237 of file GaussianBayesNet.cpp.
double gtsam::GaussianBayesNet::logProbability | ( | const VectorValues & | x | ) | const |
Sum logProbability over all variables.
Definition at line 115 of file GaussianBayesNet.cpp.
Return (dense) upper-triangular matrix representation Will return upper-triangular matrix only when using 'ordering' above. In case Bayes net is incomplete zero columns are added to the end.
Definition at line 205 of file GaussianBayesNet.cpp.
Return (dense) upper-triangular matrix representation Will return upper-triangular matrix only when using 'ordering' above. In case Bayes net is incomplete zero columns are added to the end.
Definition at line 212 of file GaussianBayesNet.cpp.
|
inline |
Evaluate probability density, sugar.
Definition at line 111 of file GaussianBayesNet.h.
VectorValues gtsam::GaussianBayesNet::optimize | ( | ) | const |
Solve the GaussianBayesNet, i.e. return , by back-substitution
Definition at line 44 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::optimize | ( | const VectorValues & | given | ) | const |
Version of optimize for incomplete BayesNet, given missing variables.
Definition at line 49 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::optimizeGradientSearch | ( | ) | const |
Optimize along the gradient direction, with a closed-form computation to perform the line search. The gradient is computed about .
This function returns that minimizes a reparametrized problem. The error function of a GaussianBayesNet is
with gradient and Hessian
This function performs the line search in the direction of the gradient evaluated at with step size that minimizes :
Optimizing by setting the derivative to zero yields . For efficiency, this function evaluates the denominator without computing the Hessian , returning
Definition at line 89 of file GaussianBayesNet.cpp.
Ordering gtsam::GaussianBayesNet::ordering | ( | ) | const |
Return ordering corresponding to a topological sort. There are many topological sorts of a Bayes net. This one corresponds to the one that makes 'matrix' below upper-triangular. In case Bayes net is incomplete any non-frontal are added to the end.
Definition at line 187 of file GaussianBayesNet.cpp.
|
inlineoverridevirtual |
print graph
Reimplemented from gtsam::FactorGraph< GaussianConditional >.
Definition at line 86 of file GaussianBayesNet.h.
VectorValues gtsam::GaussianBayesNet::sample | ( | std::mt19937_64 * | rng | ) | const |
Sample using ancestral sampling Example: std::mt19937_64 rng(42); auto sample = gbn.sample(&rng);
Definition at line 63 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::sample | ( | const VectorValues & | given, |
std::mt19937_64 * | rng | ||
) | const |
Sample from an incomplete BayesNet, given missing variables Example: std::mt19937_64 rng(42); VectorValues given = ...; auto sample = gbn.sample(given, &rng);
Definition at line 68 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::sample | ( | ) | const |
Sample using ancestral sampling, use default rng.
Definition at line 80 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::sample | ( | const VectorValues & | given | ) | const |
Sample from an incomplete BayesNet, use default rng.
Definition at line 84 of file GaussianBayesNet.cpp.