diff --git a/CMakeLists.txt b/CMakeLists.txt index 43159a935..39eefa6e6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,9 +6,6 @@ if(NOT DEFINED CMAKE_MACOSX_RPATH) set(CMAKE_MACOSX_RPATH 0) endif() -add_definitions(-Wno-deprecated-declarations) -add_definitions(-ftemplate-backtrace-limit=0) - set(CMAKE_CXX_STANDARD 17) # Set the version number for the library diff --git a/gtsam/base/OptionalJacobian.h b/gtsam/base/OptionalJacobian.h index 88718bb01..d6f0db500 100644 --- a/gtsam/base/OptionalJacobian.h +++ b/gtsam/base/OptionalJacobian.h @@ -92,12 +92,12 @@ public: } /// Constructor that will resize a dynamic matrix (unless already correct) - OptionalJacobian(Eigen::MatrixXd* dynamic) : - map_(nullptr) { - if (dynamic) { - dynamic->resize(Rows, Cols); // no malloc if correct size + OptionalJacobian(Eigen::MatrixXd* dynamic) + : map_(nullptr) { + if (dynamic) { + dynamic->resize(Rows, Cols); // no malloc if correct size usurp(dynamic->data()); - } + } } /** diff --git a/gtsam/navigation/ConstantVelocityFactor.h b/gtsam/navigation/ConstantVelocityFactor.h index 536268e5c..8bb76379a 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; public: diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 650bedfb1..e5df25ca9 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; @@ -244,6 +245,8 @@ class ExpressionFactorN : public ExpressionFactor { public: static const std::size_t NARY_EXPRESSION_SIZE = sizeof...(Args); using ArrayNKeys = std::array; + + // Provide access to the Matrix& version of unwhitenedError: using ExpressionFactor::unwhitenedError; /// Destructor diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 1d3282dd9..c026530ec 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; private: diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index be1fbb889..3c03b717b 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -247,8 +247,12 @@ public: virtual Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = OptionalMatrixVecNone) const = 0; // support taking in the actual vector instead of the pointer as well + // to get access to this version of the function from derived classes + // one will need to use the "using" keyword and specify that like this: + // public: + // using NoiseModelFactor::unwhitenedError; Vector unwhitenedError(const Values& x, std::vector& H) const { - return unwhitenedError(x, &H); + return unwhitenedError(x, &H); } /** @@ -593,10 +597,14 @@ protected: virtual Vector evaluateError(const ValueTypes&... x, OptionalMatrixTypeT... H) const = 0; - // if someone uses the evaluateError function by supplying all the optional + // If someone uses the evaluateError function by supplying all the optional // arguments then redirect the call to the one which takes pointers + // to get access to this version of the function from derived classes + // one will need to use the "using" keyword and specify that like this: + // public: + // using NoiseModelFactorN::evaluateError; Vector evaluateError(const ValueTypes&... x, MatrixTypeT&... H) const { - return evaluateError(x..., (&H)...); + return evaluateError(x..., (&H)...); } /// @} @@ -619,19 +627,23 @@ protected: */ template > inline Vector evaluateError(const ValueTypes&... x, OptionalJacArgs&&... H) const { - // A check to ensure all arguments passed are all either matrices or are all pointers to matrices + // A check to ensure all arguments passed are either matrices or are all pointers to matrices constexpr bool are_all_mat = (... && (std::is_same>::value)); + // The pointers can either be of std::nonetype_t or of Matrix* type constexpr bool are_all_ptrs = (... && (std::is_same>::value || std::is_same>::value)); static_assert((are_all_mat || are_all_ptrs), "Arguments that are passed to the evaluateError function can only be of following the types: Matrix, " "or Matrix*"); - // if they pass all matrices then we want to pass their pointers instead - if constexpr (are_all_mat) { - return evaluateError(x..., (&H)...); - } else { - return evaluateError(x..., std::forward(H)..., static_cast(OptionalNone)); - } + // if they pass all matrices then we want to pass their pointers instead + if constexpr (are_all_mat) { + return evaluateError(x..., (&H)...); + } else { + // If they are pointer version, ensure to cast them all to be Matrix* types + // This will ensure any arguments inferred as std::nonetype_t are cast to (Matrix*) nullptr + // This guides the compiler to the correct overload which is the one that takes pointers + return evaluateError(x..., std::forward(H)..., static_cast(OptionalNone)); + } } /// @} diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 2c6161760..0a97ab39e 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -31,7 +31,8 @@ namespace gtsam { public: typedef VALUE T; - using NoiseModelFactor1::evaluateError; + // Provide access to the Matrix& version of evaluateError: + using NoiseModelFactor1::evaluateError; private: diff --git a/gtsam/nonlinear/tests/CMakeLists.txt b/gtsam/nonlinear/tests/CMakeLists.txt index 4a4aff4b4..69a3700f2 100644 --- a/gtsam/nonlinear/tests/CMakeLists.txt +++ b/gtsam/nonlinear/tests/CMakeLists.txt @@ -1 +1 @@ -gtsamAddTestsGlob(nonlinear "test*.cpp" "${tests_exclude}" "gtsam") +gtsamAddTestsGlob(nonlinear "test*.cpp" "" "gtsam") diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h index 670e25d84..68d6cbd48 100644 --- a/gtsam/sam/BearingFactor.h +++ b/gtsam/sam/BearingFactor.h @@ -65,7 +65,7 @@ struct BearingFactor : public ExpressionFactorN { OptionalMatrixType H1 = OptionalNone, OptionalMatrixType H2 = OptionalNone) const { std::vector Hs(2); const auto &keys = Factor::keys(); - const Vector error = this->unwhitenedError( + const Vector error = unwhitenedError( {{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}}, Hs); if (H1) *H1 = Hs[0]; diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index a4ad013fc..897bf39e1 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -55,7 +55,8 @@ namespace gtsam { VALUE measured_; /** The measurement */ public: - using Base::evaluateError; + // Provide access to the Matrix& version of evaluateError: + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 4837d6c54..b48a3e762 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -35,6 +35,7 @@ struct BoundingConstraint1: public NoiseModelFactorN { typedef NoiseModelFactorN Base; typedef boost::shared_ptr > shared_ptr; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; double threshold_; @@ -106,6 +107,7 @@ struct BoundingConstraint2: public NoiseModelFactorN { typedef NoiseModelFactorN Base; typedef boost::shared_ptr > shared_ptr; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; double threshold_; diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index a02dbb5f6..f76193f7c 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; // shorthand for a smart pointer to a factor diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 3e4a55dd6..43bc48b7d 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -38,6 +38,8 @@ class EssentialMatrixFactor : public NoiseModelFactorN { typedef EssentialMatrixFactor This; public: + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** * Constructor @@ -235,6 +237,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; /** * Constructor @@ -336,6 +339,7 @@ class EssentialMatrixFactor4 typedef Eigen::Matrix JacobianCalibration; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /** * Constructor diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 07c79b32d..18181e091 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -54,7 +54,10 @@ class FrobeniusPrior : public NoiseModelFactorN { Eigen::Matrix vecM_; ///< vectorized matrix to approximate public: + + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// Constructor @@ -79,6 +82,8 @@ class FrobeniusFactor : public NoiseModelFactorN { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; public: + + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor2::evaluateError; /// Constructor FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr) diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index a1a78c5d3..78c7c8cd8 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -76,6 +76,9 @@ public: typedef GeneralSFMFactor This;///< typedef for this object typedef NoiseModelFactorN Base;///< typedef for the base class + // 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; @@ -123,7 +126,7 @@ public: /** h(x)-z */ Vector evaluateError(const CAMERA& camera, const LANDMARK& point, - OptionalMatrixType H1=OptionalNone, OptionalMatrixType H2=OptionalNone) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { try { return camera.project2(point,H1,H2) - measured_; } @@ -258,10 +261,7 @@ public: /** h(x)-z */ Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib, - OptionalMatrixType H1=OptionalNone, - OptionalMatrixType H2=OptionalNone, - OptionalMatrixType H3=OptionalNone) const override - { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override { try { Camera camera(pose3,calib); return camera.project(point, H1, H2, H3) - measured_; diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index a4d867e1c..4dac8b553 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; /// Constructor OrientedPlane3Factor() { @@ -55,7 +56,10 @@ class GTSAM_EXPORT OrientedPlane3DirectionPrior : public NoiseModelFactorN Base; public: + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; + typedef OrientedPlane3DirectionPrior This; /// Constructor OrientedPlane3DirectionPrior() { diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index 1d30ac859..58dfda8f9 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -25,6 +25,8 @@ public: typedef typename POSE::Translation Translation; typedef typename POSE::Rotation Rotation; + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; GTSAM_CONCEPT_POSE_TYPE(Pose) diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index 6f2982c28..fa21a7223 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -26,6 +26,8 @@ public: typedef typename POSE::Translation Translation; typedef typename POSE::Rotation Rotation; + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; GTSAM_CONCEPT_POSE_TYPE(Pose) diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index be8ad7cf0..28fd2628f 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -53,6 +53,8 @@ namespace gtsam { /// shorthand for base class type typedef NoiseModelFactor2 Base; + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// shorthand for this class diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index ed7af6ad2..412233dee 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -62,6 +62,8 @@ protected: public: typedef NoiseModelFactorN Base; typedef ReferenceFrameFactor This; + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; typedef POINT Point; diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index 33336bf2a..1591cbe2f 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -28,6 +28,8 @@ class RotateFactor: public NoiseModelFactorN { typedef RotateFactor This; public: + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// Constructor diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index 0afe67b13..55fcfd61d 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -48,9 +48,10 @@ public: typedef boost::shared_ptr shared_ptr; ///< typedef for shared pointer to this object typedef POSE CamPose; ///< typedef for Pose Lie Value type + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; - /** * Default constructor */ diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 98c972b9c..6fac062b9 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -61,6 +61,8 @@ public: /// shorthand for a smart pointer to a factor using shared_ptr = boost::shared_ptr; + + // Provide access to the Matrix& version of evaluateError: using NoiseModelFactor1::evaluateError; /// Default constructor diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index 16409d866..9ba7f67fa 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -34,6 +34,8 @@ 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/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index 6d3126369..fb698764a 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -32,6 +32,8 @@ protected: double h_; // time step public: + + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; typedef boost::shared_ptr shared_ptr; @@ -81,6 +83,7 @@ protected: public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; typedef boost::shared_ptr shared_ptr; @@ -131,6 +134,7 @@ protected: public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; typedef boost::shared_ptr shared_ptr; @@ -187,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; typedef boost::shared_ptr shared_ptr; diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 893d667c8..7938a3431 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -29,7 +29,9 @@ class Reconstruction : public NoiseModelFactorN { double h_; // time step typedef NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; + Reconstruction(Key gKey1, Key gKey, Key xiKey, double h, double mu = 1000.0) : Base(noiseModel::Constrained::All(6, std::abs(mu)), gKey1, gKey, xiKey), h_(h) { @@ -89,6 +91,7 @@ class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN Base; public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; DiscreteEulerPoincareHelicopter(Key xiKey1, Key xiKey_1, Key gKey, diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index ece781f1c..91440fc92 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; protected: diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index 0b4f5b0b6..91905699c 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -23,6 +23,7 @@ protected: public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; typedef boost::shared_ptr shared_ptr; diff --git a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp index 5cd72d377..a1ea046eb 100644 --- a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp +++ b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp @@ -58,10 +58,11 @@ TEST( Reconstruction, evaluateError) { EXPECT( assert_equal(Z_6x1, constraint.evaluateError(g2, g1, V1_g1, H1, H2, H3), tol)); - std::function f = [&constraint](const Pose3& a1, const Pose3& a2, - const Vector6& a3) { + std::function f = + [&constraint](const Pose3& a1, const Pose3& a2, const Vector6& a3) { return constraint.evaluateError(a1, a2, a3); }; + Matrix numericalH1 = numericalDerivative31(f, g2, g1, V1_g1, 1e-5); Matrix numericalH2 = numericalDerivative32(f, g2, g1, V1_g1, 1e-5); diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 510011ede..e19a4e28b 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -228,6 +228,8 @@ public: return err_wh_eq; } + // A function overload that takes a vector of matrices and passes it to the + // function above which uses a pointer to a vector instead. Vector whitenedError(const Values& x, std::vector& H) const { return whitenedError(x, &H); } diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index 0d4c2619d..e241310e9 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -37,7 +37,8 @@ namespace gtsam { Point3 measured_; /** The measurement */ public: - using Base::evaluateError; + // 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_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index a333ce439..529af878d 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -111,6 +111,7 @@ private: public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; // shorthand for a smart pointer to a factor diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 7fca72fb0..f3e27f7e5 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -109,7 +109,9 @@ private: public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; + // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index ad3c1287b..c5fbc9a32 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; // shorthand for a smart pointer to a factor diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 98eadb9e2..8db48955b 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index 39c7924d8..c8958f2f4 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index 51dfb02e9..967c9c9c5 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index 063128534..3685b48b9 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index 0bc456234..a8b42ed99 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; /// Constructor LocalOrientedPlane3Factor() {} diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 3238bcdec..1bed15bba 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; ~PartialPriorFactor() override {} diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index 9d5324c26..0d63af707 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; // shorthand for a smart pointer to a factor diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index f3bc3af57..5c73215a8 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; /// shorthand for a smart pointer to a factor diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 164f8fafa..968c56407 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -29,7 +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; // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index f19cefb1f..647cf566a 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index 8068d1e27..304a54b97 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 4fc79863d..5ac0c9cf0 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; /// shorthand for this class diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index c617c80b7..9750313c2 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; RelativeElevationFactor() : measured_(0.0) {} /* Default constructor */ diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index f3a4440be..ef8d99d63 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -42,7 +42,9 @@ class SmartRangeFactor: public NoiseModelFactor { double variance_; ///< variance on noise public: + // Provide access to the Matrix& version of unwhitenedError using NoiseModelFactor::unwhitenedError; + /** Default constructor: don't use directly */ SmartRangeFactor() { } diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index fe5e63848..caae63122 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; /// Constructor @@ -66,6 +67,7 @@ private: Point2 measured_; ///< the measurement public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// Constructor DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2& measured, @@ -119,6 +121,7 @@ private: Pose2 measured_; ///< the measurement public: + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; /// Constructor diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 591a50f13..7e0b699f6 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -245,9 +245,9 @@ namespace gtsam { } /* ************************************************************************* */ - Vector whitenedError(const Values& x, std::vector& H) const { - return whitenedError(x, &H); - } + Vector whitenedError(const Values& x, std::vector& H) const { + return whitenedError(x, &H); + } /* ************************************************************************* */ Vector calcIndicatorProb(const Values& x) const { diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index dc6f08635..feeb4c43f 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; NonlinearMotionModel(){} @@ -246,6 +247,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; NonlinearMeasurementModel(){} diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index ee0660866..cbfad704c 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -389,6 +389,7 @@ 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)) {} using Base::NoiseModelFactor4; // inherit constructors @@ -479,6 +480,7 @@ TEST(NonlinearFactor, NoiseModelFactor4) { class TestFactor5 : public NoiseModelFactor5 { public: typedef NoiseModelFactor5 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {} @@ -527,6 +529,7 @@ TEST(NonlinearFactor, NoiseModelFactor5) { class TestFactor6 : public NoiseModelFactor6 { public: typedef NoiseModelFactor6 Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5), X(6)) {} @@ -582,6 +585,7 @@ TEST(NonlinearFactor, NoiseModelFactor6) { class TestFactorN : public NoiseModelFactorN { public: typedef NoiseModelFactorN Base; + // Provide access to the Matrix& version of evaluateError: using Base::evaluateError; using Type1 = ValueType<1>; // Test that we can use the ValueType<> template