30 : values_(solution), factorization_(factorization) {
31 gttic(MarginalsConstructor);
40 gttic(MarginalsConstructor);
48 gttic(MarginalsConstructor);
56 gttic(MarginalsConstructor);
63 gttic(MarginalsConstructor);
64 for (
const auto& keyValue: solution) {
74 gttic(MarginalsConstructor);
75 for (
const auto& keyValue: solution) {
117 throw std::runtime_error(
"Marginals::marginalFactor: Unknown factorization");
145 if(variables.size() == 1)
148 std::vector<size_t> dims;
149 dims.push_back(info.rows());
156 if(variables.size() == 2) {
170 Matrix info = augmentedInfo.topLeftCorner(augmentedInfo.rows()-1, augmentedInfo.cols()-1);
174 std::sort(variablesSorted.begin(), variablesSorted.end());
177 std::vector<size_t> dims;
178 dims.reserve(variablesSorted.size());
179 for(
const auto&
key: variablesSorted) {
194 cout << s <<
"Joint marginal on keys ";
196 for(
const auto&
key: keys_) {
203 cout <<
". Use 'at' or 'operator()' to query matrix blocks." << endl;
GaussianFactorGraph graph_
void insert(Key j, const Value &val)
static enum @843 ordering
boost::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
boost::shared_ptr< BayesTreeType > marginalMultifrontalBayesTree(boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
JointMarginal jointMarginalCovariance(const KeyVector &variables) const
NonlinearFactorGraph graph
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
const KeyFormatter & formatter
VectorValues optimize() const
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
void invertInPlace()
Invert the entire active matrix in place.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
GaussianBayesTree bayesTree_
constexpr int first(int i)
Implementation details for constexpr functions.
SymmetricBlockMatrix blockMatrix_
const ValueType at(Key j) const
Marginals()
Default constructor only for wrappers.
JointMarginal jointMarginalInformation(const KeyVector &variables) const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Matrix augmentedHessian(const Ordering &ordering) const
Contains the HessianFactor class, a general quadratic factor.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
print out graph
Factorization factorization_
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const
Matrix marginalCovariance(Key variable) const
VectorValues optimize() const
A class for computing marginals in a NonlinearFactorGraph.
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
GaussianFactor::shared_ptr marginalFactor(Key variable) const
void print(const std::string &str="Marginals: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
std::uint64_t Key
Integer nonlinear key type.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
sharedFactorGraph joint(Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Matrix marginalInformation(Key variable) const