From b83a9967318a2b31813e07b3450037d7946bc0e8 Mon Sep 17 00:00:00 2001 From: djensen3 Date: Tue, 13 May 2014 17:04:16 -0400 Subject: [PATCH] Fixed SmartProjectionPoseFactor matlab wrapping --- gtsam_unstable/gtsam_unstable.h | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 440b26388..fdd75ae06 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -20,7 +20,6 @@ virtual class gtsam::NonlinearFactor; virtual class gtsam::GaussianFactor; virtual class gtsam::HessianFactor; virtual class gtsam::JacobianFactor; -virtual class gtsam::SharedNoiseModel; virtual class gtsam::Cal3_S2; class gtsam::GaussianFactorGraph; class gtsam::NonlinearFactorGraph; @@ -377,7 +376,7 @@ virtual class SmartRangeFactor : gtsam::NoiseModelFactor { void print(string s) const; }; -/* + #include template virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { @@ -386,9 +385,9 @@ virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { bool manageDegeneracy, bool enableEPI, const POSE& body_P_sensor); SmartProjectionPoseFactor(double rankTol); - //SmartProjectionPoseFactor(); + SmartProjectionPoseFactor(); - void add(const gtsam::Point2 measured_i, const gtsam::Key poseKey_i, const gtsam::SharedNoiseModel noise_i, + void add(const gtsam::Point2& measured_i, size_t poseKey_i, const gtsam::noiseModel::Base* noise_i, const CALIBRATION* K_i); // enabling serialization functionality @@ -396,7 +395,7 @@ virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { }; typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; -*/ + #include template virtual class RangeFactor : gtsam::NonlinearFactor {