Expose things in the wrapper
parent
ebe3aadada
commit
733f3e5f86
|
@ -102,6 +102,7 @@ virtual class DiscreteConditional : gtsam::DecisionTreeFactor {
|
||||||
const gtsam::KeyFormatter& keyFormatter =
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
gtsam::DefaultKeyFormatter) const;
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::DiscreteConditional& other, double tol = 1e-9) const;
|
bool equals(const gtsam::DiscreteConditional& other, double tol = 1e-9) const;
|
||||||
|
gtsam::Key firstFrontalKey() const;
|
||||||
size_t nrFrontals() const;
|
size_t nrFrontals() const;
|
||||||
size_t nrParents() const;
|
size_t nrParents() const;
|
||||||
void printSignature(
|
void printSignature(
|
||||||
|
@ -156,10 +157,13 @@ class DiscreteBayesNet {
|
||||||
const gtsam::KeyFormatter& keyFormatter =
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
gtsam::DefaultKeyFormatter) const;
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::DiscreteBayesNet& other, double tol = 1e-9) const;
|
bool equals(const gtsam::DiscreteBayesNet& other, double tol = 1e-9) const;
|
||||||
string dot(const gtsam::KeyFormatter& keyFormatter =
|
string dot(
|
||||||
gtsam::DefaultKeyFormatter) const;
|
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
|
||||||
void saveGraph(string s, const gtsam::KeyFormatter& keyFormatter =
|
const gtsam::DotWriter& writer = gtsam::DotWriter()) const;
|
||||||
gtsam::DefaultKeyFormatter) const;
|
void saveGraph(
|
||||||
|
string s,
|
||||||
|
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
|
||||||
|
const gtsam::DotWriter& writer = gtsam::DotWriter()) const;
|
||||||
double operator()(const gtsam::DiscreteValues& values) const;
|
double operator()(const gtsam::DiscreteValues& values) const;
|
||||||
gtsam::DiscreteValues sample() const;
|
gtsam::DiscreteValues sample() const;
|
||||||
gtsam::DiscreteValues sample(gtsam::DiscreteValues given) const;
|
gtsam::DiscreteValues sample(gtsam::DiscreteValues given) const;
|
||||||
|
|
|
@ -127,6 +127,8 @@ class DotWriter {
|
||||||
bool plotFactorPoints;
|
bool plotFactorPoints;
|
||||||
bool connectKeysToFactor;
|
bool connectKeysToFactor;
|
||||||
bool binaryEdges;
|
bool binaryEdges;
|
||||||
|
|
||||||
|
std::map<gtsam::Key, gtsam::Vector2> variablePositions;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/inference/VariableIndex.h>
|
#include <gtsam/inference/VariableIndex.h>
|
||||||
|
|
|
@ -443,36 +443,39 @@ class GaussianFactorGraph {
|
||||||
|
|
||||||
#include <gtsam/linear/GaussianConditional.h>
|
#include <gtsam/linear/GaussianConditional.h>
|
||||||
virtual class GaussianConditional : gtsam::JacobianFactor {
|
virtual class GaussianConditional : gtsam::JacobianFactor {
|
||||||
//Constructors
|
// Constructors
|
||||||
GaussianConditional(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas);
|
GaussianConditional(size_t key, Vector d, Matrix R,
|
||||||
|
const gtsam::noiseModel::Diagonal* sigmas);
|
||||||
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
||||||
const gtsam::noiseModel::Diagonal* sigmas);
|
const gtsam::noiseModel::Diagonal* sigmas);
|
||||||
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
||||||
size_t name2, Matrix T, const gtsam::noiseModel::Diagonal* sigmas);
|
size_t name2, Matrix T,
|
||||||
|
const gtsam::noiseModel::Diagonal* sigmas);
|
||||||
|
|
||||||
//Constructors with no noise model
|
// Constructors with no noise model
|
||||||
GaussianConditional(size_t key, Vector d, Matrix R);
|
GaussianConditional(size_t key, Vector d, Matrix R);
|
||||||
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S);
|
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S);
|
||||||
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
|
||||||
size_t name2, Matrix T);
|
size_t name2, Matrix T);
|
||||||
|
|
||||||
//Standard Interface
|
// Standard Interface
|
||||||
void print(string s = "GaussianConditional",
|
void print(string s = "GaussianConditional",
|
||||||
const gtsam::KeyFormatter& keyFormatter =
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
gtsam::DefaultKeyFormatter) const;
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
|
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
|
||||||
|
gtsam::Key firstFrontalKey() const;
|
||||||
|
|
||||||
|
// Advanced Interface
|
||||||
|
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
|
||||||
|
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
||||||
|
const gtsam::VectorValues& rhs) const;
|
||||||
|
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
||||||
|
Matrix R() const;
|
||||||
|
Matrix S() const;
|
||||||
|
Vector d() const;
|
||||||
|
|
||||||
// Advanced Interface
|
// enabling serialization functionality
|
||||||
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
|
void serialize() const;
|
||||||
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
|
||||||
const gtsam::VectorValues& rhs) const;
|
|
||||||
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
|
||||||
Matrix R() const;
|
|
||||||
Matrix S() const;
|
|
||||||
Vector d() const;
|
|
||||||
|
|
||||||
// enabling serialization functionality
|
|
||||||
void serialize() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/linear/GaussianDensity.h>
|
#include <gtsam/linear/GaussianDensity.h>
|
||||||
|
|
|
@ -98,6 +98,7 @@ virtual class SymbolicConditional : gtsam::SymbolicFactor {
|
||||||
bool equals(const gtsam::SymbolicConditional& other, double tol) const;
|
bool equals(const gtsam::SymbolicConditional& other, double tol) const;
|
||||||
|
|
||||||
// Standard interface
|
// Standard interface
|
||||||
|
gtsam::Key firstFrontalKey() const;
|
||||||
size_t nrFrontals() const;
|
size_t nrFrontals() const;
|
||||||
size_t nrParents() const;
|
size_t nrParents() const;
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue