From d4951f025d3c9c487cc6ddbea56cd975a034d538 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Fri, 23 Jul 2021 00:09:47 -0700 Subject: [PATCH] adding gtsam scope --- gtsam/geometry/geometry.i | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index b1c34ba42..0e303cbcd 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -985,21 +985,21 @@ gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Unified& cameras, gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses, gtsam::Cal3_S2* sharedCal, const gtsam::Point2Vector& measurements, - const Point3& initialEstimate); + const gtsam::Point3& initialEstimate); gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses, gtsam::Cal3DS2* sharedCal, const gtsam::Point2Vector& measurements, - const Point3& initialEstimate); + const gtsam::Point3& initialEstimate); gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses, gtsam::Cal3Bundler* sharedCal, const gtsam::Point2Vector& measurements, - const Point3& initialEstimate); -gtsam::Point3 triangulateNonlinear(const CameraSetCal3_S2& cameras, + const gtsam::Point3& initialEstimate); +gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3_S2& cameras, const gtsam::Point2Vector& measurements, - const Point3& initialEstimate); -gtsam::Point3 triangulateNonlinear(const CameraSetCal3Bundler& cameras, + const gtsam::Point3& initialEstimate); +gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3Bundler& cameras, const gtsam::Point2Vector& measurements, - const Point3& initialEstimate); + const gtsam::Point3& initialEstimate); #include template