wrap sampling methods
parent
539bf70829
commit
a25378abe7
|
@ -482,15 +482,19 @@ virtual class GaussianConditional : gtsam::JacobianFactor {
|
||||||
gtsam::Key parent2,
|
gtsam::Key parent2,
|
||||||
const Vector& b,
|
const Vector& b,
|
||||||
double sigma);
|
double sigma);
|
||||||
// Standard Interface
|
// Testable
|
||||||
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;
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
gtsam::Key firstFrontalKey() const;
|
gtsam::Key firstFrontalKey() const;
|
||||||
|
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
|
||||||
|
gtsam::VectorValues sample(const gtsam::VectorValues& parents) const;
|
||||||
|
gtsam::VectorValues sample() const;
|
||||||
|
|
||||||
// Advanced Interface
|
// Advanced Interface
|
||||||
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
|
|
||||||
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
||||||
const gtsam::VectorValues& rhs) const;
|
const gtsam::VectorValues& rhs) const;
|
||||||
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
||||||
|
@ -512,11 +516,13 @@ virtual class GaussianDensity : gtsam::GaussianConditional {
|
||||||
const Vector& mean,
|
const Vector& mean,
|
||||||
double sigma);
|
double sigma);
|
||||||
|
|
||||||
// Standard Interface
|
// Testable
|
||||||
void print(string s = "GaussianDensity",
|
void print(string s = "GaussianDensity",
|
||||||
const gtsam::KeyFormatter& keyFormatter =
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
gtsam::DefaultKeyFormatter) const;
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianDensity& cg, double tol) const;
|
bool equals(const gtsam::GaussianDensity& cg, double tol) const;
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
Vector mean() const;
|
Vector mean() const;
|
||||||
Matrix covariance() const;
|
Matrix covariance() const;
|
||||||
};
|
};
|
||||||
|
@ -533,6 +539,21 @@ virtual class GaussianBayesNet {
|
||||||
bool equals(const gtsam::GaussianBayesNet& other, double tol) const;
|
bool equals(const gtsam::GaussianBayesNet& other, double tol) const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
|
|
||||||
|
// Standard interface
|
||||||
|
void push_back(gtsam::GaussianConditional* conditional);
|
||||||
|
void push_back(const gtsam::GaussianBayesNet& bayesNet);
|
||||||
|
gtsam::GaussianConditional* front() const;
|
||||||
|
gtsam::GaussianConditional* back() const;
|
||||||
|
|
||||||
|
gtsam::VectorValues optimize() const;
|
||||||
|
gtsam::VectorValues optimize(gtsam::VectorValues given) const;
|
||||||
|
gtsam::VectorValues optimizeGradientSearch() const;
|
||||||
|
|
||||||
|
gtsam::VectorValues sample(gtsam::VectorValues given) const;
|
||||||
|
gtsam::VectorValues sample() const;
|
||||||
|
gtsam::VectorValues backSubstitute(const gtsam::VectorValues& gx) const;
|
||||||
|
gtsam::VectorValues backSubstituteTranspose(const gtsam::VectorValues& gx) const;
|
||||||
|
|
||||||
// FactorGraph derived interface
|
// FactorGraph derived interface
|
||||||
gtsam::GaussianConditional* at(size_t idx) const;
|
gtsam::GaussianConditional* at(size_t idx) const;
|
||||||
gtsam::KeySet keys() const;
|
gtsam::KeySet keys() const;
|
||||||
|
@ -541,22 +562,12 @@ virtual class GaussianBayesNet {
|
||||||
|
|
||||||
void saveGraph(const string& s) const;
|
void saveGraph(const string& s) const;
|
||||||
|
|
||||||
gtsam::GaussianConditional* front() const;
|
|
||||||
gtsam::GaussianConditional* back() const;
|
|
||||||
void push_back(gtsam::GaussianConditional* conditional);
|
|
||||||
void push_back(const gtsam::GaussianBayesNet& bayesNet);
|
|
||||||
|
|
||||||
gtsam::VectorValues optimize() const;
|
|
||||||
gtsam::VectorValues optimize(gtsam::VectorValues& solutionForMissing) const;
|
|
||||||
std::pair<Matrix, Vector> matrix() const;
|
std::pair<Matrix, Vector> matrix() const;
|
||||||
gtsam::VectorValues optimizeGradientSearch() const;
|
|
||||||
gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const;
|
gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const;
|
||||||
gtsam::VectorValues gradientAtZero() const;
|
gtsam::VectorValues gradientAtZero() const;
|
||||||
double error(const gtsam::VectorValues& x) const;
|
double error(const gtsam::VectorValues& x) const;
|
||||||
double determinant() const;
|
double determinant() const;
|
||||||
double logDeterminant() const;
|
double logDeterminant() const;
|
||||||
gtsam::VectorValues backSubstitute(const gtsam::VectorValues& gx) const;
|
|
||||||
gtsam::VectorValues backSubstituteTranspose(const gtsam::VectorValues& gx) const;
|
|
||||||
|
|
||||||
string dot(
|
string dot(
|
||||||
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
|
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
|
||||||
|
|
Loading…
Reference in New Issue