|
| void | addCameraConstraint (int j, const GeneralCamera &p) |
| |
| void | addCameraConstraint (int j, const GeneralCamera &p) |
| |
| void | addMeasurement (const int &i, const int &j, const Point2 &z, const SharedNoiseModel &model) |
| |
| void | addMeasurement (int i, int j, const Point2 &z, const SharedNoiseModel &model) |
| |
| void | addPoint3Constraint (int j, const Point3 &p) |
| |
| void | addPoint3Constraint (int j, const Point3 &p) |
| |
| | 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...
|
| |
| 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...
|
| |
| 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) |
| |
| | 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 >::type & | operator+= (std::shared_ptr< DERIVEDFACTOR > factor) |
| | Append factor to factor graph. More...
|
| |
| std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, This >::type & | operator, (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) |
| |
| This & | operator+= (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) |
| |
| 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 |
| |
| 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 |
| |