| _FactorType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | private |
| add(const GaussianFactor &factor) | gtsam::GaussianFactorGraph | inline |
| add(const sharedFactor &factor) | gtsam::GaussianFactorGraph | inline |
| add(const Vector &b) | gtsam::GaussianFactorGraph | inline |
| add(Key key1, const Matrix &A1, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) | gtsam::GaussianFactorGraph | inline |
| add(Key key1, const Matrix &A1, Key key2, const Matrix &A2, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) | gtsam::GaussianFactorGraph | inline |
| add(Key key1, const Matrix &A1, Key key2, const Matrix &A2, Key key3, const Matrix &A3, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) | gtsam::GaussianFactorGraph | inline |
| add(const TERMS &terms, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) | gtsam::GaussianFactorGraph | inline |
| FactorGraph< GaussianFactor >::add(std::shared_ptr< DERIVEDFACTOR > factor) | gtsam::FactorGraph< GaussianFactor > | inline |
| FactorGraph< GaussianFactor >::add(const FACTOR_OR_CONTAINER &factorOrContainer) | gtsam::FactorGraph< GaussianFactor > | inline |
| add_factors(const CONTAINER &factors, bool useEmptySlots=false) | gtsam::FactorGraph< GaussianFactor > | |
| asDerived() const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | inlineprivate |
| asDerived() | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | inlineprivate |
| at(size_t i) const | gtsam::FactorGraph< GaussianFactor > | inline |
| at(size_t i) | gtsam::FactorGraph< GaussianFactor > | inline |
| at(size_t i) | gtsam::FactorGraph< GaussianFactor > | inline |
| at(size_t i) const | gtsam::FactorGraph< GaussianFactor > | inline |
| augmentedHessian(const Ordering &ordering) const | gtsam::GaussianFactorGraph | |
| augmentedHessian() const | gtsam::GaussianFactorGraph | |
| augmentedJacobian(const Ordering &ordering) const | gtsam::GaussianFactorGraph | |
| augmentedJacobian() const | gtsam::GaussianFactorGraph | |
| back() const | gtsam::FactorGraph< GaussianFactor > | inline |
| Base typedef | gtsam::GaussianFactorGraph | |
| BaseEliminateable typedef | gtsam::GaussianFactorGraph | |
| BayesNetType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| BayesTreeType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| begin() const | gtsam::FactorGraph< GaussianFactor > | inline |
| begin() | gtsam::FactorGraph< GaussianFactor > | inline |
| clone() const | gtsam::GaussianFactorGraph | virtual |
| cloneToPtr() const | gtsam::GaussianFactorGraph | virtual |
| ConditionalType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| const_iterator typedef | gtsam::FactorGraph< GaussianFactor > | |
| dot(std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const | gtsam::FactorGraph< GaussianFactor > | |
| dot(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const | gtsam::FactorGraph< GaussianFactor > | |
| Eliminate typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminateMultifrontal(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminatePartialMultifrontal(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminatePartialMultifrontal(const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminatePartialSequential(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminatePartialSequential(const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| eliminateSequential(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| EliminationResult typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| EliminationTraitsType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| EliminationTreeType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| emplace_shared(Args &&... args) | gtsam::FactorGraph< GaussianFactor > | inline |
| empty() const | gtsam::FactorGraph< GaussianFactor > | inline |
| end() const | gtsam::FactorGraph< GaussianFactor > | inline |
| end() | gtsam::FactorGraph< GaussianFactor > | inline |
| equals(const This &fg, double tol=1e-9) const | gtsam::GaussianFactorGraph | |
| FactorGraph< GaussianFactor >::equals(const This &fg, double tol=1e-9) const | gtsam::FactorGraph< GaussianFactor > | |
| erase(iterator item) | gtsam::FactorGraph< GaussianFactor > | inline |
| erase(iterator first, iterator last) | gtsam::FactorGraph< GaussianFactor > | inline |
| error(const VectorValues &x) const | gtsam::GaussianFactorGraph | |
| FactorGraph< GaussianFactor >::error(const HybridValues &values) const | gtsam::FactorGraph< GaussianFactor > | |
| exists(size_t idx) const | gtsam::FactorGraph< GaussianFactor > | inline |
| FactorGraph() | gtsam::FactorGraph< GaussianFactor > | inlineprotected |
| FactorGraph(ITERATOR firstFactor, ITERATOR lastFactor) | gtsam::FactorGraph< GaussianFactor > | inlineprotected |
| FactorGraph(const CONTAINER &factors) | gtsam::FactorGraph< GaussianFactor > | inlineexplicitprotected |
| FactorGraph(std::initializer_list< std::shared_ptr< DERIVEDFACTOR >> sharedFactors) | gtsam::FactorGraph< GaussianFactor > | inline |
| FactorGraphType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | private |
| factors_ | gtsam::FactorGraph< GaussianFactor > | protected |
| FactorType typedef | gtsam::FactorGraph< GaussianFactor > | |
| front() const | gtsam::FactorGraph< GaussianFactor > | inline |
| gaussianErrors(const VectorValues &x) const | gtsam::GaussianFactorGraph | |
| GaussianFactorGraph() | gtsam::GaussianFactorGraph | inline |
| GaussianFactorGraph(std::initializer_list< sharedFactor > factors) | gtsam::GaussianFactorGraph | inline |
| GaussianFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor) | gtsam::GaussianFactorGraph | inline |
| GaussianFactorGraph(const CONTAINER &factors) | gtsam::GaussianFactorGraph | inlineexplicit |
| GaussianFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph) | gtsam::GaussianFactorGraph | inline |
| getKeyDimMap() const | gtsam::GaussianFactorGraph | |
| gradient(const VectorValues &x0) const | gtsam::GaussianFactorGraph | |
| gradientAtZero() const | gtsam::GaussianFactorGraph | virtual |
| HasDerivedElementType typedef | gtsam::FactorGraph< GaussianFactor > | private |
| HasDerivedValueType typedef | gtsam::FactorGraph< GaussianFactor > | private |
| hessian(const Ordering &ordering) const | gtsam::GaussianFactorGraph | |
| hessian() const | gtsam::GaussianFactorGraph | |
| hessianBlockDiagonal() const | gtsam::GaussianFactorGraph | virtual |
| hessianDiagonal() const | gtsam::GaussianFactorGraph | virtual |
| IsDerived typedef | gtsam::FactorGraph< GaussianFactor > | private |
| isEqual(const FactorGraph &other) const | gtsam::FactorGraph< GaussianFactor > | inlineprotected |
| iterator typedef | gtsam::FactorGraph< GaussianFactor > | |
| jacobian(const Ordering &ordering) const | gtsam::GaussianFactorGraph | |
| jacobian() const | gtsam::GaussianFactorGraph | |
| JunctionTreeType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| keys() const | gtsam::GaussianFactorGraph | |
| FactorGraph< GaussianFactor >::keys() const | gtsam::FactorGraph< GaussianFactor > | |
| Keys typedef | gtsam::GaussianFactorGraph | |
| keyVector() const | gtsam::FactorGraph< GaussianFactor > | |
| marginal(const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesNet(const Ordering &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesNet(const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesNet(const Ordering &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesNet(const KeyVector &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesTree(const Ordering &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesTree(const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesTree(const Ordering &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| marginalMultifrontalBayesTree(const KeyVector &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const | gtsam::GaussianFactorGraph | |
| multiplyInPlace(const VectorValues &x, Errors &e) const | gtsam::GaussianFactorGraph | |
| multiplyInPlace(const VectorValues &x, const Errors::iterator &e) const | gtsam::GaussianFactorGraph | |
| negate() const | gtsam::GaussianFactorGraph | |
| nrFactors() const | gtsam::FactorGraph< GaussianFactor > | |
| operator*(const VectorValues &x) const | gtsam::GaussianFactorGraph | |
| operator+=(std::shared_ptr< DERIVEDFACTOR > factor) | gtsam::FactorGraph< GaussianFactor > | inline |
| operator+=(const FACTOR_OR_CONTAINER &factorOrContainer) | gtsam::FactorGraph< GaussianFactor > | inline |
| operator,(std::shared_ptr< DERIVEDFACTOR > factor) | gtsam::FactorGraph< GaussianFactor > | inline |
| operator==(const GaussianFactorGraph &lhs, const GaussianFactorGraph &rhs) | gtsam::GaussianFactorGraph | friend |
| operator[](size_t i) const | gtsam::FactorGraph< GaussianFactor > | inline |
| operator[](size_t i) | gtsam::FactorGraph< GaussianFactor > | inline |
| optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const | gtsam::GaussianFactorGraph | |
| optimize(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const | gtsam::GaussianFactorGraph | |
| optimizeDensely() const | gtsam::GaussianFactorGraph | |
| optimizeGradientSearch() const | gtsam::GaussianFactorGraph | |
| OptionalOrderingType typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| OptionalVariableIndex typedef | gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
| print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const | gtsam::FactorGraph< GaussianFactor > | virtual |
| printErrors(const VectorValues &x, const std::string &str="GaussianFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) { return true;}) const | gtsam::GaussianFactorGraph | |
| probPrime(const VectorValues &c) const | gtsam::GaussianFactorGraph | |
| push_back(std::shared_ptr< DERIVEDFACTOR > factor) | gtsam::FactorGraph< GaussianFactor > | inline |
| push_back(const DERIVEDFACTOR &factor) | gtsam::FactorGraph< GaussianFactor > | inline |
| push_back(ITERATOR firstFactor, ITERATOR lastFactor) | gtsam::FactorGraph< GaussianFactor > | inline |
| push_back(ITERATOR firstFactor, ITERATOR lastFactor) | gtsam::FactorGraph< GaussianFactor > | inline |
| push_back(const CONTAINER &container) | gtsam::FactorGraph< GaussianFactor > | inline |
| push_back(const CONTAINER &container) | gtsam::FactorGraph< GaussianFactor > | inline |
| push_back(const BayesTree< CLIQUE > &bayesTree) | gtsam::FactorGraph< GaussianFactor > | inline |
| remove(size_t i) | gtsam::FactorGraph< GaussianFactor > | inline |
| replace(size_t index, sharedFactor factor) | gtsam::FactorGraph< GaussianFactor > | inline |
| reserve(size_t size) | gtsam::FactorGraph< GaussianFactor > | inline |
| resize(size_t size) | gtsam::FactorGraph< GaussianFactor > | inlinevirtual |
| saveGraph(const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const | gtsam::FactorGraph< GaussianFactor > | |
| shared_ptr typedef | gtsam::GaussianFactorGraph | |
| sharedFactor typedef | gtsam::FactorGraph< GaussianFactor > | |
| size() const | gtsam::FactorGraph< GaussianFactor > | inline |
| sparseJacobian(const Ordering &ordering, size_t &nrows, size_t &ncols) const | gtsam::GaussianFactorGraph | |
| sparseJacobian() const | gtsam::GaussianFactorGraph | |
| sparseJacobian_() const | gtsam::GaussianFactorGraph | |
| This typedef | gtsam::GaussianFactorGraph | |
| transposeMultiply(const Errors &e) const | gtsam::GaussianFactorGraph | |
| transposeMultiplyAdd(double alpha, const Errors &e, VectorValues &x) const | gtsam::GaussianFactorGraph | |
| value_type typedef | gtsam::FactorGraph< GaussianFactor > | |
| ~FactorGraph()=default | gtsam::FactorGraph< GaussianFactor > | virtual |