111 Matrix marginalInformation(
Key variable)
const;
114 Matrix marginalCovariance(
Key variable)
const;
128 void computeBayesTree();
131 void computeBayesTree(
const Ordering& ordering);
136 const Ordering& ordering) :
Marginals(graph, solution, ordering, factorization) {}
140 const Ordering& ordering) :
Marginals(graph, solution, ordering, factorization) {}
144 const Ordering& ordering) :
Marginals(graph, solution, ordering, factorization) {}
176 const auto indexI = indices_.at(iVariable);
177 const auto indexJ = indices_.at(jVariable);
178 return blockMatrix_.
block(indexI, indexJ);
183 return (*
this)(iVariable, jVariable);
196 blockMatrix_(dims, fullMatrix), keys_(keys), indices_(
Ordering(keys).invert()) {}
void print(const Matrix &A, const string &s, ostream &stream)
GaussianFactorGraph graph_
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
static enum @843 ordering
NonlinearFactorGraph graph
Matrix operator()(Key iVariable, Key jVariable) const
static const KeyFormatter DefaultKeyFormatter
const KeyFormatter & formatter
JointMarginal(const Matrix &fullMatrix, const std::vector< size_t > &dims, const KeyVector &keys)
Marginals(const GaussianFactorGraph &graph, const Values &solution, Factorization factorization, const Ordering &ordering)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
GaussianBayesTree bayesTree_
SymmetricBlockMatrix blockMatrix_
Marginals(const GaussianFactorGraph &graph, const VectorValues &solution, Factorization factorization, const Ordering &ordering)
FastMap< Key, size_t > indices_
Marginals()
Default constructor only for wrappers.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Matrix at(Key iVariable, Key jVariable) const
JointMarginal()
Default constructor only for wrappers.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Matrix block(DenseIndex I, DenseIndex J) const
Factorization factorization_
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
Matrix fullMatrix() const
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
Marginals(const NonlinearFactorGraph &graph, const Values &solution, Factorization factorization, const Ordering &ordering)
std::uint64_t Key
Integer nonlinear key type.