diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 79b63ff6a..928b3029f 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -611,6 +611,16 @@ class ISAM2GaussNewtonParams { void setWildfireThreshold(double wildfireThreshold); }; +class ISAM2LevenbergMarquardtParams { + ISAM2LevenbergMarquardtParams(); + + void print(string s = "") const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); +}; + class ISAM2DoglegParams { ISAM2DoglegParams(); @@ -738,12 +748,13 @@ class ISAM2 { const gtsam::KeyList& extraReelimKeys, bool force_relinearize); - void marginalizeLeaves( - const gtsam::KeyList& leafKeys, - boost::optional marginalFactorIndices = - boost::none, - boost::optional deletedFactorsIndices = - boost::none); + // void marginalizeLeaves( + // const gtsam::KeyList& leafKeys, + // boost::optional marginalFactorIndices = + // boost::none, + // boost::optional deletedFactorsIndices = + // boost::none); + gtsam::Values getLinearizationPoint() const; bool valueExists(gtsam::Key key) const; gtsam::Values calculateEstimate() const;