removed again
parent
b66b5c1657
commit
28658a3bf1
|
@ -979,7 +979,7 @@ gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
||||||
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
||||||
gtsam::Cal3Bundler* sharedCal,
|
gtsam::Cal3Bundler* sharedCal,
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
double rank_tol, bool optimize);
|
double rank_tol, bool optimize);
|
||||||
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3_S2& cameras,
|
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3_S2& cameras,
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
double rank_tol, bool optimize);
|
double rank_tol, bool optimize);
|
||||||
|
@ -992,9 +992,6 @@ gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Fisheye& cameras,
|
||||||
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Unified& cameras,
|
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Unified& cameras,
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
double rank_tol, bool optimize);
|
double rank_tol, bool optimize);
|
||||||
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetSpherical& cameras,
|
|
||||||
const std::vector<gtsam::Unit3>& measurements,
|
|
||||||
double rank_tol, bool optimize);
|
|
||||||
gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses,
|
gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses,
|
||||||
gtsam::Cal3_S2* sharedCal,
|
gtsam::Cal3_S2* sharedCal,
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
|
@ -1013,10 +1010,7 @@ gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3_S2& cameras,
|
||||||
gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3Bundler& cameras,
|
gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetCal3Bundler& cameras,
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
const gtsam::Point3& initialEstimate);
|
const gtsam::Point3& initialEstimate);
|
||||||
gtsam::Point3 triangulateNonlinear(const gtsam::CameraSetSpherical& cameras,
|
|
||||||
const std::vector<gtsam::Unit3>& measurements,
|
|
||||||
const gtsam::Point3& initialEstimate);
|
|
||||||
|
|
||||||
#include <gtsam/geometry/BearingRange.h>
|
#include <gtsam/geometry/BearingRange.h>
|
||||||
template <POSE, POINT, BEARING, RANGE>
|
template <POSE, POINT, BEARING, RANGE>
|
||||||
class BearingRange {
|
class BearingRange {
|
||||||
|
|
Loading…
Reference in New Issue