tried some changes for wrapping

release/4.3a0
Luca 2014-05-01 10:48:54 -04:00
parent 2cb448fa24
commit 32e1a8f994
1 changed files with 8 additions and 7 deletions

View File

@ -377,19 +377,20 @@ virtual class SmartRangeFactor : gtsam::NoiseModelFactor {
}; };
#include <gtsam_unstable/slam/SmartProjectionPoseFactor.h> #include <gtsam_unstable/slam/SmartProjectionPoseFactor.h>
template<POSE, LANDMARK, CALIBRATION> template<POSE = {gtsam::Pose3},LANDMARK = {gtsam::Point3},CALIBRATION = {gtsam::Cal3_S2}>
virtual class SmartProjectionPoseFactor: gtsam::SmartProjectionFactor { virtual class SmartProjectionPoseFactor : gtsam::SmartProjectionFactor {
SmartProjectionPoseFactor(double rankTol, double linThreshold, //SmartProjectionPoseFactor(double rankTol, double linThreshold, bool manageDegeneracy, bool enableEPI, const POSE& body_P_sensor);
bool manageDegeneracy, bool enableEPI, const POSE& body_P_sensor); SmartProjectionPoseFactor();
void add(const Point2 measured_i, const Key poseKey_i, const SharedNoiseModel noise_i, //void add(gtsam::Point2 measured_i, size_t poseKey_i, gtsam::SharedNoiseModel noise_i, CALIBRATION* K_i);
const CALIBRATION* K_i);
// enabling serialization functionality // enabling serialization functionality
void serialize() const; // void serialize() const;
}; };
//typedef gtsam::SmartProjectionPoseFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2 > SmartProjectionPose3Factor;
#include <gtsam/slam/RangeFactor.h> #include <gtsam/slam/RangeFactor.h>
template<POSE, POINT> template<POSE, POINT>