From e73d8a97421701aea6d0610cd1ad79f9832482d0 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Thu, 24 Nov 2016 19:23:22 -0500 Subject: [PATCH] add missing constructors and copy constructors --- cython/gtsam.h | 59 ++++++++++++++++++++++++++++++++++++++++---------- 1 file changed, 47 insertions(+), 12 deletions(-) diff --git a/cython/gtsam.h b/cython/gtsam.h index 8455b7793..da5f277af 100644 --- a/cython/gtsam.h +++ b/cython/gtsam.h @@ -638,7 +638,7 @@ class Cal3_S2 { Cal3_S2(double fx, double fy, double s, double u0, double v0); Cal3_S2(Vector v); Cal3_S2(double fov, int w, int h); - Cal3_S2(const gtsam::Cal3_S2& pose); + Cal3_S2(const gtsam::Cal3_S2& other); // Testable void print(string s) const; @@ -1497,6 +1497,7 @@ class GaussianFactorGraph { #include virtual class GaussianConditional : gtsam::GaussianFactor { //Constructors + GaussianConditional(); 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); @@ -1505,9 +1506,9 @@ virtual class GaussianConditional : gtsam::GaussianFactor { //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); GaussianConditional(const gtsam::GaussianConditional& other); //Standard Interface @@ -1527,8 +1528,9 @@ virtual class GaussianConditional : gtsam::GaussianFactor { #include virtual class GaussianDensity : gtsam::GaussianConditional { //Constructors - GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); + GaussianDensity(); GaussianDensity(const gtsam::GaussianDensity& other); + GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); //Standard Interface void print(string s) const; @@ -1541,8 +1543,8 @@ virtual class GaussianDensity : gtsam::GaussianConditional { virtual class GaussianBayesNet { //Constructors GaussianBayesNet(); - GaussianBayesNet(const gtsam::GaussianConditional* conditional); GaussianBayesNet(const gtsam::GaussianBayesNet& other); + GaussianBayesNet(const gtsam::GaussianConditional* conditional); // Testable void print(string s) const; @@ -1601,8 +1603,8 @@ virtual class GaussianBayesTree { class Errors { //Constructors Errors(); - Errors(const gtsam::VectorValues& V); Errors(const gtsam::Errors& other); + Errors(const gtsam::VectorValues& V); //Testable void print(string s); @@ -1709,8 +1711,8 @@ void PrintKeySet (const gtsam::KeySet& keys, string s); #include class LabeledSymbol { LabeledSymbol(); - LabeledSymbol(size_t full_key); LabeledSymbol(const gtsam::LabeledSymbol& key); + LabeledSymbol(size_t full_key); LabeledSymbol(unsigned char valType, unsigned char label, size_t j); size_t key() const; @@ -1836,6 +1838,8 @@ class Values { // enabling serialization functionality void serialize() const; + // void insert(size_t j, const gtsam::Value& v); + // New in 4.0, we have to specialize every insert/update/at to generate wrappers // Instead of the old: // void insert(size_t j, const gtsam::Value& value); @@ -1845,20 +1849,51 @@ class Values { template void insert(size_t j, const T& t); template void update(size_t j, const T& t); - template + gtsam::Cal3Bundler, gtsam::EssentialMatrix, + gtsam::SimpleCamera, gtsam::imuBias::ConstantBias, + Vector, Matrix}> T at(size_t j); /// version for double