From 2ea9d1bcf3d91f3cc481915164bd76b4bac37ed9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 28 Jun 2024 16:17:27 -0400 Subject: [PATCH] update gtsam:: namespace in slam.i --- gtsam/slam/slam.i | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/gtsam/slam/slam.i b/gtsam/slam/slam.i index 97b198b2f..f054aaab4 100644 --- a/gtsam/slam/slam.i +++ b/gtsam/slam/slam.i @@ -12,7 +12,7 @@ namespace gtsam { // ###### #include -template virtual class BetweenFactor : gtsam::NoiseModelFactor { @@ -227,7 +227,7 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::EssentialMatrixFactor& other, double tol) const; - Vector evaluateError(const gtsam::EssentialMatrix& E) const; + gtsam::Vector evaluateError(const gtsam::EssentialMatrix& E) const; }; #include @@ -237,7 +237,7 @@ virtual class EssentialMatrixConstraint : gtsam::NoiseModelFactor { void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::EssentialMatrixConstraint& other, double tol) const; - Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const; + gtsam::Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const; const gtsam::EssentialMatrix& measured() const; }; @@ -336,7 +336,7 @@ virtual class FrobeniusFactor : gtsam::NoiseModelFactor { FrobeniusFactor(size_t key1, size_t key2); FrobeniusFactor(size_t key1, size_t key2, gtsam::noiseModel::Base* model); - Vector evaluateError(const T& R1, const T& R2); + gtsam::Vector evaluateError(const T& R1, const T& R2); }; template @@ -345,7 +345,7 @@ virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor { FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12, gtsam::noiseModel::Base* model); - Vector evaluateError(const T& R1, const T& R2); + gtsam::Vector evaluateError(const T& R1, const T& R2); }; #include