diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index cfc76786a..be13af210 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -71,6 +71,7 @@ class UnaryFactor: public NoiseModelFactorN { double mx_, my_; public: + // Provide access to Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 0d3ce7695..e353def6a 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -158,6 +158,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN, typedef NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index 9dea1c5ab..aad88a816 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; diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 4196f5f22..8e6979f1b 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -268,6 +268,7 @@ private: PreintegratedCombinedMeasurements _PIM_; public: + // Provide access to Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/navigation/ConstantVelocityFactor.h b/gtsam/navigation/ConstantVelocityFactor.h index 8bb76379a..f75436ae3 100644 --- a/gtsam/navigation/ConstantVelocityFactor.h +++ b/gtsam/navigation/ConstantVelocityFactor.h @@ -31,6 +31,7 @@ class ConstantVelocityFactor : public NoiseModelFactorN { public: using Base = NoiseModelFactor2; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index 7b4435030..7965af066 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -122,6 +122,7 @@ private: Point3 nT_; ///< Position measurement in cartesian coordinates public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index c71078ed6..4c1b07a82 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; diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 9e87b8324..142d5a957 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -37,6 +37,7 @@ class MagFactor: public NoiseModelFactorN { const Point3 bias_; ///< bias public: + // Provide access to Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; @@ -95,6 +96,7 @@ class MagFactor1: public NoiseModelFactorN { const Point3 bias_; ///< bias public: + // Provide access to Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; @@ -134,6 +136,7 @@ class MagFactor2: public NoiseModelFactorN { const Rot3 bRn_; ///< The assumed known rotation from nav to body public: + // Provide access to Matrix& version of evaluateError: using NoiseModelFactor2::evaluateError; @@ -177,6 +180,7 @@ class MagFactor3: public NoiseModelFactorN { const Rot3 bRn_; ///< The assumed known rotation from nav to body public: + // Provide access to Matrix& version of evaluateError: using NoiseModelFactor3::evaluateError; diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index 75b0aeedf..8cc243583 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; diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 23dc3014b..16d7eff8b 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -55,6 +55,7 @@ protected: public: + // Provide access to the Matrix& version of unwhitenedError: using NoiseModelFactor::unwhitenedError; typedef boost::shared_ptr > shared_ptr; diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 0648bebfe..4053891f1 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; @@ -168,6 +169,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { FunctionType func_; ///< functor instance public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 09c58ba80..bda16da08 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -46,6 +46,7 @@ class NonlinearEquality: public NoiseModelFactorN { public: typedef VALUE T; + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; @@ -307,6 +308,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/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 6d0fcb4fc..4202bb33c 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -31,6 +31,7 @@ namespace gtsam { public: typedef VALUE T; + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; diff --git a/gtsam/sfm/ShonanFactor.h b/gtsam/sfm/ShonanFactor.h index 6fea8ac14..3e6ea218d 100644 --- a/gtsam/sfm/ShonanFactor.h +++ b/gtsam/sfm/ShonanFactor.h @@ -42,6 +42,7 @@ class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN { using Rot = typename std::conditional::type; public: + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor2::evaluateError; diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index df7c8a65a..abbfa7fcb 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -45,6 +45,7 @@ class TranslationFactor : public NoiseModelFactorN { Point3 measured_w_aZb_; public: + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor2::evaluateError; diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 897bf39e1..7d30c0c54 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -55,6 +55,7 @@ namespace gtsam { VALUE measured_; /** The measurement */ public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index f76193f7c..631748964 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -37,6 +37,7 @@ private: EssentialMatrix measuredE_; /** The measurement is an essential matrix */ public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 8e564ddb6..854ba8fad 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -118,6 +118,7 @@ class EssentialMatrixFactor2 typedef EssentialMatrixFactor2 This; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -240,6 +241,7 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 { Rot3 cRb_; ///< Rotation from body to camera frame public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -343,6 +345,7 @@ class EssentialMatrixFactor4 typedef Eigen::Matrix JacobianCalibration; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 6c9027f6f..a000a1514 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -114,6 +114,7 @@ class FrobeniusBetweenFactor : public NoiseModelFactorN { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; public: + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor2::evaluateError; diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index 4b9398cb3..99ac81ba1 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -21,6 +21,7 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor2::evaluateError; diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index 9caf239f8..aa88f978f 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; diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 798432f7f..fe3b7dc51 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; diff --git a/gtsam_unstable/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index fb698764a..f520de7b7 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -191,6 +191,7 @@ protected: double alpha_; //! in [0,1], define the mid-point between [q_k,q_{k+1}] for approximation. The sympletic rule above can be obtained as a special case when alpha = 0. public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 7938a3431..3e4ad0d9f 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -29,6 +29,7 @@ class Reconstruction : public NoiseModelFactorN { double h_; // time step typedef NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -91,6 +92,7 @@ class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index 91440fc92..1c3dbcde7 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -35,6 +35,7 @@ typedef enum { class VelocityConstraint : public gtsam::NoiseModelFactorN { public: typedef gtsam::NoiseModelFactor2 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index e241310e9..6e0d300ac 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -37,6 +37,7 @@ namespace gtsam { Point3 measured_; /** The measurement */ public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index 32755b18d..f151dd63e 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; diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index c1c448b97..f1f118c2d 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -95,6 +95,7 @@ private: boost::optional body_P_sensor_; // The pose of the sensor in the body frame public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index f32399c87..3891cc41c 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -35,6 +35,7 @@ public: /// shorthand for base class type typedef NoiseModelFactor3 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index fb2b12cf2..7372e9ebb 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -35,6 +35,7 @@ public: /// shorthand for base class type typedef NoiseModelFactor2 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index dfe75c10e..8284cd9ba 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -37,6 +37,7 @@ public: /// shorthand for base class type typedef NoiseModelFactor2 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index bd373f20d..e90a2e609 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -35,6 +35,7 @@ public: /// shorthand for base class type typedef NoiseModelFactor2 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index 8b958da22..50388f4aa 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h @@ -40,6 +40,7 @@ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor OrientedPlane3 measured_p_; typedef NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 1bed15bba..ab4a2bce3 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -61,6 +61,7 @@ namespace gtsam { : Base(model, key) {} public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index 0d63af707..14a18d938 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -43,6 +43,7 @@ namespace gtsam { GTSAM_CONCEPT_TESTABLE_TYPE(POSE) GTSAM_CONCEPT_POSE_TYPE(POSE) public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index 5c73215a8..ac199588b 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -40,6 +40,7 @@ namespace gtsam { GTSAM_CONCEPT_TESTABLE_TYPE(POSE) GTSAM_CONCEPT_POSE_TYPE(POSE) public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index f45b6c6b9..335e3b8d0 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -29,6 +29,7 @@ class PoseToPointFactor : public NoiseModelFactorN { POINT measured_; /** the point measurement in local coordinates */ public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index 647cf566a..9ef11f022 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -46,6 +46,7 @@ namespace gtsam { /// shorthand for base class type typedef NoiseModelFactor3 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index 304a54b97..7159cd5e0 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -45,6 +45,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC public: /// shorthand for base class type typedef NoiseModelFactor4 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 859e44f6d..bbf108ecc 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -61,6 +61,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter public: /// shorthand for base class type typedef NoiseModelFactor3 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index 9750313c2..5beb454bc 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -34,6 +34,7 @@ private: typedef NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 7202ba8ff..301508c0f 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -42,6 +42,7 @@ class SmartRangeFactor: public NoiseModelFactor { double variance_; ///< variance on noise public: + // Provide access to the Matrix& version of unwhitenedError using NoiseModelFactor::unwhitenedError; diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index 4dca82903..3d65f0f61 100644 --- a/gtsam_unstable/slam/TSAMFactors.h +++ b/gtsam_unstable/slam/TSAMFactors.h @@ -37,6 +37,7 @@ private: Point2 measured_; ///< the measurement public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -67,6 +68,7 @@ private: Point2 measured_; ///< the measurement public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -122,6 +124,7 @@ private: Pose2 measured_; ///< the measurement public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/tests/simulated2DOriented.h b/tests/simulated2DOriented.h index c9c35099d..983432728 100644 --- a/tests/simulated2DOriented.h +++ b/tests/simulated2DOriented.h @@ -108,7 +108,7 @@ namespace simulated2DOriented { typedef GenericOdometry This; // Provide access to the Matrix& version of evaluateError: - using NoiseModelFactor2::evaluateError; + using NoiseModelFactor2::evaluateError; /** * Creates an odometry factor between two poses diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index eb17ecd9e..e9747e624 100644 --- a/tests/testExtendedKalmanFilter.cpp +++ b/tests/testExtendedKalmanFilter.cpp @@ -101,6 +101,7 @@ protected: Matrix Q_invsqrt_; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -247,6 +248,7 @@ protected: Matrix R_invsqrt_; /** The inv sqrt of the measurement error covariance */ public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index e9e755044..c0bee0aaa 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -337,10 +337,12 @@ class TestFactor1 : public NoiseModelFactor1 { public: typedef NoiseModelFactor1 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; TestFactor1() : Base(noiseModel::Diagonal::Sigmas(Vector1(2.0)), L(1)) {} + // Provide access to the Matrix& version of evaluateError: using Base::NoiseModelFactor1; // inherit constructors @@ -392,10 +394,12 @@ class TestFactor4 : public NoiseModelFactor4 { public: typedef NoiseModelFactor4 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} + // Provide access to the Matrix& version of evaluateError: using Base::NoiseModelFactor4; // inherit constructors @@ -485,6 +489,7 @@ TEST(NonlinearFactor, NoiseModelFactor4) { class TestFactor5 : public NoiseModelFactor5 { public: typedef NoiseModelFactor5 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -535,6 +540,7 @@ TEST(NonlinearFactor, NoiseModelFactor5) { class TestFactor6 : public NoiseModelFactor6 { public: typedef NoiseModelFactor6 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; @@ -592,6 +598,7 @@ TEST(NonlinearFactor, NoiseModelFactor6) { class TestFactorN : public NoiseModelFactorN { public: typedef NoiseModelFactorN Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError;