dcsam
Factored inference for discrete-continuous smoothing and mapping
dcsam::HybridFactorGraph Class Reference

#include <HybridFactorGraph.h>

Collaboration diagram for dcsam::HybridFactorGraph:

Public Member Functions

 HybridFactorGraph ()
 
template<typename NonlinearFactorType >
void push_nonlinear (const NonlinearFactorType &nonlinearFactor)
 
void push_nonlinear (boost::shared_ptr< gtsam::NonlinearFactor > nonlinearFactor)
 
template<typename DiscreteFactorType >
void push_discrete (const DiscreteFactorType &discreteFactor)
 
void push_discrete (boost::shared_ptr< gtsam::DiscreteFactor > discreteFactor)
 
template<typename DCFactorType >
void push_dc (const DCFactorType &dcFactor)
 
void push_dc (boost::shared_ptr< DCFactor > dcFactor)
 
void print (const std::string &str="HybridFactorGraph", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const
 
gtsam::FastSet< gtsam::Key > keys () const
 
gtsam::NonlinearFactorGraph nonlinearGraph () const
 
gtsam::DiscreteFactorGraph discreteGraph () const
 
DCFactorGraph dcGraph () const
 
bool empty () const
 
bool equals (const HybridFactorGraph &other, double tol=1e-9) const
 
size_t size () const
 
size_t size_nonlinear () const
 
size_t size_discrete () const
 
size_t size_dc () const
 
void clear ()
 

Protected Attributes

gtsam::NonlinearFactorGraph nonlinearGraph_
 
gtsam::DiscreteFactorGraph discreteGraph_
 
DCFactorGraph dcGraph_
 

Constructor & Destructor Documentation

◆ HybridFactorGraph()

dcsam::HybridFactorGraph::HybridFactorGraph ( )

Member Function Documentation

◆ clear()

void dcsam::HybridFactorGraph::clear ( )

Clears all internal factor graphs

◆ dcGraph()

DCFactorGraph dcsam::HybridFactorGraph::dcGraph ( ) const

Utility for retrieving the internal DC factor graph

Returns
the member variable dcGraph_

◆ discreteGraph()

gtsam::DiscreteFactorGraph dcsam::HybridFactorGraph::discreteGraph ( ) const

Utility for retrieving the internal discrete factor graph

Returns
the member variable discreteGraph_

◆ empty()

bool dcsam::HybridFactorGraph::empty ( ) const
Returns
true if all internal graphs are empty

◆ equals()

bool dcsam::HybridFactorGraph::equals ( const HybridFactorGraph other,
double  tol = 1e-9 
) const
Returns
true if all internal graphs of this are equal to those of other

◆ keys()

gtsam::FastSet< gtsam::Key > dcsam::HybridFactorGraph::keys ( ) const

Mimics the GTSAM::FactorGraph API: retrieve the keys from each internal factor graph. Internally uses FastSet::merge(const FastSet &other) to combine sets from the different member factor graphs.

Returns
the (aggregate) set of keys in all of the internal factor graphs.

◆ nonlinearGraph()

gtsam::NonlinearFactorGraph dcsam::HybridFactorGraph::nonlinearGraph ( ) const

Utility for retrieving the internal nonlinear factor graph

Returns
the member variable nolinearGraph_

◆ print()

void dcsam::HybridFactorGraph::print ( const std::string &  str = "HybridFactorGraph",
const gtsam::KeyFormatter &  keyFormatter = gtsam::DefaultKeyFormatter 
) const

Simply prints the factor graph.

◆ push_dc() [1/2]

void dcsam::HybridFactorGraph::push_dc ( boost::shared_ptr< DCFactor dcFactor)

Add a discrete-continuous (DC) factor pointer to the internal DC graph

Parameters
dcFactor- boost::shared_ptr to the factor to add

◆ push_dc() [2/2]

template<typename DCFactorType >
void dcsam::HybridFactorGraph::push_dc ( const DCFactorType &  dcFactor)
inline

Add a discrete-continuous (DC) factor to the internal DC graph

Parameters
dcFactor- the factor to add

◆ push_discrete() [1/2]

void dcsam::HybridFactorGraph::push_discrete ( boost::shared_ptr< gtsam::DiscreteFactor >  discreteFactor)

Add a discrete factor pointer to the internal discrete graph

Parameters
discreteFactor- boost::shared_ptr to the factor to add

◆ push_discrete() [2/2]

template<typename DiscreteFactorType >
void dcsam::HybridFactorGraph::push_discrete ( const DiscreteFactorType &  discreteFactor)
inline

Add a discrete factor to the internal discrete graph

Parameters
discreteFactor- the factor to add

◆ push_nonlinear() [1/2]

void dcsam::HybridFactorGraph::push_nonlinear ( boost::shared_ptr< gtsam::NonlinearFactor >  nonlinearFactor)

Add a nonlinear factor pointer to the internal nonlinear factor graph

Parameters
nonlinearFactor- boost::shared_ptr to the factor to add

◆ push_nonlinear() [2/2]

template<typename NonlinearFactorType >
void dcsam::HybridFactorGraph::push_nonlinear ( const NonlinearFactorType &  nonlinearFactor)
inline

Add a nonlinear factor to the internal nonlinear factor graph

Parameters
nonlinearFactor- the factor to add

◆ size()

size_t dcsam::HybridFactorGraph::size ( ) const
Returns
the total number of factors across all internal graphs

◆ size_dc()

size_t dcsam::HybridFactorGraph::size_dc ( ) const
Returns
the total number of factors in the DC factor graph

◆ size_discrete()

size_t dcsam::HybridFactorGraph::size_discrete ( ) const
Returns
the total number of factors in the discrete factor graph

◆ size_nonlinear()

size_t dcsam::HybridFactorGraph::size_nonlinear ( ) const
Returns
the total number of factors in the nonlinear factor graph

Member Data Documentation

◆ dcGraph_

DCFactorGraph dcsam::HybridFactorGraph::dcGraph_
protected

◆ discreteGraph_

gtsam::DiscreteFactorGraph dcsam::HybridFactorGraph::discreteGraph_
protected

◆ nonlinearGraph_

gtsam::NonlinearFactorGraph dcsam::HybridFactorGraph::nonlinearGraph_
protected

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