diff --git a/gtsam/discrete/discrete.i b/gtsam/discrete/discrete.i index 80b8df1bc..9db1cb7f6 100644 --- a/gtsam/discrete/discrete.i +++ b/gtsam/discrete/discrete.i @@ -102,6 +102,7 @@ virtual class DiscreteConditional : gtsam::DecisionTreeFactor { const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::DiscreteConditional& other, double tol = 1e-9) const; + gtsam::Key firstFrontalKey() const; size_t nrFrontals() const; size_t nrParents() const; void printSignature( @@ -156,10 +157,13 @@ class DiscreteBayesNet { const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::DiscreteBayesNet& other, double tol = 1e-9) const; - string dot(const gtsam::KeyFormatter& keyFormatter = - gtsam::DefaultKeyFormatter) const; - void saveGraph(string s, const gtsam::KeyFormatter& keyFormatter = - gtsam::DefaultKeyFormatter) const; + string dot( + const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter, + const gtsam::DotWriter& writer = gtsam::DotWriter()) 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; gtsam::DiscreteValues sample() const; gtsam::DiscreteValues sample(gtsam::DiscreteValues given) const; diff --git a/gtsam/inference/inference.i b/gtsam/inference/inference.i index 5b9cef7ef..862c49178 100644 --- a/gtsam/inference/inference.i +++ b/gtsam/inference/inference.i @@ -127,6 +127,8 @@ class DotWriter { bool plotFactorPoints; bool connectKeysToFactor; bool binaryEdges; + + std::map variablePositions; }; #include diff --git a/gtsam/linear/linear.i b/gtsam/linear/linear.i index d2a86ddc8..f17e95620 100644 --- a/gtsam/linear/linear.i +++ b/gtsam/linear/linear.i @@ -443,36 +443,39 @@ class GaussianFactorGraph { #include virtual class GaussianConditional : gtsam::JacobianFactor { - //Constructors - GaussianConditional(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); + // Constructors + 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, - const gtsam::noiseModel::Diagonal* sigmas); + const gtsam::noiseModel::Diagonal* sigmas); 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, size_t name1, Matrix S); - GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, - size_t name2, Matrix T); + 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); - //Standard Interface - void print(string s = "GaussianConditional", - const gtsam::KeyFormatter& keyFormatter = - gtsam::DefaultKeyFormatter) const; - bool equals(const gtsam::GaussianConditional& cg, double tol) const; + // Standard Interface + void print(string s = "GaussianConditional", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) 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 - 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; - - // enabling serialization functionality - void serialize() const; + // enabling serialization functionality + void serialize() const; }; #include diff --git a/gtsam/symbolic/symbolic.i b/gtsam/symbolic/symbolic.i index 771e5309a..0297b6c4a 100644 --- a/gtsam/symbolic/symbolic.i +++ b/gtsam/symbolic/symbolic.i @@ -98,6 +98,7 @@ virtual class SymbolicConditional : gtsam::SymbolicFactor { bool equals(const gtsam::SymbolicConditional& other, double tol) const; // Standard interface + gtsam::Key firstFrontalKey() const; size_t nrFrontals() const; size_t nrParents() const; };