diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 87bcfa16d..5092713b7 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -17,6 +17,8 @@ namespace gtsam { #include #include #include +#include +#include #include #include #include @@ -74,6 +76,8 @@ class NonlinearFactorGraph { gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, + gtsam::Similarity2, + gtsam::Similarity3, gtsam::Cal3_S2, gtsam::Cal3f, gtsam::Cal3Bundler, @@ -544,7 +548,7 @@ class ISAM2 { bool valueExists(gtsam::Key key) const; gtsam::Values calculateEstimate() const; template , @@ -609,6 +613,8 @@ template template , gtsam::PinholeCamera, gtsam::PinholeCamera, @@ -651,7 +657,7 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor { template , gtsam::PinholeCamera, gtsam::PinholeCamera, @@ -720,7 +726,7 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother { gtsam::NonlinearFactorGraph getFactors() const; template VALUE calculateEstimate(size_t key) const; }; @@ -732,6 +738,8 @@ template virtual class ExtendedKalmanFilter { diff --git a/gtsam/nonlinear/values.i b/gtsam/nonlinear/values.i index 99548d8ec..e1fc6666f 100644 --- a/gtsam/nonlinear/values.i +++ b/gtsam/nonlinear/values.i @@ -17,6 +17,8 @@ namespace gtsam { #include #include #include +#include +#include #include #include #include @@ -80,6 +82,8 @@ class Values { void insert(size_t j, const gtsam::SOn& P); void insert(size_t j, const gtsam::Rot3& rot3); void insert(size_t j, const gtsam::Pose3& pose3); + void insert(size_t j, const gtsam::Similarity2& similarity2); + void insert(size_t j, const gtsam::Similarity3& similarity3); void insert(size_t j, const gtsam::Unit3& unit3); void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler); void insert(size_t j, const gtsam::Cal3f& cal3f); @@ -122,6 +126,8 @@ class Values { void update(size_t j, const gtsam::SOn& P); void update(size_t j, const gtsam::Rot3& rot3); void update(size_t j, const gtsam::Pose3& pose3); + void update(size_t j, const gtsam::Similarity2& similarity2); + void update(size_t j, const gtsam::Similarity3& similarity3); void update(size_t j, const gtsam::Unit3& unit3); void update(size_t j, const gtsam::Cal3Bundler& cal3bundler); void update(size_t j, const gtsam::Cal3f& cal3f); @@ -161,6 +167,8 @@ class Values { void insert_or_assign(size_t j, const gtsam::SOn& P); void insert_or_assign(size_t j, const gtsam::Rot3& rot3); void insert_or_assign(size_t j, const gtsam::Pose3& pose3); + void insert_or_assign(size_t j, const gtsam::Similarity2& similarity2); + void insert_or_assign(size_t j, const gtsam::Similarity3& similarity3); void insert_or_assign(size_t j, const gtsam::Unit3& unit3); void insert_or_assign(size_t j, const gtsam::Cal3Bundler& cal3bundler); void insert_or_assign(size_t j, const gtsam::Cal3f& cal3f); @@ -196,6 +204,8 @@ class Values { gtsam::SOn, gtsam::Rot3, gtsam::Pose3, + gtsam::Similarity2, + gtsam::Similarity3, gtsam::Unit3, gtsam::Cal3Bundler, gtsam::Cal3f,