From d472362614f63f286135d3dc0ec6b910360e076e Mon Sep 17 00:00:00 2001 From: klaas kelchtermans Date: Thu, 4 May 2023 11:11:45 +0200 Subject: [PATCH] add ProjectionFactorPPPCal3Fisheye --- gtsam_unstable/gtsam_unstable.i | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam_unstable/gtsam_unstable.i b/gtsam_unstable/gtsam_unstable.i index f36118873..eea4d861a 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 ProjectionFactorPPPCal3Fisheye; #include virtual class ProjectionFactorRollingShutter : gtsam::NoiseModelFactor {