adding gtsam scope
parent
bd994d07bc
commit
d4951f025d
|
|
@ -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 <gtsam/geometry/BearingRange.h>
|
||||
template <POSE, POINT, BEARING, RANGE>
|
||||
|
|
|
|||
Loading…
Reference in New Issue