Public Types | List of all members
gtsam::HybridNonlinearFactorGraph Class Reference

#include <HybridNonlinearFactorGraph.h>

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

Public Types

using Base = HybridFactorGraph
 
using Indices = KeyVector
 
using shared_ptr = std::shared_ptr< This >
 shared_ptr to This More...
 
using This = HybridNonlinearFactorGraph
 this class More...
 
using Values = gtsam::Values
 backwards compatibility More...
 
- Public Types inherited from gtsam::HybridFactorGraph
using Base = FactorGraph< Factor >
 
using Indices = KeyVector
 
using shared_ptr = std::shared_ptr< This >
 shared_ptr to This More...
 
using This = HybridFactorGraph
 this class More...
 
using Values = gtsam::Values
 backwards compatibility More...
 
- Public Types inherited from gtsam::FactorGraph< Factor >
typedef FastVector< sharedFactor >::const_iterator const_iterator
 
typedef Factor FactorType
 factor type More...
 
typedef FastVector< sharedFactor >::iterator iterator
 
typedef std::shared_ptr< FactorsharedFactor
 Shared pointer to a factor. More...
 
typedef sharedFactor value_type
 

Public Member Functions

Constructors
 HybridNonlinearFactorGraph ()=default
 
template<class DERIVEDFACTOR >
 HybridNonlinearFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph)
 
void print (const std::string &s="HybridNonlinearFactorGraph", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 Print the factor graph. More...
 
void printErrors (const HybridValues &values, const std::string &str="HybridNonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) { return true;}) const
 
Standard Interface
std::shared_ptr< HybridGaussianFactorGraphlinearize (const Values &continuousValues) const
 Linearize all the continuous factors in the HybridNonlinearFactorGraph. More...
 
AlgebraicDecisionTree< KeyerrorTree (const Values &values) const
 Compute error of (hybrid) nonlinear factors and discrete factors over each discrete assignment, and return as a tree. More...
 
AlgebraicDecisionTree< KeydiscretePosterior (const Values &continuousValues) const
 Computer posterior P(M|X=x) when all continuous values X are given. This is efficient as this simply takes -exp(.) of errorTree and normalizes. More...
 
HybridNonlinearFactorGraph restrict (const DiscreteValues &assignment) const
 Restrict all factors in the graph to the given discrete values. More...
 
- Public Member Functions inherited from gtsam::HybridFactorGraph
 HybridFactorGraph ()=default
 Default constructor. More...
 
template<class DERIVEDFACTOR >
 HybridFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph)
 
template<class CONTAINER >
 HybridFactorGraph (const CONTAINER &factors)
 
std::set< DiscreteKeydiscreteKeys () const
 Get all the discrete keys in the factor graph. More...
 
KeySet discreteKeySet () const
 Get all the discrete keys in the factor graph, as a set of Keys. More...
 
const KeySet continuousKeySet () const
 Get all the continuous keys in the factor graph. More...
 
- Public Member Functions inherited from gtsam::FactorGraph< Factor >
 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...
 
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, This >::typeoperator+= (std::shared_ptr< DERIVEDFACTOR > factor)
 Append factor to factor graph. More...
 
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, This >::typeoperator, (std::shared_ptr< DERIVEDFACTOR > factor)
 Overload comma operator to allow for append chaining. 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)
 
Thisoperator+= (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
 
sharedFactorat (size_t i)
 
std::shared_ptr< F > at (size_t i)
 
const std::shared_ptr< F > at (size_t i) const
 Const version of templated at method. More...
 
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
 
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::FactorGraph< Factor >
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< Factor >
FastVector< sharedFactorfactors_
 

Detailed Description

Nonlinear Hybrid Factor Graph

This is the non-linear version of a hybrid factor graph. Everything inside needs to be hybrid factor or hybrid conditional.

Definition at line 33 of file HybridNonlinearFactorGraph.h.

Member Typedef Documentation

◆ Base

Definition at line 36 of file HybridNonlinearFactorGraph.h.

◆ Indices

Definition at line 41 of file HybridNonlinearFactorGraph.h.

◆ shared_ptr

shared_ptr to This

Definition at line 38 of file HybridNonlinearFactorGraph.h.

◆ This

this class

Definition at line 37 of file HybridNonlinearFactorGraph.h.

◆ Values

backwards compatibility

Definition at line 40 of file HybridNonlinearFactorGraph.h.

Constructor & Destructor Documentation

◆ HybridNonlinearFactorGraph() [1/2]

gtsam::HybridNonlinearFactorGraph::HybridNonlinearFactorGraph ( )
default

◆ HybridNonlinearFactorGraph() [2/2]

template<class DERIVEDFACTOR >
gtsam::HybridNonlinearFactorGraph::HybridNonlinearFactorGraph ( const FactorGraph< DERIVEDFACTOR > &  graph)
inline

Implicit copy/downcast constructor to override explicit template container constructor. In BayesTree this is used for: cachedSeparatorMarginal_.reset(*separatorMarginal)

Definition at line 54 of file HybridNonlinearFactorGraph.h.

Member Function Documentation

◆ discretePosterior()

AlgebraicDecisionTree< Key > gtsam::HybridNonlinearFactorGraph::discretePosterior ( const Values continuousValues) const

Computer posterior P(M|X=x) when all continuous values X are given. This is efficient as this simply takes -exp(.) of errorTree and normalizes.

Note
Not a DiscreteConditional as the cardinalities of the DiscreteKeys, which we would need, are hard to recover.
Parameters
continuousValuesContinuous values x to condition on.
Returns
DecisionTreeFactor

Definition at line 214 of file HybridNonlinearFactorGraph.cpp.

◆ errorTree()

AlgebraicDecisionTree< Key > gtsam::HybridNonlinearFactorGraph::errorTree ( const Values values) const

Compute error of (hybrid) nonlinear factors and discrete factors over each discrete assignment, and return as a tree.

Error $ e = \Vert f(x) - \mu \Vert_{\Sigma} $.

Note
: Gaussian and hybrid Gaussian factors are not considered!
Parameters
valuesManifold values at which to compute the error.
Returns
AlgebraicDecisionTree<Key>

Definition at line 183 of file HybridNonlinearFactorGraph.cpp.

◆ linearize()

HybridGaussianFactorGraph::shared_ptr gtsam::HybridNonlinearFactorGraph::linearize ( const Values continuousValues) const

Linearize all the continuous factors in the HybridNonlinearFactorGraph.

Parameters
continuousValuesDictionary of continuous values.
Returns
HybridGaussianFactorGraph::shared_ptr

Definition at line 139 of file HybridNonlinearFactorGraph.cpp.

◆ print()

void gtsam::HybridNonlinearFactorGraph::print ( const std::string &  s = "HybridNonlinearFactorGraph",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtual

Print the factor graph.

Reimplemented from gtsam::FactorGraph< Factor >.

Definition at line 30 of file HybridNonlinearFactorGraph.cpp.

◆ printErrors()

void gtsam::HybridNonlinearFactorGraph::printErrors ( const HybridValues values,
const std::string &  str = "HybridNonlinearFactorGraph: ",
const KeyFormatter keyFormatter = DefaultKeyFormatter,
const std::function< bool(const Factor *, double, size_t)> &  printCondition = [](const Factor*, double, size_t) { return true; } 
) const

print errors along with factors

Definition at line 46 of file HybridNonlinearFactorGraph.cpp.

◆ restrict()

HybridNonlinearFactorGraph gtsam::HybridNonlinearFactorGraph::restrict ( const DiscreteValues assignment) const

Restrict all factors in the graph to the given discrete values.

Definition at line 225 of file HybridNonlinearFactorGraph.cpp.


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


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:14:50