Wrapped GaussianMultifrontalSolver
parent
24111423d7
commit
c251487baf
14
gtsam.h
14
gtsam.h
|
|
@ -1316,6 +1316,20 @@ class GaussianSequentialSolver {
|
||||||
Matrix marginalCovariance(size_t j) const;
|
Matrix marginalCovariance(size_t j) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/linear/GaussianMultifrontalSolver.h>
|
||||||
|
class GaussianMultifrontalSolver {
|
||||||
|
//Constructors
|
||||||
|
GaussianMultifrontalSolver(const gtsam::GaussianFactorGraph& graph,
|
||||||
|
bool useQR);
|
||||||
|
|
||||||
|
//Standard Interface
|
||||||
|
void replaceFactors(const gtsam::GaussianFactorGraph* factorGraph);
|
||||||
|
gtsam::GaussianBayesTree* eliminate() const;
|
||||||
|
gtsam::VectorValues* optimize() const;
|
||||||
|
gtsam::GaussianFactor* marginalFactor(size_t j) const;
|
||||||
|
Matrix marginalCovariance(size_t j) const;
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/linear/IterativeSolver.h>
|
#include <gtsam/linear/IterativeSolver.h>
|
||||||
virtual class IterativeOptimizationParameters {
|
virtual class IterativeOptimizationParameters {
|
||||||
string getKernel() const ;
|
string getKernel() const ;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue