From b3748cf7c6724194413313ca40e49b4af8bbd352 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Mon, 10 Jun 2013 20:49:47 +0000 Subject: [PATCH] Added access functions to measurements and noisemodels for a variety of common nonlinear factors --- gtsam.h | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/gtsam.h b/gtsam.h index 8ff9056f9..20ea0bf8a 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1958,6 +1958,8 @@ class NonlinearISAM { template virtual class PriorFactor : gtsam::NonlinearFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); + T prior() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; @@ -1965,6 +1967,8 @@ virtual class PriorFactor : gtsam::NonlinearFactor { template virtual class BetweenFactor : gtsam::NonlinearFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); + T measured() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; @@ -1982,6 +1986,7 @@ virtual class NonlinearEquality : gtsam::NonlinearFactor { template virtual class RangeFactor : gtsam::NonlinearFactor { RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::RangeFactor RangeFactorPosePoint2; @@ -1998,6 +2003,7 @@ typedef gtsam::RangeFactor RangeFactor template virtual class BearingFactor : gtsam::NonlinearFactor { BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::BearingFactor BearingFactor2D; @@ -2007,6 +2013,7 @@ typedef gtsam::BearingFactor BearingFa template virtual class BearingRangeFactor : gtsam::NonlinearFactor { BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::BearingRangeFactor BearingRangeFactor2D; @@ -2030,6 +2037,7 @@ virtual class GenericProjectionFactor : gtsam::NonlinearFactor { CALIBRATION* calibration() const; bool verboseCheirality() const; bool throwCheirality() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; @@ -2058,6 +2066,7 @@ virtual class GenericStereoFactor : gtsam::NonlinearFactor { size_t poseKey, size_t landmarkKey, const gtsam::Cal3_S2Stereo* K); gtsam::StereoPoint2 measured() const; gtsam::Cal3_S2Stereo* calibration() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::GenericStereoFactor GenericStereoFactor3D; @@ -2065,6 +2074,7 @@ typedef gtsam::GenericStereoFactor GenericStereoFac template virtual class PoseTranslationPrior : gtsam::NonlinearFactor { PoseTranslationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::PoseTranslationPrior PoseTranslationPrior2D; @@ -2074,6 +2084,7 @@ typedef gtsam::PoseTranslationPrior PoseTranslationPrior3D; template virtual class PoseRotationPrior : gtsam::NonlinearFactor { PoseRotationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::PoseRotationPrior PoseRotationPrior2D;