diff --git a/gtsam_unstable/gtsam_unstable.i b/gtsam_unstable/gtsam_unstable.i index f36118873b..9323255adf 100644 --- a/gtsam_unstable/gtsam_unstable.i +++ b/gtsam_unstable/gtsam_unstable.i @@ -699,6 +699,7 @@ virtual class OdometryFactorBase : gtsam::NoiseModelFactor { #include #include +#include template virtual class ProjectionFactorPPP : gtsam::NoiseModelFactor { ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, @@ -717,7 +718,7 @@ virtual class ProjectionFactorPPP : gtsam::NoiseModelFactor { }; typedef gtsam::ProjectionFactorPPP ProjectionFactorPPPCal3_S2; typedef gtsam::ProjectionFactorPPP ProjectionFactorPPPCal3DS2; - +typedef gtsam::ProjectionFactorPPP ProjectionFactorPPPCal3Fisheye; #include template @@ -737,6 +738,7 @@ virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor { }; typedef gtsam::ProjectionFactorPPPC ProjectionFactorPPPCCal3_S2; typedef gtsam::ProjectionFactorPPPC ProjectionFactorPPPCCal3DS2; +typedef gtsam::ProjectionFactorPPPC ProjectionFactorPPPCCal3Fisheye; #include virtual class ProjectionFactorRollingShutter : gtsam::NoiseModelFactor {