Skip to content

Commit

Permalink
Merge pull request #828 from borglab/feature/wrap-triangulate-nonlinear
Browse files Browse the repository at this point in the history
Wrapping triangulateNonlinear from triangulation.h
  • Loading branch information
akshay-krishnan authored Jul 25, 2021
2 parents 5bb69f7 + d4951f0 commit 158d279
Showing 1 changed file with 18 additions and 0 deletions.
18 changes: 18 additions & 0 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -982,6 +982,24 @@ 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 triangulateNonlinear(const gtsam::Pose3Vector& poses,
gtsam::Cal3_S2* sharedCal,
const gtsam::Point2Vector& measurements,
const gtsam::Point3& initialEstimate);
gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses,
gtsam::Cal3DS2* sharedCal,
const gtsam::Point2Vector& measurements,
const gtsam::Point3& initialEstimate);
gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses,
gtsam::Cal3Bundler* sharedCal,
const gtsam::Point2Vector& measurements,
const gtsam::Point3& initialEstimate);
gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3_S2& cameras,
const gtsam::Point2Vector& measurements,
const gtsam::Point3& initialEstimate);
gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3Bundler& cameras,
const gtsam::Point2Vector& measurements,
const gtsam::Point3& initialEstimate);

#include <gtsam/geometry/BearingRange.h>
template <POSE, POINT, BEARING, RANGE>
Expand Down

0 comments on commit 158d279

Please sign in to comment.