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

#include <DiscreteBayesNet.h>

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

Public Types

typedef FactorGraph< DiscreteConditionalBase
 
typedef DiscreteConditional ConditionalType
 
typedef boost::shared_ptr< Thisshared_ptr
 
typedef boost::shared_ptr< ConditionalTypesharedConditional
 
typedef DiscreteBayesNet This
 
- Public Types inherited from gtsam::BayesNet< DiscreteConditional >
typedef boost::shared_ptr< DiscreteConditionalsharedConditional
 A shared pointer to a conditional. More...
 
- Public Types inherited from gtsam::FactorGraph< DiscreteConditional >
typedef FastVector< sharedFactor >::const_iterator const_iterator
 
typedef DiscreteConditional FactorType
 factor type More...
 
typedef FastVector< sharedFactor >::iterator iterator
 
typedef boost::shared_ptr< DiscreteConditionalsharedFactor
 Shared pointer to a factor. More...
 
typedef sharedFactor value_type
 

Public Member Functions

Standard Constructors
 DiscreteBayesNet ()
 
template<typename ITERATOR >
 DiscreteBayesNet (ITERATOR firstConditional, ITERATOR lastConditional)
 
template<class CONTAINER >
 DiscreteBayesNet (const CONTAINER &conditionals)
 
template<class DERIVEDCONDITIONAL >
 DiscreteBayesNet (const FactorGraph< DERIVEDCONDITIONAL > &graph)
 
virtual ~DiscreteBayesNet ()
 Destructor. More...
 
Testable
bool equals (const This &bn, double tol=1e-9) const
 
Standard Interface
void add (const Signature &s)
 
double evaluate (const DiscreteConditional::Values &values) const
 
DiscreteFactor::sharedValues optimize () const
 
DiscreteFactor::sharedValues sample () const
 
- Public Member Functions inherited from gtsam::BayesNet< DiscreteConditional >
void print (const std::string &s="BayesNet", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 
void saveGraph (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 
- Public Member Functions inherited from gtsam::FactorGraph< DiscreteConditional >
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
 
sharedFactorat (size_t i)
 
const sharedFactor operator[] (size_t i) const
 
sharedFactoroperator[] (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::BayesNet< DiscreteConditional >
 BayesNet ()
 
 BayesNet (ITERATOR firstConditional, ITERATOR lastConditional)
 
- Protected Member Functions inherited from gtsam::FactorGraph< DiscreteConditional >
 FactorGraph ()
 
 FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor)
 
 FactorGraph (const CONTAINER &factors)
 
- Protected Attributes inherited from gtsam::FactorGraph< DiscreteConditional >
FastVector< sharedFactorfactors_
 

Detailed Description

A Bayes net made from linear-Discrete densities

Definition at line 30 of file DiscreteBayesNet.h.

Member Typedef Documentation

Definition at line 34 of file DiscreteBayesNet.h.

Definition at line 36 of file DiscreteBayesNet.h.

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

Definition at line 37 of file DiscreteBayesNet.h.

Definition at line 38 of file DiscreteBayesNet.h.

Definition at line 35 of file DiscreteBayesNet.h.

Constructor & Destructor Documentation

gtsam::DiscreteBayesNet::DiscreteBayesNet ( )
inline

Construct empty factor graph

Definition at line 44 of file DiscreteBayesNet.h.

template<typename ITERATOR >
gtsam::DiscreteBayesNet::DiscreteBayesNet ( ITERATOR  firstConditional,
ITERATOR  lastConditional 
)
inline

Construct from iterator over conditionals

Definition at line 48 of file DiscreteBayesNet.h.

template<class CONTAINER >
gtsam::DiscreteBayesNet::DiscreteBayesNet ( const CONTAINER &  conditionals)
inlineexplicit

Construct from container of factors (shared_ptr or plain objects)

Definition at line 52 of file DiscreteBayesNet.h.

template<class DERIVEDCONDITIONAL >
gtsam::DiscreteBayesNet::DiscreteBayesNet ( const FactorGraph< DERIVEDCONDITIONAL > &  graph)
inline

Implicit copy/downcast constructor to override explicit template container constructor

Definition at line 56 of file DiscreteBayesNet.h.

virtual gtsam::DiscreteBayesNet::~DiscreteBayesNet ( )
inlinevirtual

Destructor.

Definition at line 59 of file DiscreteBayesNet.h.

Member Function Documentation

void gtsam::DiscreteBayesNet::add ( const Signature s)

Add a DiscreteCondtional

Definition at line 43 of file DiscreteBayesNet.cpp.

bool gtsam::DiscreteBayesNet::equals ( const This bn,
double  tol = 1e-9 
) const

Check equality

Definition at line 32 of file DiscreteBayesNet.cpp.

double gtsam::DiscreteBayesNet::evaluate ( const DiscreteConditional::Values values) const

Add a DiscreteCondtional in front, when listing parents first

Definition at line 48 of file DiscreteBayesNet.cpp.

DiscreteFactor::sharedValues gtsam::DiscreteBayesNet::optimize ( ) const

Solve the DiscreteBayesNet by back-substitution

Definition at line 57 of file DiscreteBayesNet.cpp.

DiscreteFactor::sharedValues gtsam::DiscreteBayesNet::sample ( ) const

Do ancestral sampling

Definition at line 66 of file DiscreteBayesNet.cpp.

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

Definition at line 97 of file DiscreteBayesNet.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 95 of file DiscreteBayesNet.h.


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


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