From 405771397ba3938f094f7d023e75ccbb9a8e3ea3 Mon Sep 17 00:00:00 2001 From: Tim McGrath Date: Sat, 31 Oct 2020 13:40:05 -0400 Subject: [PATCH] adding additional Unit3 support in the wrapper: PriorFactorUnit3, Values::insert/update/at(Unit3) --- gtsam/gtsam.i | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 575a216d62..b578d134d7 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -2157,6 +2157,7 @@ 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::Unit3& unit3); void insert(size_t j, const gtsam::Cal3_S2& cal3_s2); void insert(size_t j, const gtsam::Cal3DS2& cal3ds2); void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler); @@ -2175,6 +2176,7 @@ 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::Unit3& unit3); void update(size_t j, const gtsam::Cal3_S2& cal3_s2); void update(size_t j, const gtsam::Cal3DS2& cal3ds2); void update(size_t j, const gtsam::Cal3Bundler& cal3bundler); @@ -2186,7 +2188,7 @@ class Values { void update(size_t j, Vector vector); void update(size_t j, Matrix matrix); - template, gtsam::imuBias::ConstantBias, gtsam::NavState, Vector, Matrix}> + template, gtsam::imuBias::ConstantBias, gtsam::NavState, Vector, Matrix}> T at(size_t j); /// version for double @@ -2529,7 +2531,7 @@ class NonlinearISAM { #include #include -template}> +template}> virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const;