diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 9bcfcca3e..9baa49e8e 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -979,7 +979,7 @@ gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses, gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses, gtsam::Cal3Bundler* sharedCal, const gtsam::Point2Vector& measurements, - double rank_tol, bool optimize); + double rank_tol, bool optimize); gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3_S2& cameras, const gtsam::Point2Vector& measurements, double rank_tol, bool optimize); @@ -992,9 +992,6 @@ gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Fisheye& cameras, gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Unified& cameras, const gtsam::Point2Vector& measurements, double rank_tol, bool optimize); -gtsam::Point3 triangulatePoint3(const gtsam::CameraSetSpherical& cameras, - const std::vector& measurements, - double rank_tol, bool optimize); gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses, gtsam::Cal3_S2* sharedCal, const gtsam::Point2Vector& measurements, @@ -1013,10 +1010,7 @@ gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3_S2& cameras, gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3Bundler& cameras, const gtsam::Point2Vector& measurements, const gtsam::Point3& initialEstimate); -gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetSpherical& cameras, - const std::vector& measurements, - const gtsam::Point3& initialEstimate); - + #include template class BearingRange {