Add prior templates
parent
c0bac3cac5
commit
60ce938e31
|
@ -75,13 +75,20 @@ class NonlinearFactorGraph {
|
||||||
gtsam::Pose2,
|
gtsam::Pose2,
|
||||||
gtsam::Pose3,
|
gtsam::Pose3,
|
||||||
gtsam::Cal3_S2,
|
gtsam::Cal3_S2,
|
||||||
|
gtsam::Cal3f,
|
||||||
|
gtsam::Cal3Bundler,
|
||||||
gtsam::Cal3Fisheye,
|
gtsam::Cal3Fisheye,
|
||||||
gtsam::Cal3Unified,
|
gtsam::Cal3Unified,
|
||||||
gtsam::CalibratedCamera,
|
gtsam::CalibratedCamera,
|
||||||
|
gtsam::EssentialMatrix,
|
||||||
|
gtsam::FundamentalMatrix,
|
||||||
|
gtsam::SimpleFundamentalMatrix,
|
||||||
gtsam::PinholeCamera<gtsam::Cal3_S2>,
|
gtsam::PinholeCamera<gtsam::Cal3_S2>,
|
||||||
|
gtsam::PinholeCamera<gtsam::Cal3f>,
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
|
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Unified>,
|
gtsam::PinholeCamera<gtsam::Cal3Unified>,
|
||||||
|
gtsam::PinholeCamera<gtsam::CalibratedCamera>,
|
||||||
gtsam::imuBias::ConstantBias}>
|
gtsam::imuBias::ConstantBias}>
|
||||||
void addPrior(size_t key, const T& prior,
|
void addPrior(size_t key, const T& prior,
|
||||||
const gtsam::noiseModel::Base* noiseModel);
|
const gtsam::noiseModel::Base* noiseModel);
|
||||||
|
|
Loading…
Reference in New Issue