Move Transform factors to unstable

release/4.3a0
cbeall3 2014-07-01 16:03:35 -04:00
parent 7485a8f2d5
commit 5b2f4a2c3a
4 changed files with 43 additions and 22 deletions

21
gtsam.h
View File

@ -2179,27 +2179,6 @@ typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2; typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2;
#include <gtsam/slam/TransformProjectionFactor.h>
template<POSE, LANDMARK, CALIBRATION>
virtual class TransformProjectionFactor : gtsam::NoiseModelFactor {
TransformProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k);
TransformProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality);
gtsam::Point2 measured() const;
CALIBRATION* calibration() const;
bool verboseCheirality() const;
bool throwCheirality() const;
// enabling serialization functionality
void serialize() const;
};
typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> TransformProjectionFactorCal3_S2;
typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformProjectionFactorCal3DS2;
#include <gtsam/slam/GeneralSFMFactor.h> #include <gtsam/slam/GeneralSFMFactor.h>
template<CAMERA, LANDMARK> template<CAMERA, LANDMARK>
virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { virtual class GeneralSFMFactor : gtsam::NoiseModelFactor {

View File

@ -24,6 +24,7 @@ virtual class gtsam::GaussianFactor;
virtual class gtsam::HessianFactor; virtual class gtsam::HessianFactor;
virtual class gtsam::JacobianFactor; virtual class gtsam::JacobianFactor;
virtual class gtsam::Cal3_S2; virtual class gtsam::Cal3_S2;
virtual class gtsam::Cal3DS2;
class gtsam::GaussianFactorGraph; class gtsam::GaussianFactorGraph;
class gtsam::NonlinearFactorGraph; class gtsam::NonlinearFactorGraph;
class gtsam::Ordering; class gtsam::Ordering;
@ -740,4 +741,45 @@ virtual class OdometryFactorBase : gtsam::NoiseModelFactor {
void print(string s) const; void print(string s) const;
}; };
#include <gtsam/geometry/Cal3DS2.h>
#include <gtsam_unstable/slam/TransformProjectionFactor.h>
template<POSE, LANDMARK, CALIBRATION>
virtual class TransformProjectionFactor : gtsam::NoiseModelFactor {
TransformProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k);
TransformProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality);
gtsam::Point2 measured() const;
CALIBRATION* calibration() const;
bool verboseCheirality() const;
bool throwCheirality() const;
// enabling serialization functionality
void serialize() const;
};
typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> TransformProjectionFactorCal3_S2;
typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformProjectionFactorCal3DS2;
#include <gtsam_unstable/slam/TransformCalProjectionFactor.h>
template<POSE, LANDMARK, CALIBRATION>
virtual class TransformCalProjectionFactor : gtsam::NoiseModelFactor {
TransformCalProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey);
TransformCalProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality);
gtsam::Point2 measured() const;
bool verboseCheirality() const;
bool throwCheirality() const;
// enabling serialization functionality
void serialize() const;
};
typedef gtsam::TransformCalProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> TransformCalProjectionFactorCal3_S2;
typedef gtsam::TransformCalProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformCalProjectionFactorCal3DS2;
} //\namespace gtsam } //\namespace gtsam

View File

@ -18,7 +18,7 @@
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/TestableAssertions.h>
#include <gtsam/slam/TransformProjectionFactor.h> #include <gtsam_unstable/slam/TransformProjectionFactor.h>
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <gtsam/geometry/Cal3DS2.h> #include <gtsam/geometry/Cal3DS2.h>
#include <gtsam/geometry/Cal3_S2.h> #include <gtsam/geometry/Cal3_S2.h>