Fixed MATLAB wrapping of smart factor

release/4.3a0
dellaert 2015-06-20 11:49:44 -07:00
parent 51df837f74
commit acf4629f85
1 changed files with 20 additions and 7 deletions

27
gtsam.h
View File

@ -2354,18 +2354,31 @@ virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor {
void serialize() const; void serialize() const;
}; };
#include <gtsam/slam/SmartProjectionFactor.h>
class SmartProjectionParams {
SmartProjectionParams();
// TODO(frank): make these work:
// void setLinearizationMode(LinearizationMode linMode);
// void setDegeneracyMode(DegeneracyMode degMode);
void setRankTolerance(double rankTol);
void setEnableEPI(bool enableEPI);
void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold);
void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold);
};
#include <gtsam/slam/SmartProjectionPoseFactor.h> #include <gtsam/slam/SmartProjectionPoseFactor.h>
template<CALIBRATION> template<CALIBRATION>
virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor {
SmartProjectionPoseFactor(double rankTol, double linThreshold, SmartProjectionPoseFactor(const CALIBRATION* K);
bool manageDegeneracy, bool enableEPI, const gtsam::Pose3& body_P_sensor); SmartProjectionPoseFactor(const CALIBRATION* K,
const gtsam::Pose3& body_P_sensor);
SmartProjectionPoseFactor(double rankTol); SmartProjectionPoseFactor(const CALIBRATION* K,
SmartProjectionPoseFactor(); const gtsam::Pose3& body_P_sensor,
const gtsam::SmartProjectionParams& params);
void add(const gtsam::Point2& measured_i, size_t poseKey_i, void add(const gtsam::Point2& measured_i, size_t poseKey_i,
const gtsam::noiseModel::Base* noise_i, const CALIBRATION* K_i); const gtsam::noiseModel::Base* noise_i);
// enabling serialization functionality // enabling serialization functionality
//void serialize() const; //void serialize() const;