Wrapped GeneralSFMFactor and added placeholders for Cal3DS2 once it has a 'calibrate' function

release/4.3a0
Richard Roberts 2012-07-23 21:27:42 +00:00
parent bcad0b661c
commit cd69779754
1 changed files with 57 additions and 1 deletions

58
gtsam.h
View File

@ -593,6 +593,43 @@ virtual class SimpleCamera : gtsam::Value {
double range(const gtsam::Pose3& point); // FIXME, overload
};
// TODO: Add this back in when Cal3DS2 has a calibrate function
//template<CALIBRATION = {gtsam::Cal3DS2}>
//virtual class PinholeCamera : gtsam::Value {
// // Standard Constructors and Named Constructors
// PinholeCamera();
// PinholeCamera(const gtsam::Pose3& pose);
// PinholeCamera(const gtsam::Pose3& pose, const gtsam::Cal3DS2& K);
// static This Level(const gtsam::Cal3DS2& K,
// const gtsam::Pose2& pose, double height);
// static This Level(const gtsam::Pose2& pose, double height); // FIXME overload
// static This Lookat(const gtsam::Point3& eye,
// const gtsam::Point3& target, const gtsam::Point3& upVector,
// const gtsam::Cal3DS2& K);
//
// // Testable
// void print(string s) const;
// bool equals(const This& camera, double tol) const;
//
// // Standard Interface
// gtsam::Pose3 pose() const;
// CALIBRATION calibration() const;
//
// // Manifold
// This retract(const Vector& d) const;
// Vector localCoordinates(const This& T2) const;
// size_t dim() const;
// static size_t Dim();
//
// // Transformations and measurement functions
// static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint);
// pair<gtsam::Point2,bool> projectSafe(const gtsam::Point3& pw) const;
// gtsam::Point2 project(const gtsam::Point3& point);
// gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const;
// double range(const gtsam::Point3& point);
// double range(const gtsam::Pose3& point); // FIXME, overload
//};
//*************************************************************************
// inference
//*************************************************************************
@ -1388,7 +1425,26 @@ virtual class GenericProjectionFactor : gtsam::NonlinearFactor {
CALIBRATION* calibration() const;
};
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> GenericProjectionFactorCal3_S2;
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2;
// FIXME: Add Cal3DS2 when it has a 'calibrate' function
//typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2;
#include <gtsam/slam/GeneralSFMFactor.h>
template<CAMERA, LANDMARK>
virtual class GeneralSFMFactor : gtsam::NonlinearFactor {
GeneralSFMFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t cameraKey, size_t landmarkKey);
gtsam::Point2 measured() const;
};
typedef gtsam::GeneralSFMFactor<gtsam::SimpleCamera, gtsam::Point3> GeneralSFMFactorCal3_S2;
// FIXME: Add Cal3DS2 when it has a 'calibrate' function
//typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
// FIXME: Add Cal3DS2 when it has a 'calibrate' function
template<CALIBRATION = {gtsam::Cal3_S2}>
virtual class GeneralSFMFactor2 : gtsam::NonlinearFactor {
GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey);
gtsam::Point2 measured() const;
};
} //\namespace gtsam