diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index e5a92ec47..0a67b6b39 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -140,6 +140,7 @@ class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN { public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** Shorthand for a smart pointer to a factor */ #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5 diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 4339fc5de..743bba1f4 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -82,6 +82,7 @@ class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN, public At public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -156,6 +157,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN, typedef NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// shorthand for a smart pointer to a factor diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index a72b87024..646731a09 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -38,6 +38,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { double nT_; ///< Height Measurement based on a standard atmosphere public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index df2b2474f..da6b453eb 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -42,6 +42,7 @@ private: public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -120,6 +121,7 @@ private: Point3 nT_; ///< Position measurement in cartesian coordinates public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// shorthand for a smart pointer to a factor diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index e521e6b19..41648674b 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -179,6 +179,7 @@ private: PreintegratedImuMeasurements _PIM_; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** Shorthand for a smart pointer to a factor */ diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index bf64933dc..f0b82eed7 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -49,6 +49,7 @@ class MagPoseFactor: public NoiseModelFactorN { GTSAM_CONCEPT_POSE_TYPE(POSE) public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; ~MagPoseFactor() override {} diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 53c92155b..59702ee74 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -65,6 +65,7 @@ class FunctorizedFactor : public NoiseModelFactorN { std::function func_; ///< functor instance public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** default constructor - only use for serialization */ FunctorizedFactor() {} @@ -166,6 +167,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { FunctionType func_; ///< functor instance public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** default constructor - only use for serialization */ FunctorizedFactor2() {} diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index c026530ec..309cababa 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -305,6 +305,7 @@ class NonlinearEquality2 : public NoiseModelFactorN { public: typedef boost::shared_ptr> shared_ptr; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 43bc48b7d..645fb611c 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -117,6 +117,7 @@ class EssentialMatrixFactor2 typedef EssentialMatrixFactor2 This; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** * Constructor diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index 1591cbe2f..9caf239f8 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -74,6 +74,7 @@ class RotateDirectionsFactor: public NoiseModelFactorN { typedef RotateDirectionsFactor This; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// Constructor diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 90a37751c..798432f7f 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -32,6 +32,7 @@ protected: double dt_; /// time between measurements public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** Standard constructor */ diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index 2f087cedf..6dfd8d295 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -53,6 +53,7 @@ private: Vector tau_; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; // shorthand for a smart pointer to a factor diff --git a/tests/simulated2D.h b/tests/simulated2D.h index 7f89d5ac2..e1f0c5116 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -133,6 +133,7 @@ namespace simulated2D { typedef boost::shared_ptr > shared_ptr; typedef VALUE Pose; ///< shortcut to Pose type + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; Pose measured_; ///< prior mean @@ -179,6 +180,7 @@ namespace simulated2D { typedef boost::shared_ptr > shared_ptr; typedef VALUE Pose; ///< shortcut to Pose type + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; Pose measured_; ///< odometry measurement @@ -227,6 +229,7 @@ namespace simulated2D { typedef POSE Pose; ///< shortcut to Pose type typedef LANDMARK Landmark; ///< shortcut to Landmark type + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; Landmark measured_; ///< Measurement