Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
gtsam::Potentials Class Reference

#include <Potentials.h>

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

Public Types

typedef AlgebraicDecisionTree< KeyADT
 
- Public Types inherited from gtsam::AlgebraicDecisionTree< Key >
typedef DecisionTree< Key, double > Super
 
- Public Types inherited from gtsam::DecisionTree< Key, double >
typedef boost::function< double(const double &, const double &)> Binary
 
typedef std::pair< Key, size_tLabelC
 
typedef Node::Ptr NodePtr
 
typedef boost::function< double(const double &)> Unary
 

Public Member Functions

size_t cardinality (Key j) const
 
GTSAM_EXPORT bool equals (const Potentials &other, double tol=1e-9) const
 
GTSAM_EXPORT Potentials ()
 
GTSAM_EXPORT Potentials (const DiscreteKeys &keys, const ADT &decisionTree)
 
template<class SOURCE >
 Potentials (const DiscreteKeys &keys, SOURCE table)
 
GTSAM_EXPORT void print (const std::string &s="Potentials: ", const KeyFormatter &formatter=DefaultKeyFormatter) const
 
- Public Member Functions inherited from gtsam::AlgebraicDecisionTree< Key >
 AlgebraicDecisionTree ()
 
 AlgebraicDecisionTree (const Super &add)
 
 AlgebraicDecisionTree (const Key &label, double y1, double y2)
 
 AlgebraicDecisionTree (const typename Super::LabelC &labelC, double y1, double y2)
 
 AlgebraicDecisionTree (const std::vector< typename Super::LabelC > &labelCs, const std::vector< double > &ys)
 
 AlgebraicDecisionTree (const std::vector< typename Super::LabelC > &labelCs, const std::string &table)
 
 AlgebraicDecisionTree (Iterator begin, Iterator end, const Key &label)
 
 AlgebraicDecisionTree (const AlgebraicDecisionTree< M > &other, const std::map< M, Key > &map)
 
AlgebraicDecisionTree operator* (const AlgebraicDecisionTree &g) const
 
AlgebraicDecisionTree operator+ (const AlgebraicDecisionTree &g) const
 
AlgebraicDecisionTree operator/ (const AlgebraicDecisionTree &g) const
 
AlgebraicDecisionTree sum (const Key &label, size_t cardinality) const
 
AlgebraicDecisionTree sum (const typename Super::LabelC &labelC) const
 
- Public Member Functions inherited from gtsam::DecisionTree< Key, double >
 DecisionTree (const double &y)
 
 DecisionTree (const Key &label, const double &y1, const double &y2)
 
 DecisionTree (const LabelC &label, const double &y1, const double &y2)
 
 DecisionTree (const std::vector< LabelC > &labelCs, const std::vector< double > &ys)
 
 DecisionTree (const std::vector< LabelC > &labelCs, const std::string &table)
 
 DecisionTree (Iterator begin, Iterator end, const Key &label)
 
 DecisionTree (const Key &label, const DecisionTree &f0, const DecisionTree &f1)
 
 DecisionTree (const DecisionTree< M, X > &other, const std::map< M, Key > &map, boost::function< double(const X &)> op)
 
 DecisionTree (const NodePtr &root)
 
NodePtr compose (Iterator begin, Iterator end, const Key &label) const
 
void print (const std::string &s="DecisionTree") const
 
bool equals (const DecisionTree &other, double tol=1e-9) const
 
virtual ~DecisionTree ()
 
bool operator== (const DecisionTree &q) const
 
const double & operator() (const Assignment< Key > &x) const
 
DecisionTree apply (const Unary &op) const
 
DecisionTree apply (const DecisionTree &g, const Binary &op) const
 
DecisionTree choose (const Key &label, size_t index) const
 
DecisionTree combine (const Key &label, size_t cardinality, const Binary &op) const
 
DecisionTree combine (const LabelC &labelC, const Binary &op) const
 
void dot (std::ostream &os, bool showZero=true) const
 
void dot (const std::string &name, bool showZero=true) const
 

Protected Member Functions

 Potentials (const ADT &potentials)
 
- Protected Member Functions inherited from gtsam::DecisionTree< Key, double >
NodePtr convert (const typename DecisionTree< M, X >::NodePtr &f, const std::map< M, Key > &map, boost::function< double(const X &)> op)
 
NodePtr create (It begin, It end, ValueIt beginY, ValueIt endY) const
 
 DecisionTree ()
 

Static Protected Member Functions

static GTSAM_EXPORT double safe_div (const double &a, const double &b)
 

Protected Attributes

std::map< Key, size_tcardinalities_
 Cardinality for each key, used in combine. More...
 

Additional Inherited Members

- Public Attributes inherited from gtsam::DecisionTree< Key, double >
NodePtr root_
 

Detailed Description

A base class for both DiscreteFactor and DiscreteConditional

Definition at line 32 of file Potentials.h.

Member Typedef Documentation

Definition at line 36 of file Potentials.h.

Constructor & Destructor Documentation

gtsam::Potentials::Potentials ( const ADT potentials)
inlineprotected

Constructor from ColumnIndex, and ADT

Definition at line 44 of file Potentials.h.

gtsam::Potentials::Potentials ( )

Default constructor for I/O

Definition at line 44 of file Potentials.cpp.

gtsam::Potentials::Potentials ( const DiscreteKeys keys,
const ADT decisionTree 
)

Constructor from Indices and ADT

Definition at line 48 of file Potentials.cpp.

template<class SOURCE >
gtsam::Potentials::Potentials ( const DiscreteKeys keys,
SOURCE  table 
)
inline

Constructor from Indices and (string or doubles)

Definition at line 65 of file Potentials.h.

Member Function Documentation

size_t gtsam::Potentials::cardinality ( Key  j) const
inline

Definition at line 74 of file Potentials.h.

bool gtsam::Potentials::equals ( const Potentials other,
double  tol = 1e-9 
) const

Definition at line 52 of file Potentials.cpp.

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

Definition at line 57 of file Potentials.cpp.

double gtsam::Potentials::safe_div ( const double &  a,
const double &  b 
)
staticprotected

Definition at line 34 of file Potentials.cpp.

Member Data Documentation

std::map<Key,size_t> gtsam::Potentials::cardinalities_
protected

Cardinality for each key, used in combine.

Definition at line 41 of file Potentials.h.


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


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