diff --git a/gtsam.h b/gtsam.h index 0c00047b1..678e2a3d6 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2197,6 +2197,25 @@ virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { void serialize() const; }; +#include +template +virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { + + SmartProjectionPoseFactor(double rankTol, double linThreshold, + bool manageDegeneracy, bool enableEPI, const POSE& body_P_sensor); + + SmartProjectionPoseFactor(double rankTol); + SmartProjectionPoseFactor(); + + void add(const gtsam::Point2& measured_i, size_t poseKey_i, const gtsam::noiseModel::Base* noise_i, + const CALIBRATION* K_i); + + // enabling serialization functionality + //void serialize() const; +}; + +typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; + #include template diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 256f313ac..06a41f5ec 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -380,25 +380,6 @@ virtual class SmartRangeFactor : gtsam::NoiseModelFactor { }; -#include -template -virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { - - SmartProjectionPoseFactor(double rankTol, double linThreshold, - bool manageDegeneracy, bool enableEPI, const POSE& body_P_sensor); - - SmartProjectionPoseFactor(double rankTol); - SmartProjectionPoseFactor(); - - void add(const gtsam::Point2& measured_i, size_t poseKey_i, const gtsam::noiseModel::Base* noise_i, - const CALIBRATION* K_i); - - // enabling serialization functionality - //void serialize() const; -}; - -typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; - #include template virtual class RangeFactor : gtsam::NonlinearFactor {