#include <HybridNonlinearFactorGraph.h>
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< Factor > | sharedFactor |
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... | |
Standard Interface | |
std::shared_ptr< HybridGaussianFactorGraph > | linearize (const Values &continuousValues) const |
Linearize all the continuous factors in the HybridNonlinearFactorGraph. More... | |
Public Member Functions inherited from gtsam::HybridFactorGraph | |
HybridFactorGraph ()=default | |
Default constructor. More... | |
template<class DERIVEDFACTOR > | |
HybridFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph) | |
std::set< DiscreteKey > | discreteKeys () 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. More... | |
std::unordered_map< Key, DiscreteKey > | discreteKeyMap () const |
Get a map from Key to corresponding DiscreteKey. 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... | |
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) |
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 |
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 |
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< sharedFactor > | factors_ |
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.
Definition at line 36 of file HybridNonlinearFactorGraph.h.
Definition at line 41 of file HybridNonlinearFactorGraph.h.
using gtsam::HybridNonlinearFactorGraph::shared_ptr = std::shared_ptr<This> |
shared_ptr to This
Definition at line 38 of file HybridNonlinearFactorGraph.h.
this class
Definition at line 37 of file HybridNonlinearFactorGraph.h.
backwards compatibility
Definition at line 40 of file HybridNonlinearFactorGraph.h.
|
default |
|
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.
HybridGaussianFactorGraph::shared_ptr gtsam::HybridNonlinearFactorGraph::linearize | ( | const Values & | continuousValues | ) | const |
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
continuousValues | Dictionary of continuous values. |
Definition at line 45 of file HybridNonlinearFactorGraph.cpp.
|
overridevirtual |
Print the factor graph.
Reimplemented from gtsam::FactorGraph< Factor >.
Definition at line 29 of file HybridNonlinearFactorGraph.cpp.