adding to python?
parent
43ddf2d5dd
commit
b66b5c1657
|
@ -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,6 +992,9 @@ 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<gtsam::Unit3>& measurements,
|
||||
double rank_tol, bool optimize);
|
||||
gtsam::Point3 triangulateNonlinear(const gtsam::Pose3Vector& poses,
|
||||
gtsam::Cal3_S2* sharedCal,
|
||||
const gtsam::Point2Vector& measurements,
|
||||
|
@ -1010,7 +1013,10 @@ 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<gtsam::Unit3>& measurements,
|
||||
const gtsam::Point3& initialEstimate);
|
||||
|
||||
#include <gtsam/geometry/BearingRange.h>
|
||||
template <POSE, POINT, BEARING, RANGE>
|
||||
class BearingRange {
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
#include <gtsam/geometry/CameraSet.h>
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/geometry/SphericalCamera.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
|
@ -518,6 +519,6 @@ using CameraSetCal3Bundler = CameraSet<PinholeCamera<Cal3Bundler>>;
|
|||
using CameraSetCal3_S2 = CameraSet<PinholeCamera<Cal3_S2>>;
|
||||
using CameraSetCal3Fisheye = CameraSet<PinholeCamera<Cal3Fisheye>>;
|
||||
using CameraSetCal3Unified = CameraSet<PinholeCamera<Cal3Unified>>;
|
||||
|
||||
using CameraSetSpherical = CameraSet<SphericalCamera>;
|
||||
} // \namespace gtsam
|
||||
|
||||
|
|
Loading…
Reference in New Issue