From 15c29cacd2c5d796b62b530bdfb9c8b4d6c73e6d Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Wed, 21 Jul 2021 05:14:58 +0000 Subject: [PATCH] wrapping triangulate nonlinear --- gtsam/gtsam.i | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 94d10953b..155275702 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -1145,7 +1145,20 @@ gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3_S2& cameras, gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Bundler& cameras, const gtsam::Point2Vector& measurements, double rank_tol, bool optimize); - +gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses, + gtsam::Cal3_S2* sharedCal, const gtsam::Point2Vector& measurements, + const Point3& initialEstimate); +gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses, + gtsam::Cal3DS2* sharedCal, const gtsam::Point2Vector& measurements, + const 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::Point2Vector& measurements, const Point3& initialEstimate); +gtsam::Point3 triangulateNonlinear(const CameraSetCal3Bundler& cameras, + const gtsam::Point2Vector& measurements, const Point3& initialEstimate); + //************************************************************************* // Symbolic //*************************************************************************