From a25e3f6d38f853d53fb6935511a74546efc9ba1d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 2 Jan 2022 16:23:56 -0500 Subject: [PATCH] Remove deprecated methods from wrapper --- gtsam/linear/GaussianConditional.h | 2 +- gtsam/linear/linear.i | 1 - gtsam/navigation/navigation.i | 11 ----------- gtsam/slam/slam.i | 2 -- 4 files changed, 1 insertion(+), 15 deletions(-) diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 958f411f8..d93f65b42 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -128,7 +128,7 @@ namespace gtsam { #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 /** Scale the values in \c gy according to the sigmas for the frontal variables in this * conditional. */ - void scaleFrontalsBySigma(VectorValues& gy) const; + void GTSAM_DEPRECATED scaleFrontalsBySigma(VectorValues& gy) const; #endif private: diff --git a/gtsam/linear/linear.i b/gtsam/linear/linear.i index 7b1ce550f..7acc5bd41 100644 --- a/gtsam/linear/linear.i +++ b/gtsam/linear/linear.i @@ -467,7 +467,6 @@ virtual class GaussianConditional : gtsam::JacobianFactor { gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents, const gtsam::VectorValues& rhs) const; void solveTransposeInPlace(gtsam::VectorValues& gy) const; - void scaleFrontalsBySigma(gtsam::VectorValues& gy) const; Matrix R() const; Matrix S() const; Vector d() const; diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index c2a3bcdb4..6ede1645f 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -18,23 +18,12 @@ class ConstantBias { // Group static gtsam::imuBias::ConstantBias identity(); - gtsam::imuBias::ConstantBias inverse() const; - gtsam::imuBias::ConstantBias compose(const gtsam::imuBias::ConstantBias& b) const; - gtsam::imuBias::ConstantBias between(const gtsam::imuBias::ConstantBias& b) const; // Operator Overloads gtsam::imuBias::ConstantBias operator-() const; gtsam::imuBias::ConstantBias operator+(const gtsam::imuBias::ConstantBias& b) const; gtsam::imuBias::ConstantBias operator-(const gtsam::imuBias::ConstantBias& b) const; - // Manifold - gtsam::imuBias::ConstantBias retract(Vector v) const; - Vector localCoordinates(const gtsam::imuBias::ConstantBias& b) const; - - // Lie Group - static gtsam::imuBias::ConstantBias Expmap(Vector v); - static Vector Logmap(const gtsam::imuBias::ConstantBias& b); - // Standard Interface Vector vector() const; Vector accelerometer() const; diff --git a/gtsam/slam/slam.i b/gtsam/slam/slam.i index d276c4f2e..a0a7329dd 100644 --- a/gtsam/slam/slam.i +++ b/gtsam/slam/slam.i @@ -264,8 +264,6 @@ pair load2D( pair load2D( string filename, gtsam::noiseModel::Diagonal* model); pair load2D(string filename); -pair load2D_robust( - string filename, gtsam::noiseModel::Base* model, int maxIndex); void save2D(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config, gtsam::noiseModel::Diagonal* model, string filename);