From 0814efafd7be9a93e29911613c0e2089ec55de4a Mon Sep 17 00:00:00 2001 From: senselessDev Date: Sat, 22 Jan 2022 15:35:53 +0100 Subject: [PATCH] expose some iSAM2/FixedLagSmoothing functionality for the bindings --- gtsam/nonlinear/ISAM2Params.h | 7 +++++++ gtsam/nonlinear/nonlinear.i | 3 +++ gtsam_unstable/gtsam_unstable.i | 6 ++++++ 3 files changed, 16 insertions(+) diff --git a/gtsam/nonlinear/ISAM2Params.h b/gtsam/nonlinear/ISAM2Params.h index c6e1001c4..a939ab691 100644 --- a/gtsam/nonlinear/ISAM2Params.h +++ b/gtsam/nonlinear/ISAM2Params.h @@ -313,6 +313,10 @@ struct GTSAM_EXPORT ISAM2Params { return enablePartialRelinearizationCheck; } + bool isFindUnusedFactorSlots() const { + return findUnusedFactorSlots; + } + void setOptimizationParams(OptimizationParams optimizationParams) { this->optimizationParams = optimizationParams; } @@ -344,6 +348,9 @@ struct GTSAM_EXPORT ISAM2Params { bool enablePartialRelinearizationCheck) { this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck; } + void setFindUnusedFactorSlots(bool findUnusedFactorSlots) { + this->findUnusedFactorSlots = findUnusedFactorSlots; + } GaussianFactorGraph::Eliminate getEliminationFunction() const { return factorization == CHOLESKY diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 84c4939f4..bc07c334b 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -696,6 +696,9 @@ class ISAM2Params { bool isEnablePartialRelinearizationCheck() const; void setEnablePartialRelinearizationCheck( bool enablePartialRelinearizationCheck); + bool isFindUnusedFactorSlots() const; + void setFindUnusedFactorSlots(bool findUnusedFactorSlots); + }; class ISAM2Clique { diff --git a/gtsam_unstable/gtsam_unstable.i b/gtsam_unstable/gtsam_unstable.i index 8c9345147..b7de97be3 100644 --- a/gtsam_unstable/gtsam_unstable.i +++ b/gtsam_unstable/gtsam_unstable.i @@ -567,6 +567,10 @@ virtual class FixedLagSmoother { double smootherLag() const; gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps); + gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph &newFactors, + const gtsam::Values &newTheta, + const gtsam::FixedLagSmootherKeyTimestampMap ×tamps, + const gtsam::FactorIndices &factorsToRemove); gtsam::Values calculateEstimate() const; }; @@ -590,6 +594,8 @@ virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother { IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params); gtsam::ISAM2Params params() const; + + gtsam::NonlinearFactorGraph getFactors() const; }; #include