From 09f09fa44fc04381b66f695deb760a96a4cce720 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Sep 2020 19:01:52 -0400 Subject: [PATCH] update wrapper to also work for Matlab --- gtsam/gtsam.i | 18 +++++------------- 1 file changed, 5 insertions(+), 13 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index fedb28226..5f031dd1d 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -314,14 +314,6 @@ class DSFMapIndexPair { gtsam::IndexPairSetMap sets(); }; -#include -template -class FastList {}; - -#include -template -class FastMap {}; - #include bool linear_independent(Matrix A, Matrix B, double tol); @@ -2575,10 +2567,9 @@ class ISAM2 { gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices); gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap& constrainedKeys); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap& constrainedKeys, const gtsam::FastList& noRelinKeys); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap& constrainedKeys, const gtsam::FastList& noRelinKeys, const gtsam::FastList& extraReelimKeys); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap& constrainedKeys, const gtsam::FastList& noRelinKeys, const gtsam::FastList& extraReelimKeys, bool force_relinearize); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, gtsam::KeyGroupMap& constrainedKeys, const gtsam::KeyList& noRelinKeys); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, gtsam::KeyGroupMap& constrainedKeys, const gtsam::KeyList& noRelinKeys, const gtsam::KeyList& extraReelimKeys); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, gtsam::KeyGroupMap& constrainedKeys, const gtsam::KeyList& noRelinKeys, const gtsam::KeyList& extraReelimKeys, bool force_relinearize); gtsam::Values getLinearizationPoint() const; gtsam::Values calculateEstimate() const; @@ -2710,7 +2701,8 @@ class BearingRange { BearingRange(const BEARING& b, const RANGE& r); BEARING bearing() const; RANGE range() const; - static gtsam::BearingRange Measure(const POSE& pose, const POINT& point); + //TODO need to update wrap to allow self referencing of class + // static gtsam::BearingRange Measure(const POSE& pose, const POINT& point); static BEARING MeasureBearing(const POSE& pose, const POINT& point); static RANGE MeasureRange(const POSE& pose, const POINT& point); void print(string s) const;