wrap keys for GaussianFactor

release/4.3a0
thduynguyen 2014-10-19 00:35:18 -04:00
parent 3227766569
commit 32586ad175
1 changed files with 4 additions and 0 deletions

View File

@ -1192,6 +1192,7 @@ class VectorValues {
#include <gtsam/linear/GaussianFactor.h> #include <gtsam/linear/GaussianFactor.h>
virtual class GaussianFactor { virtual class GaussianFactor {
gtsam::KeyVector keys() const;
void print(string s) const; void print(string s) const;
bool equals(const gtsam::GaussianFactor& lf, double tol) const; bool equals(const gtsam::GaussianFactor& lf, double tol) const;
double error(const gtsam::VectorValues& c) const; double error(const gtsam::VectorValues& c) const;
@ -1632,6 +1633,7 @@ class NonlinearFactorGraph {
void push_back(gtsam::NonlinearFactor* factor); void push_back(gtsam::NonlinearFactor* factor);
void add(gtsam::NonlinearFactor* factor); void add(gtsam::NonlinearFactor* factor);
bool exists(size_t idx) const; bool exists(size_t idx) const;
gtsam::KeySet keys() const;
// NonlinearFactorGraph // NonlinearFactorGraph
double error(const gtsam::Values& values) const; double error(const gtsam::Values& values) const;
@ -1639,6 +1641,7 @@ class NonlinearFactorGraph {
gtsam::Ordering orderingCOLAMD() const; gtsam::Ordering orderingCOLAMD() const;
// Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map<gtsam::Key,int>& constraints) const; // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map<gtsam::Key,int>& constraints) const;
gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const; gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const;
gtsam::GaussianFactorGraph* multipliedHessians(const gtsam::Values& values, const gtsam::VectorValues& duals) const;
gtsam::NonlinearFactorGraph clone() const; gtsam::NonlinearFactorGraph clone() const;
// enabling serialization functionality // enabling serialization functionality
@ -1649,6 +1652,7 @@ virtual class NonlinearFactor {
// Factor base class // Factor base class
size_t size() const; size_t size() const;
gtsam::KeyVector keys() const; gtsam::KeyVector keys() const;
size_t dualKey() const;
void print(string s) const; void print(string s) const;
void printKeys(string s) const; void printKeys(string s) const;
// NonlinearFactor // NonlinearFactor