#include <ExpressionFactorGraph.h>
Public Member Functions | |
Adding Factors | |
template<typename T > | |
void | addExpressionFactor (const Expression< T > &h, const T &z, const SharedNoiseModel &R) |
Public Member Functions inherited from gtsam::NonlinearFactorGraph | |
NonlinearFactorGraph () | |
template<typename ITERATOR > | |
NonlinearFactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
template<class CONTAINER > | |
NonlinearFactorGraph (const CONTAINER &factors) | |
template<class DERIVEDFACTOR > | |
NonlinearFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph) | |
void | print (const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
void | printErrors (const Values &values, const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) {return true;}) const |
bool | equals (const NonlinearFactorGraph &other, double tol=1e-9) const |
void | dot (std::ostream &os, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const |
Output to graphviz format, stream version, with Values/extra options. More... | |
std::string | dot (const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const |
Output to graphviz format string, with Values/extra options. More... | |
void | saveGraph (const std::string &filename, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const |
output to file with graphviz format, with Values/extra options. More... | |
double | error (const Values &values) const |
double | probPrime (const Values &values) const |
std::shared_ptr< SymbolicFactorGraph > | symbolic () const |
Ordering | orderingCOLAMD () const |
Ordering | orderingCOLAMDConstrained (const FastMap< Key, int > &constraints) const |
std::shared_ptr< GaussianFactorGraph > | linearize (const Values &linearizationPoint) const |
Linearize a nonlinear factor graph. More... | |
std::shared_ptr< HessianFactor > | linearizeToHessianFactor (const Values &values, const Dampen &dampen=nullptr) const |
std::shared_ptr< HessianFactor > | linearizeToHessianFactor (const Values &values, const Ordering &ordering, const Dampen &dampen=nullptr) const |
Values | updateCholesky (const Values &values, const Dampen &dampen=nullptr) const |
Values | updateCholesky (const Values &values, const Ordering &ordering, const Dampen &dampen=nullptr) const |
NonlinearFactorGraph | clone () const |
Clone() performs a deep-copy of the graph, including all of the factors. More... | |
NonlinearFactorGraph | rekey (const std::map< Key, Key > &rekey_mapping) const |
template<typename T > | |
void | addExpressionFactor (const SharedNoiseModel &R, const T &z, const Expression< T > &h) |
template<typename T > | |
void | addPrior (Key key, const T &prior, const SharedNoiseModel &model=nullptr) |
template<typename T > | |
void | addPrior (Key key, const T &prior, const Matrix &covariance) |
Public Member Functions inherited from gtsam::FactorGraph< NonlinearFactor > | |
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 | |
Public Types inherited from gtsam::NonlinearFactorGraph | |
typedef FactorGraph< NonlinearFactor > | Base |
typedef std::shared_ptr< This > | shared_ptr |
typedef NonlinearFactorGraph | This |
typedef std::function< void(const std::shared_ptr< HessianFactor > &hessianFactor)> | Dampen |
typdef for dampen functions used below More... | |
Public Types inherited from gtsam::FactorGraph< NonlinearFactor > | |
typedef FastVector< sharedFactor >::const_iterator | const_iterator |
typedef NonlinearFactor | FactorType |
factor type More... | |
typedef FastVector< sharedFactor >::iterator | iterator |
typedef std::shared_ptr< NonlinearFactor > | sharedFactor |
Shared pointer to a factor. More... | |
typedef sharedFactor | value_type |
Protected Member Functions inherited from gtsam::FactorGraph< NonlinearFactor > | |
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< NonlinearFactor > | |
FastVector< sharedFactor > | factors_ |
Factor graph that supports adding ExpressionFactors directly
Definition at line 29 of file ExpressionFactorGraph.h.
|
inline |
Directly add ExpressionFactor that implements |h(x)-z|^2_R
h | expression that implements measurement function |
z | measurement |
R | model |
Definition at line 43 of file ExpressionFactorGraph.h.