#include <GaussianBayesNet.h>
Public Types | |
typedef FactorGraph< GaussianConditional > | Base |
typedef GaussianConditional | ConditionalType |
typedef boost::shared_ptr< This > | shared_ptr |
typedef boost::shared_ptr< ConditionalType > | sharedConditional |
typedef GaussianBayesNet | This |
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 boost::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) | |
virtual | ~GaussianBayesNet () |
Destructor. More... | |
Testable | |
bool | equals (const This &bn, double tol=1e-9) const |
Standard Interface | |
VectorValues | optimize () const |
Solve the GaussianBayesNet, i.e. return , by back-substitution. More... | |
VectorValues | optimize (const VectorValues &solutionForMissing) const |
Version of optimize for incomplete BayesNet, needs solution for missing variables. 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 | error (const VectorValues &x) const |
double | determinant () const |
double | logDeterminant () const |
VectorValues | backSubstitute (const VectorValues &gx) const |
VectorValues | backSubstituteTranspose (const VectorValues &gx) const |
void | print (const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print graph More... | |
void | saveGraph (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
Save the GaussianBayesNet as an image. Requires dot to be installed. More... | |
Public Member Functions inherited from gtsam::FactorGraph< GaussianConditional > | |
virtual | ~FactorGraph ()=default |
Default destructor. More... | |
void | reserve (size_t size) |
IsDerived< DERIVEDFACTOR > | push_back (boost::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 (boost::shared_ptr< DERIVEDFACTOR > factor) |
add is a synonym for push_back. More... | |
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, boost::assign::list_inserter< RefCallPushBack< This > > >::type | operator+= (boost::shared_ptr< DERIVEDFACTOR > factor) |
+= works well with boost::assign list inserter. 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) |
boost::assign::list_inserter< CRefCallPushBack< This > > | operator+= (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 |
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 |
iterator | begin () |
iterator | end () |
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) |
size_t | nrFactors () const |
KeySet | keys () const |
KeyVector | keyVector () const |
bool | exists (size_t idx) const |
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::FactorGraph< GaussianConditional > | |
FactorGraph () | |
FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
FactorGraph (const CONTAINER &factors) | |
Protected Attributes inherited from gtsam::FactorGraph< GaussianConditional > | |
FastVector< sharedFactor > | factors_ |
A Bayes net made from linear-Gaussian densities
Definition at line 30 of file GaussianBayesNet.h.
Definition at line 34 of file GaussianBayesNet.h.
Definition at line 36 of file GaussianBayesNet.h.
typedef boost::shared_ptr<This> gtsam::GaussianBayesNet::shared_ptr |
Definition at line 37 of file GaussianBayesNet.h.
typedef boost::shared_ptr<ConditionalType> gtsam::GaussianBayesNet::sharedConditional |
Definition at line 38 of file GaussianBayesNet.h.
Definition at line 35 of file GaussianBayesNet.h.
|
inline |
Construct empty factor graph
Definition at line 44 of file GaussianBayesNet.h.
|
inline |
Construct from iterator over conditionals
Definition at line 48 of file GaussianBayesNet.h.
|
inlineexplicit |
Construct from container of factors (shared_ptr or plain objects)
Definition at line 52 of file GaussianBayesNet.h.
|
inline |
Implicit copy/downcast constructor to override explicit template container constructor
Definition at line 56 of file GaussianBayesNet.h.
|
inlinevirtual |
Destructor.
Definition at line 59 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 84 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 100 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 186 of file GaussianBayesNet.cpp.
bool gtsam::GaussianBayesNet::equals | ( | const This & | bn, |
double | tol = 1e-9 |
||
) | const |
Check equality
Definition at line 35 of file GaussianBayesNet.cpp.
double gtsam::GaussianBayesNet::error | ( | const VectorValues & | x | ) | const |
0.5 * sum of squared Mahalanobis distances.
Definition at line 79 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 69 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 74 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 192 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 160 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 167 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::optimize | ( | ) | const |
Solve the GaussianBayesNet, i.e. return , by back-substitution.
Definition at line 41 of file GaussianBayesNet.cpp.
VectorValues gtsam::GaussianBayesNet::optimize | ( | const VectorValues & | solutionForMissing | ) | const |
Version of optimize for incomplete BayesNet, needs solution for missing variables.
solve each node in turn in topological sort order (parents first)
Definition at line 48 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 62 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 142 of file GaussianBayesNet.cpp.
|
inlineoverridevirtual |
print graph
Reimplemented from gtsam::FactorGraph< GaussianConditional >.
Definition at line 184 of file GaussianBayesNet.h.
void gtsam::GaussianBayesNet::saveGraph | ( | const std::string & | s, |
const KeyFormatter & | keyFormatter = DefaultKeyFormatter |
||
) | const |
Save the GaussianBayesNet as an image. Requires dot
to be installed.
s | The name of the figure. |
keyFormatter | Formatter to use for styling keys in the graph. |
Definition at line 208 of file GaussianBayesNet.cpp.
|
inlineprivate |
Definition at line 206 of file GaussianBayesNet.h.
|
friend |
Serialization function
Definition at line 204 of file GaussianBayesNet.h.