From f349f42a8600559a1d24d6d496beda5bd37ccbc9 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 26 Dec 2022 21:58:57 -0500 Subject: [PATCH 1/8] Add deprecated `X1`, `X2`, ... aliases to pre-defined GTSAM classes for backward compatibility. --- gtsam/navigation/AHRSFactor.h | 3 +- gtsam/navigation/AttitudeFactor.h | 4 +- gtsam/navigation/BarometricFactor.h | 2 + gtsam/navigation/CombinedImuFactor.h | 2 +- gtsam/navigation/ConstantVelocityFactor.h | 2 + gtsam/navigation/GPSFactor.h | 2 + gtsam/navigation/ImuFactor.h | 4 ++ gtsam/navigation/MagFactor.h | 4 ++ gtsam/navigation/MagPoseFactor.h | 2 + gtsam/nonlinear/FunctorizedFactor.h | 4 ++ gtsam/nonlinear/NonlinearEquality.h | 3 ++ gtsam/nonlinear/NonlinearFactor.h | 45 +++++++++++++++++++ gtsam/nonlinear/PriorFactor.h | 1 + gtsam/sfm/ShonanFactor.h | 2 + gtsam/sfm/TranslationFactor.h | 2 + gtsam/slam/BetweenFactor.h | 1 + gtsam/slam/EssentialMatrixConstraint.h | 1 + gtsam/slam/EssentialMatrixFactor.h | 6 +++ gtsam/slam/FrobeniusFactor.h | 6 +++ gtsam/slam/GeneralSFMFactor.h | 2 + gtsam/slam/OrientedPlane3Factor.h | 4 ++ gtsam/slam/PoseRotationPrior.h | 2 + gtsam/slam/PoseTranslationPrior.h | 2 + gtsam/slam/ProjectionFactor.h | 2 + gtsam/slam/ReferenceFrameFactor.h | 2 + gtsam/slam/RotateFactor.h | 2 + gtsam/slam/StereoFactor.h | 2 + gtsam/slam/TriangulationFactor.h | 1 + gtsam_unstable/dynamics/FullIMUFactor.h | 2 + gtsam_unstable/dynamics/IMUFactor.h | 2 + gtsam_unstable/dynamics/Pendulum.h | 8 ++++ gtsam_unstable/dynamics/SimpleHelicopter.h | 2 + gtsam_unstable/dynamics/VelocityConstraint.h | 2 + gtsam_unstable/dynamics/VelocityConstraint3.h | 2 + gtsam_unstable/slam/BiasedGPSFactor.h | 1 + .../slam/EquivInertialNavFactor_GlobalVel.h | 1 + .../EquivInertialNavFactor_GlobalVel_NoBias.h | 1 + .../slam/GaussMarkov1stOrderFactor.h | 1 + .../slam/InertialNavFactor_GlobalVelocity.h | 1 + gtsam_unstable/slam/InvDepthFactor3.h | 2 + gtsam_unstable/slam/InvDepthFactorVariant1.h | 2 + gtsam_unstable/slam/InvDepthFactorVariant2.h | 2 + gtsam_unstable/slam/InvDepthFactorVariant3.h | 4 ++ .../slam/LocalOrientedPlane3Factor.h | 2 + gtsam_unstable/slam/PartialPriorFactor.h | 1 + gtsam_unstable/slam/PoseBetweenFactor.h | 1 + gtsam_unstable/slam/PosePriorFactor.h | 1 + gtsam_unstable/slam/PoseToPointFactor.h | 2 + gtsam_unstable/slam/ProjectionFactorPPP.h | 2 + gtsam_unstable/slam/ProjectionFactorPPPC.h | 2 + .../slam/ProjectionFactorRollingShutter.h | 3 ++ gtsam_unstable/slam/RelativeElevationFactor.h | 2 + gtsam_unstable/slam/TSAMFactors.h | 3 ++ tests/testNonlinearFactor.cpp | 4 ++ 54 files changed, 168 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 87fdd2e918..6bca61a41d 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -128,7 +128,8 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation } }; -class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN { +class GTSAM_EXPORT AHRSFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(AHRSFactor, 3); typedef AHRSFactor This; typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 93495f227a..1ed4cc4bb5 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -76,7 +76,8 @@ class AttitudeFactor { * Version of AttitudeFactor for Rot3 * @ingroup navigation */ -class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN, public AttitudeFactor { +class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN, public AttitudeFactor { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Rot3AttitudeFactor, 1); typedef NoiseModelFactorN Base; @@ -152,6 +153,7 @@ template<> struct traits : public Testable, public AttitudeFactor { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Pose3AttitudeFactor, 1); typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index 2d793c475a..b24d43396f 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -32,6 +32,8 @@ namespace gtsam { * @ingroup navigation */ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BarometricFactor, 2); + private: typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 3448e77948..0107cd2326 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -257,7 +257,7 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType */ class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN { -public: + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(CombinedImuFactor, 6); private: diff --git a/gtsam/navigation/ConstantVelocityFactor.h b/gtsam/navigation/ConstantVelocityFactor.h index 4db2b82c0c..03cfa848ea 100644 --- a/gtsam/navigation/ConstantVelocityFactor.h +++ b/gtsam/navigation/ConstantVelocityFactor.h @@ -27,6 +27,8 @@ namespace gtsam { * The only measurement is dt, the time delta between the states. */ class ConstantVelocityFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ConstantVelocityFactor, 2); + double dt_; public: diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index e515d90122..aab4582fce 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -33,6 +33,7 @@ namespace gtsam { * @ingroup navigation */ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GPSFactor, 1); private: @@ -112,6 +113,7 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { * @ingroup navigation */ class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GPSFactor2, 1); private: diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index feae1eb140..62e0e89241 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -170,6 +170,8 @@ class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType { */ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ImuFactor, 5); + private: typedef ImuFactor This; @@ -261,6 +263,8 @@ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ImuFactor2, 3); + private: typedef ImuFactor2 This; diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 9a718a5e1a..3321d2d857 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -31,6 +31,7 @@ namespace gtsam { * Rotation is around negative Z axis, i.e. positive is yaw to right! */ class MagFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor, 1); const Point3 measured_; ///< The measured magnetometer values const Point3 nM_; ///< Local magnetic field (mag output units) @@ -88,6 +89,7 @@ class MagFactor: public NoiseModelFactorN { * and assumes scale, direction, and the bias are given */ class MagFactor1: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor1, 1); const Point3 measured_; ///< The measured magnetometer values const Point3 nM_; ///< Local magnetic field (mag output units) @@ -126,6 +128,7 @@ class MagFactor1: public NoiseModelFactorN { * and optimizes for both nM and the bias, where nM is in units defined by magnetometer */ class MagFactor2: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor2, 2); const Point3 measured_; ///< The measured magnetometer values const Rot3 bRn_; ///< The assumed known rotation from nav to body @@ -167,6 +170,7 @@ class MagFactor2: public NoiseModelFactorN { * and optimizes for both scale, direction, and the bias. */ class MagFactor3: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor3, 3); const Point3 measured_; ///< The measured magnetometer values const Rot3 bRn_; ///< The assumed known rotation from nav to body diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index c817e22b43..791de28de8 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -26,6 +26,8 @@ namespace gtsam { */ template class MagPoseFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagPoseFactor, 1); + private: using This = MagPoseFactor; using Base = NoiseModelFactorN; diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 1fb44ebf77..df2c2b04f3 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -57,6 +57,8 @@ namespace gtsam { */ template class FunctorizedFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FunctorizedFactor, 1); + private: using Base = NoiseModelFactorN; @@ -157,6 +159,8 @@ FunctorizedFactor MakeFunctorizedFactor(Key key, const R &z, */ template class FunctorizedFactor2 : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FunctorizedFactor2, 2); + private: using Base = NoiseModelFactorN; diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index d1aa58b27a..5e2b4b99dd 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -43,6 +43,7 @@ namespace gtsam { */ template class NonlinearEquality: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(NonlinearEquality, 1); public: typedef VALUE T; @@ -293,6 +294,8 @@ struct traits > */ template class NonlinearEquality2 : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(NonlinearEquality2, 2); + protected: using Base = NoiseModelFactorN; using This = NonlinearEquality2; diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index c58179db35..76c258bbda 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -594,6 +594,51 @@ class NoiseModelFactorN : public NoiseModelFactor { }; // \class NoiseModelFactorN +/* *************************************************************************** + * THE REMAINDER OF THIS FILE IS JUST FOR DEPRECATED BACKWARD COMPATIBILITY * + * DEFINITIONS. DO NOT USE THESE FOR NEW CODE * +/* ************************************************************************* */ + +/** Convenience macros to add deprecated typedefs `X1`, `X2`, ..., `X6`. + * This was only used to maintain backwards compatibility of existing factors! + * Do NOT use for new factors! + * When transitioning from NoiseModelFactor1 to NoiseModelFactorN, this macro + * was used to add deprecated typedefs for the old NoiseModelFactor1. + * Usage example: + * ``` + * class MyFactor : public NoiseModelFactorN { + * ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MyFactor, 2); + * // class implementation ... + * }; + * + * // MyFactor::X1 == Pose3 + * // MyFactor::X2 == Point3 + * ``` + */ +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1(CLASS) \ + using X GTSAM_DEPRECATED = typename CLASS::template ValueType<1>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1_(CLASS) \ + using X1 GTSAM_DEPRECATED = typename CLASS::template ValueType<1>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS2(CLASS) \ + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1_(CLASS) \ + using X2 GTSAM_DEPRECATED = typename CLASS::template ValueType<2>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS3(CLASS) \ + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS2(CLASS) \ + using X3 GTSAM_DEPRECATED = typename CLASS::template ValueType<3>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS4(CLASS) \ + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS3(CLASS) \ + using X4 GTSAM_DEPRECATED = typename CLASS::template ValueType<4>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS5(CLASS) \ + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS4(CLASS) \ + using X5 GTSAM_DEPRECATED = typename CLASS::template ValueType<5>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS6(CLASS) \ + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS5(CLASS) \ + using X6 GTSAM_DEPRECATED = typename CLASS::template ValueType<6>; +#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(CLASS, N) \ + public: \ + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS##N(CLASS); \ + private: + /* ************************************************************************* */ /** @deprecated: use NoiseModelFactorN, replacing .key() with .key<1>() and X1 * with ValueType<1>. diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index d81ffbd319..66aaf9d2cd 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -28,6 +28,7 @@ namespace gtsam { */ template class PriorFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PriorFactor, 1); public: typedef VALUE T; diff --git a/gtsam/sfm/ShonanFactor.h b/gtsam/sfm/ShonanFactor.h index 78cc397656..c0de65d377 100644 --- a/gtsam/sfm/ShonanFactor.h +++ b/gtsam/sfm/ShonanFactor.h @@ -34,6 +34,8 @@ namespace gtsam { */ template class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ShonanFactor, 2); + Matrix M_; ///< measured rotation between R1 and R2 size_t p_, pp_; ///< dimensionality constants boost::shared_ptr G_; ///< matrix of vectorized generators diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 8850d7d2d0..a879028286 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -40,6 +40,8 @@ namespace gtsam { * */ class TranslationFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(TranslationFactor, 2); + private: typedef NoiseModelFactorN Base; Point3 measured_w_aZb_; diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index f2b41e0a1c..cfbdfc16a6 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -38,6 +38,7 @@ namespace gtsam { */ template class BetweenFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BetweenFactor, 2); // Check that VALUE type is a testable Lie group BOOST_CONCEPT_ASSERT((IsTestable)); diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 9d84dfa7be..58e4173cac 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -28,6 +28,7 @@ namespace gtsam { * @ingroup slam */ class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixConstraint, 2); private: diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 8a0277a459..5c6afdae45 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -32,6 +32,8 @@ namespace gtsam { * Factor that evaluates epipolar error p'Ep for given essential matrix */ class EssentialMatrixFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor, 1); + Vector3 vA_, vB_; ///< Homogeneous versions, in ideal coordinates typedef NoiseModelFactorN Base; @@ -107,6 +109,8 @@ class EssentialMatrixFactor : public NoiseModelFactorN { */ class EssentialMatrixFactor2 : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor2, 2); + Point3 dP1_; ///< 3D point corresponding to measurement in image 1 Point2 pn_; ///< Measurement in image 2, in ideal coordinates double f_; ///< approximate conversion factor for error scaling @@ -322,6 +326,8 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 { template class EssentialMatrixFactor4 : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor4, 2); + private: Point2 pA_, pB_; ///< points in pixel coordinates diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 60f880a7a9..98b066f711 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -49,6 +49,8 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n, */ template class FrobeniusPrior : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusPrior, 1); + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; using MatrixNN = typename Rot::MatrixNN; Eigen::Matrix vecM_; ///< vectorized matrix to approximate @@ -76,6 +78,8 @@ class FrobeniusPrior : public NoiseModelFactorN { */ template class FrobeniusFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusFactor, 2); + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; public: @@ -102,6 +106,8 @@ class FrobeniusFactor : public NoiseModelFactorN { */ template class FrobeniusBetweenFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusBetweenFactor, 2); + Rot R12_; ///< measured rotation between R1 and R2 Eigen::Matrix R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1 diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index f3089bd71f..773897e7a5 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -58,6 +58,7 @@ namespace gtsam { */ template class GeneralSFMFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GeneralSFMFactor, 2); GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA) GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK) @@ -202,6 +203,7 @@ struct traits > : Testable< */ template class GeneralSFMFactor2: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GeneralSFMFactor2, 3); GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) static const int DimK = FixedDimension::value; diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index 1550201ecd..1151e0f287 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -16,6 +16,8 @@ namespace gtsam { * Factor to measure a planar landmark from a given pose */ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OrientedPlane3Factor, 2); + protected: OrientedPlane3 measured_p_; typedef NoiseModelFactorN Base; @@ -50,6 +52,8 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OrientedPlane3DirectionPrior, 1); + protected: OrientedPlane3 measured_p_; /// measured plane parameters typedef NoiseModelFactorN Base; diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index 759e66341d..aa3cd9f5f3 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -17,6 +17,8 @@ namespace gtsam { template class PoseRotationPrior : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseRotationPrior, 1); + public: typedef PoseRotationPrior This; diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index e009ace293..e8c8300df0 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -19,6 +19,8 @@ namespace gtsam { */ template class PoseTranslationPrior : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseTranslationPrior, 1); + public: typedef PoseTranslationPrior This; typedef NoiseModelFactorN Base; diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index add6c86c4c..bb182b3ec5 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -38,6 +38,8 @@ namespace gtsam { template class GenericProjectionFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GenericProjectionFactor, 2); + protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index 74e8444046..8895a4f8b9 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -55,6 +55,8 @@ P transform_point( */ template class ReferenceFrameFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ReferenceFrameFactor, 3); + protected: /** default constructor for serialization only */ ReferenceFrameFactor() {} diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index 85539e17e5..af44de5a5b 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -21,6 +21,7 @@ namespace gtsam { * p = iRc * z */ class RotateFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(RotateFactor, 1); Point3 p_, z_; ///< Predicted and measured directions, p = iRc * z @@ -65,6 +66,7 @@ class RotateFactor: public NoiseModelFactorN { * Directions provide less constraints than a full rotation */ class RotateDirectionsFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(RotateDirectionsFactor, 1); Unit3 i_p_, c_z_; ///< Predicted and measured directions, i_p = iRc * c_z diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index 1d2ef501d6..a8a4fd25ae 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -29,6 +29,8 @@ namespace gtsam { */ template class GenericStereoFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GenericStereoFactor, 2); + private: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index f33ba2ca22..922144e331 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -31,6 +31,7 @@ namespace gtsam { */ template class TriangulationFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(TriangulationFactor, 1); public: diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index dcca226955..8afe050231 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -23,6 +23,8 @@ namespace gtsam { */ template class FullIMUFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FullIMUFactor, 2); + public: typedef NoiseModelFactorN Base; typedef FullIMUFactor This; diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 4eaa3139da..047b4d4668 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -21,6 +21,8 @@ namespace gtsam { */ template class IMUFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(IMUFactor, 2); + public: typedef NoiseModelFactorN Base; typedef IMUFactor This; diff --git a/gtsam_unstable/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index d7301a5767..14f35f734f 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -21,6 +21,8 @@ namespace gtsam { * - For sympletic Euler method: q_{k+1} = q_k + h*v_{k+1} */ class PendulumFactor1: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactor1, 3); + public: protected: @@ -67,6 +69,8 @@ class PendulumFactor1: public NoiseModelFactorN { * - For sympletic Euler method: v_{k+1} = v_k - h*g/L*sin(q_k) */ class PendulumFactor2: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactor2, 3); + public: protected: @@ -114,6 +118,8 @@ class PendulumFactor2: public NoiseModelFactorN { * \f$ = (1/h)mr^2 (q_{k+1}-q_k) + mgrh(1-alpha) sin ((1-alpha)q_k+\alpha q_{k+1}) \f$ */ class PendulumFactorPk: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactorPk, 3); + public: protected: @@ -170,6 +176,8 @@ class PendulumFactorPk: public NoiseModelFactorN { * \f$ = (1/h)mr^2 (q_{k+1}-q_k) - mgrh alpha sin ((1-alpha)q_k+\alpha q_{k+1}) \f$ */ class PendulumFactorPk1: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactorPk1, 3); + public: protected: diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 941b7c7acc..6e64408f53 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -25,6 +25,7 @@ namespace gtsam { * in sequential update method. */ class Reconstruction : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Reconstruction, 3); double h_; // time step typedef NoiseModelFactorN Base; @@ -74,6 +75,7 @@ class Reconstruction : public NoiseModelFactorN { * Implement the Discrete Euler-Poincare' equation: */ class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(DiscreteEulerPoincareHelicopter, 3); double h_; /// time step Matrix Inertia_; /// Inertia tensors Inertia = [ J 0; 0 M ] diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index 0fa3d9cb73..ea952831b9 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -33,6 +33,8 @@ typedef enum { * if timesteps are small. */ class VelocityConstraint : public gtsam::NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(VelocityConstraint, 2); + public: typedef gtsam::NoiseModelFactorN Base; diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index 2880b9c8cd..6e2bfaa146 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -11,6 +11,8 @@ namespace gtsam { class VelocityConstraint3 : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(VelocityConstraint3, 3); + public: protected: diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index 6f0aa605b8..62bb0c155d 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -28,6 +28,7 @@ namespace gtsam { * @ingroup slam */ class BiasedGPSFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BiasedGPSFactor, 2); private: diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index 43001fbc2a..647c9a1aaa 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -89,6 +89,7 @@ namespace gtsam { template class EquivInertialNavFactor_GlobalVel : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EquivInertialNavFactor_GlobalVel, 5); private: diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 6423fabda3..c8dca9fd16 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -88,6 +88,7 @@ namespace gtsam { template class EquivInertialNavFactor_GlobalVel_NoBias : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EquivInertialNavFactor_GlobalVel_NoBias, 4); private: diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index c3682e536d..5bafd3bf03 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -43,6 +43,7 @@ namespace gtsam { */ template class GaussMarkov1stOrderFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GaussMarkov1stOrderFactor, 2); private: diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index efaf71d229..284b58b963 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -78,6 +78,7 @@ namespace gtsam { */ template class InertialNavFactor_GlobalVelocity : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InertialNavFactor_GlobalVelocity, 5); private: diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 59a834f0b7..0bbd9ba912 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -25,6 +25,8 @@ namespace gtsam { */ template class InvDepthFactor3: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactor3, 3); + protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index a41a06ccde..cd860b73e0 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -25,6 +25,8 @@ namespace gtsam { * Binary factor representing a visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant1: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant1, 2); + protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index d120eff321..d14f67c0f8 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -26,6 +26,8 @@ namespace gtsam { * Binary factor representing a visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant2: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant2, 2); + protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index cade280f0d..ce2def7eb1 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -25,6 +25,8 @@ namespace gtsam { * Binary factor representing the first visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant3a: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant3a, 2); + protected: // Keep a copy of measurement and calibration for I/O @@ -151,6 +153,8 @@ class InvDepthFactorVariant3a: public NoiseModelFactorN { * Ternary factor representing a visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant3b: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant3b, 3); + protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index f2c5dd3a97..d97f07ed9f 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h @@ -36,6 +36,8 @@ namespace gtsam { */ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(LocalOrientedPlane3Factor, 3); + protected: OrientedPlane3 measured_p_; typedef NoiseModelFactorN Base; diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index b49b491314..24bcd86677 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -36,6 +36,7 @@ namespace gtsam { */ template class PartialPriorFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PartialPriorFactor, 1); public: typedef VALUE T; diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index 676e011de2..05ac3d454f 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -30,6 +30,7 @@ namespace gtsam { */ template class PoseBetweenFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseBetweenFactor, 2); private: diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index c7a094bda3..dd79f2045b 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -27,6 +27,7 @@ namespace gtsam { */ template class PosePriorFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PosePriorFactor, 1); private: diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index ad1ba5fbe6..895551ce25 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -22,6 +22,8 @@ namespace gtsam { */ template class PoseToPointFactor : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseToPointFactor, 2); + private: typedef PoseToPointFactor This; typedef NoiseModelFactorN Base; diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index 8962b31b2d..469ab831bd 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -32,6 +32,8 @@ namespace gtsam { */ template class ProjectionFactorPPP: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ProjectionFactorPPP, 3); + protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index afbf858382..963652fd91 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -35,6 +35,8 @@ namespace gtsam { template class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ProjectionFactorPPPC, 4); + protected: Point2 measured_; ///< 2D measurement diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 806f54fa55..7a198d14a4 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -43,6 +43,9 @@ namespace gtsam { class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter : public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ProjectionFactorRollingShutter, + 3); + protected: // Keep a copy of measurement and calibration for I/O Point2 measured_; ///< 2D measurement diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index c6273ff4bb..7f453f08d4 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -26,6 +26,8 @@ namespace gtsam { * TODO: enable use of a Pose3 for the target as well */ class GTSAM_UNSTABLE_EXPORT RelativeElevationFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(RelativeElevationFactor, 2); + private: double measured_; /** measurement */ diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index 2e024c5bbe..d85afabce3 100644 --- a/gtsam_unstable/slam/TSAMFactors.h +++ b/gtsam_unstable/slam/TSAMFactors.h @@ -27,6 +27,7 @@ namespace gtsam { * DeltaFactor: relative 2D measurement between Pose2 and Point2 */ class DeltaFactor: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(DeltaFactor, 2); public: typedef DeltaFactor This; @@ -56,6 +57,7 @@ class DeltaFactor: public NoiseModelFactorN { * DeltaFactorBase: relative 2D measurement between Pose2 and Point2, with Basenodes */ class DeltaFactorBase: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(DeltaFactorBase, 4); public: typedef DeltaFactorBase This; @@ -111,6 +113,7 @@ class DeltaFactorBase: public NoiseModelFactorN { * OdometryFactorBase: Pose2 odometry, with Basenodes */ class OdometryFactorBase: public NoiseModelFactorN { + ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OdometryFactorBase, 4); public: typedef OdometryFactorBase This; diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index c536a48c3f..e368132d9e 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -380,6 +380,10 @@ TEST(NonlinearFactor, NoiseModelFactor1) { EXPECT(assert_equal(tf.key(), L(1))); std::vector H = {Matrix()}; EXPECT(assert_equal(Vector1(1.0), tf.unwhitenedError(tv, H))); + IGNORE_DEPRECATED_PUSH + static_assert(std::is_same::X, double>::value, + "PriorFactor backwards compatibility type incorrect"); + DIAGNOSTIC_POP() // Test constructors TestFactor1 tf2(noiseModel::Unit::Create(1), L(1)); From f013394604161e47c829f40fb593e39b5a518c45 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 26 Dec 2022 22:09:52 -0500 Subject: [PATCH 2/8] suppress deprecations warnings when building deprecated NoiseModelFactor1-6 classes. --- gtsam/nonlinear/NonlinearFactor.h | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 76c258bbda..399d512812 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -594,10 +594,10 @@ class NoiseModelFactorN : public NoiseModelFactor { }; // \class NoiseModelFactorN -/* *************************************************************************** - * THE REMAINDER OF THIS FILE IS JUST FOR DEPRECATED BACKWARD COMPATIBILITY * - * DEFINITIONS. DO NOT USE THESE FOR NEW CODE * -/* ************************************************************************* */ +/****************************************************************************** + * THE REMAINDER OF THIS FILE IS JUST FOR DEPRECATED BACKWARD COMPATIBILITY * + * DEFINITIONS. DO NOT USE THESE FOR NEW CODE * + ******************************************************************************/ /** Convenience macros to add deprecated typedefs `X1`, `X2`, ..., `X6`. * This was only used to maintain backwards compatibility of existing factors! @@ -649,6 +649,9 @@ class NoiseModelFactorN : public NoiseModelFactor { * A convenient base class for creating your own NoiseModelFactor * with 1 variable. To derive from this class, implement evaluateError(). */ +CLANG_DIAGNOSTIC_PUSH_IGNORE("-Wdeprecated-declarations") // Silence warnings +GCC_DIAGNOSTIC_PUSH_IGNORE("-Wdeprecated-declarations") // while we define +MSVC_DIAGNOSTIC_PUSH_IGNORE(4996) // deprecated classes template class GTSAM_DEPRECATED NoiseModelFactor1 : public NoiseModelFactorN { public: @@ -902,5 +905,6 @@ class GTSAM_DEPRECATED NoiseModelFactor6 "NoiseModelFactor", boost::serialization::base_object(*this)); } }; // \class NoiseModelFactor6 +DIAGNOSTIC_POP() // Finish silencing warnings } // \namespace gtsam From 148ac147ada6a77e3ac6d5390528db5018bd7654 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 26 Dec 2022 22:28:47 -0500 Subject: [PATCH 3/8] Switch ExtendedKalmanFilter.h back to deprecated version --- gtsam/nonlinear/ExtendedKalmanFilter.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/nonlinear/ExtendedKalmanFilter.h b/gtsam/nonlinear/ExtendedKalmanFilter.h index d76a6ea7e6..dc51de7bbb 100644 --- a/gtsam/nonlinear/ExtendedKalmanFilter.h +++ b/gtsam/nonlinear/ExtendedKalmanFilter.h @@ -53,8 +53,8 @@ class ExtendedKalmanFilter { #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 //@deprecated: any NoiseModelFactor will do, as long as they have the right keys - typedef NoiseModelFactorN MotionFactor; - typedef NoiseModelFactorN MeasurementFactor; + typedef NoiseModelFactor2 MotionFactor; + typedef NoiseModelFactor1 MeasurementFactor; #endif protected: From 311c546b3f4cece4ae53536d4b5bb34864366ca6 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 4 Jan 2023 10:49:38 -0500 Subject: [PATCH 4/8] update example code file to use NoiseModelFactorN --- doc/Code/LocalizationFactor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp index 2c1f01c435..f20b93c6e9 100644 --- a/doc/Code/LocalizationFactor.cpp +++ b/doc/Code/LocalizationFactor.cpp @@ -1,9 +1,9 @@ -class UnaryFactor: public NoiseModelFactor1 { +class UnaryFactor: public NoiseModelFactorN { double mx_, my_; ///< X and Y measurements public: UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): - NoiseModelFactor1(model, j), mx_(x), my_(y) {} + NoiseModelFactorN(model, j), mx_(x), my_(y) {} Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const override { From e88a17a4ece1eddf5c2af795c698509e8cdadd6c Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 4 Jan 2023 12:28:32 -0500 Subject: [PATCH 5/8] switch `using` to `typedef` for MSVC MSVC only supports deprecated typedefs, not deprecated `using`. --- gtsam/nonlinear/NonlinearFactor.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 399d512812..0c090a87db 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -616,24 +616,24 @@ class NoiseModelFactorN : public NoiseModelFactor { * ``` */ #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1(CLASS) \ - using X GTSAM_DEPRECATED = typename CLASS::template ValueType<1>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<1> X; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1_(CLASS) \ - using X1 GTSAM_DEPRECATED = typename CLASS::template ValueType<1>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<1> X1; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS2(CLASS) \ ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1_(CLASS) \ - using X2 GTSAM_DEPRECATED = typename CLASS::template ValueType<2>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<2> X2; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS3(CLASS) \ ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS2(CLASS) \ - using X3 GTSAM_DEPRECATED = typename CLASS::template ValueType<3>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<3> X3; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS4(CLASS) \ ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS3(CLASS) \ - using X4 GTSAM_DEPRECATED = typename CLASS::template ValueType<4>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<4> X4; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS5(CLASS) \ ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS4(CLASS) \ - using X5 GTSAM_DEPRECATED = typename CLASS::template ValueType<5>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<5> X5; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS6(CLASS) \ ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS5(CLASS) \ - using X6 GTSAM_DEPRECATED = typename CLASS::template ValueType<6>; + typedef GTSAM_DEPRECATED typename CLASS::template ValueType<6> X6; #define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(CLASS, N) \ public: \ ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS##N(CLASS); \ From 831cb350e9a7ba14b2048aaad2e17437f8c07585 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 4 Jan 2023 14:30:31 -0500 Subject: [PATCH 6/8] remove macro versions, in prep for inheritance version --- gtsam/navigation/AHRSFactor.h | 1 - gtsam/navigation/AttitudeFactor.h | 2 -- gtsam/navigation/BarometricFactor.h | 1 - gtsam/navigation/CombinedImuFactor.h | 1 - gtsam/navigation/ConstantVelocityFactor.h | 1 - gtsam/navigation/GPSFactor.h | 2 -- gtsam/navigation/ImuFactor.h | 2 -- gtsam/navigation/MagFactor.h | 4 ---- gtsam/navigation/MagPoseFactor.h | 1 - gtsam/nonlinear/FunctorizedFactor.h | 2 -- gtsam/nonlinear/NonlinearEquality.h | 2 -- gtsam/nonlinear/PriorFactor.h | 1 - gtsam/sfm/ShonanFactor.h | 1 - gtsam/sfm/TranslationFactor.h | 1 - gtsam/slam/BetweenFactor.h | 1 - gtsam/slam/EssentialMatrixConstraint.h | 1 - gtsam/slam/EssentialMatrixFactor.h | 3 --- gtsam/slam/FrobeniusFactor.h | 3 --- gtsam/slam/GeneralSFMFactor.h | 2 -- gtsam/slam/OrientedPlane3Factor.h | 2 -- gtsam/slam/PoseRotationPrior.h | 1 - gtsam/slam/PoseTranslationPrior.h | 1 - gtsam/slam/ProjectionFactor.h | 1 - gtsam/slam/ReferenceFrameFactor.h | 1 - gtsam/slam/StereoFactor.h | 1 - gtsam/slam/TriangulationFactor.h | 1 - gtsam_unstable/dynamics/FullIMUFactor.h | 1 - gtsam_unstable/dynamics/IMUFactor.h | 1 - gtsam_unstable/dynamics/Pendulum.h | 4 ---- gtsam_unstable/dynamics/SimpleHelicopter.h | 2 -- gtsam_unstable/dynamics/VelocityConstraint.h | 1 - gtsam_unstable/dynamics/VelocityConstraint3.h | 1 - gtsam_unstable/slam/BiasedGPSFactor.h | 1 - gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h | 1 - gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h | 1 - gtsam_unstable/slam/GaussMarkov1stOrderFactor.h | 1 - gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h | 1 - gtsam_unstable/slam/InvDepthFactor3.h | 1 - gtsam_unstable/slam/InvDepthFactorVariant1.h | 1 - gtsam_unstable/slam/InvDepthFactorVariant2.h | 1 - gtsam_unstable/slam/InvDepthFactorVariant3.h | 2 -- gtsam_unstable/slam/LocalOrientedPlane3Factor.h | 1 - gtsam_unstable/slam/PartialPriorFactor.h | 1 - gtsam_unstable/slam/PoseBetweenFactor.h | 1 - gtsam_unstable/slam/PosePriorFactor.h | 1 - gtsam_unstable/slam/PoseToPointFactor.h | 1 - gtsam_unstable/slam/ProjectionFactorPPP.h | 1 - gtsam_unstable/slam/ProjectionFactorPPPC.h | 1 - gtsam_unstable/slam/ProjectionFactorRollingShutter.h | 1 - gtsam_unstable/slam/RelativeElevationFactor.h | 1 - gtsam_unstable/slam/TSAMFactors.h | 3 --- 51 files changed, 72 deletions(-) diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 6bca61a41d..77501bdef1 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -129,7 +129,6 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation }; class GTSAM_EXPORT AHRSFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(AHRSFactor, 3); typedef AHRSFactor This; typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 1ed4cc4bb5..25d9535d63 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -77,7 +77,6 @@ class AttitudeFactor { * @ingroup navigation */ class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN, public AttitudeFactor { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Rot3AttitudeFactor, 1); typedef NoiseModelFactorN Base; @@ -153,7 +152,6 @@ template<> struct traits : public Testable, public AttitudeFactor { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Pose3AttitudeFactor, 1); typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index b24d43396f..c9db48141c 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -32,7 +32,6 @@ namespace gtsam { * @ingroup navigation */ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BarometricFactor, 2); private: typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 0107cd2326..7e8ecde41e 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -257,7 +257,6 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType */ class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(CombinedImuFactor, 6); private: diff --git a/gtsam/navigation/ConstantVelocityFactor.h b/gtsam/navigation/ConstantVelocityFactor.h index 03cfa848ea..3bf6b20132 100644 --- a/gtsam/navigation/ConstantVelocityFactor.h +++ b/gtsam/navigation/ConstantVelocityFactor.h @@ -27,7 +27,6 @@ namespace gtsam { * The only measurement is dt, the time delta between the states. */ class ConstantVelocityFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ConstantVelocityFactor, 2); double dt_; diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index aab4582fce..e515d90122 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -33,7 +33,6 @@ namespace gtsam { * @ingroup navigation */ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GPSFactor, 1); private: @@ -113,7 +112,6 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { * @ingroup navigation */ class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GPSFactor2, 1); private: diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 62e0e89241..74d315da3c 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -170,7 +170,6 @@ class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType { */ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ImuFactor, 5); private: @@ -263,7 +262,6 @@ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ImuFactor2, 3); private: diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 3321d2d857..9a718a5e1a 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -31,7 +31,6 @@ namespace gtsam { * Rotation is around negative Z axis, i.e. positive is yaw to right! */ class MagFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor, 1); const Point3 measured_; ///< The measured magnetometer values const Point3 nM_; ///< Local magnetic field (mag output units) @@ -89,7 +88,6 @@ class MagFactor: public NoiseModelFactorN { * and assumes scale, direction, and the bias are given */ class MagFactor1: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor1, 1); const Point3 measured_; ///< The measured magnetometer values const Point3 nM_; ///< Local magnetic field (mag output units) @@ -128,7 +126,6 @@ class MagFactor1: public NoiseModelFactorN { * and optimizes for both nM and the bias, where nM is in units defined by magnetometer */ class MagFactor2: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor2, 2); const Point3 measured_; ///< The measured magnetometer values const Rot3 bRn_; ///< The assumed known rotation from nav to body @@ -170,7 +167,6 @@ class MagFactor2: public NoiseModelFactorN { * and optimizes for both scale, direction, and the bias. */ class MagFactor3: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagFactor3, 3); const Point3 measured_; ///< The measured magnetometer values const Rot3 bRn_; ///< The assumed known rotation from nav to body diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index 791de28de8..eeb4224f92 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -26,7 +26,6 @@ namespace gtsam { */ template class MagPoseFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagPoseFactor, 1); private: using This = MagPoseFactor; diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index df2c2b04f3..50c1885105 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -57,7 +57,6 @@ namespace gtsam { */ template class FunctorizedFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FunctorizedFactor, 1); private: using Base = NoiseModelFactorN; @@ -159,7 +158,6 @@ FunctorizedFactor MakeFunctorizedFactor(Key key, const R &z, */ template class FunctorizedFactor2 : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FunctorizedFactor2, 2); private: using Base = NoiseModelFactorN; diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 5e2b4b99dd..b7cd655521 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -43,7 +43,6 @@ namespace gtsam { */ template class NonlinearEquality: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(NonlinearEquality, 1); public: typedef VALUE T; @@ -294,7 +293,6 @@ struct traits > */ template class NonlinearEquality2 : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(NonlinearEquality2, 2); protected: using Base = NoiseModelFactorN; diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 66aaf9d2cd..d81ffbd319 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -28,7 +28,6 @@ namespace gtsam { */ template class PriorFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PriorFactor, 1); public: typedef VALUE T; diff --git a/gtsam/sfm/ShonanFactor.h b/gtsam/sfm/ShonanFactor.h index c0de65d377..e0411c8ff5 100644 --- a/gtsam/sfm/ShonanFactor.h +++ b/gtsam/sfm/ShonanFactor.h @@ -34,7 +34,6 @@ namespace gtsam { */ template class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ShonanFactor, 2); Matrix M_; ///< measured rotation between R1 and R2 size_t p_, pp_; ///< dimensionality constants diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index a879028286..e87a1159a6 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -40,7 +40,6 @@ namespace gtsam { * */ class TranslationFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(TranslationFactor, 2); private: typedef NoiseModelFactorN Base; diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index cfbdfc16a6..f2b41e0a1c 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -38,7 +38,6 @@ namespace gtsam { */ template class BetweenFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BetweenFactor, 2); // Check that VALUE type is a testable Lie group BOOST_CONCEPT_ASSERT((IsTestable)); diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 58e4173cac..9d84dfa7be 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -28,7 +28,6 @@ namespace gtsam { * @ingroup slam */ class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixConstraint, 2); private: diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 5c6afdae45..0d02ef681b 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -32,7 +32,6 @@ namespace gtsam { * Factor that evaluates epipolar error p'Ep for given essential matrix */ class EssentialMatrixFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor, 1); Vector3 vA_, vB_; ///< Homogeneous versions, in ideal coordinates @@ -109,7 +108,6 @@ class EssentialMatrixFactor : public NoiseModelFactorN { */ class EssentialMatrixFactor2 : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor2, 2); Point3 dP1_; ///< 3D point corresponding to measurement in image 1 Point2 pn_; ///< Measurement in image 2, in ideal coordinates @@ -326,7 +324,6 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 { template class EssentialMatrixFactor4 : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor4, 2); private: Point2 pA_, pB_; ///< points in pixel coordinates diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 98b066f711..dcb8d96f9f 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -49,7 +49,6 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n, */ template class FrobeniusPrior : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusPrior, 1); enum { Dim = Rot::VectorN2::RowsAtCompileTime }; using MatrixNN = typename Rot::MatrixNN; @@ -78,7 +77,6 @@ class FrobeniusPrior : public NoiseModelFactorN { */ template class FrobeniusFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusFactor, 2); enum { Dim = Rot::VectorN2::RowsAtCompileTime }; @@ -106,7 +104,6 @@ class FrobeniusFactor : public NoiseModelFactorN { */ template class FrobeniusBetweenFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusBetweenFactor, 2); Rot R12_; ///< measured rotation between R1 and R2 Eigen::Matrix diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 773897e7a5..f3089bd71f 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -58,7 +58,6 @@ namespace gtsam { */ template class GeneralSFMFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GeneralSFMFactor, 2); GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA) GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK) @@ -203,7 +202,6 @@ struct traits > : Testable< */ template class GeneralSFMFactor2: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GeneralSFMFactor2, 3); GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) static const int DimK = FixedDimension::value; diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index 1151e0f287..0ef9fd91bc 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -16,7 +16,6 @@ namespace gtsam { * Factor to measure a planar landmark from a given pose */ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OrientedPlane3Factor, 2); protected: OrientedPlane3 measured_p_; @@ -52,7 +51,6 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OrientedPlane3DirectionPrior, 1); protected: OrientedPlane3 measured_p_; /// measured plane parameters diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index aa3cd9f5f3..aaa7e780af 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -17,7 +17,6 @@ namespace gtsam { template class PoseRotationPrior : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseRotationPrior, 1); public: diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index e8c8300df0..68c9f69cad 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -19,7 +19,6 @@ namespace gtsam { */ template class PoseTranslationPrior : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseTranslationPrior, 1); public: typedef PoseTranslationPrior This; diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index bb182b3ec5..23b6d3dad4 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -38,7 +38,6 @@ namespace gtsam { template class GenericProjectionFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GenericProjectionFactor, 2); protected: diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index 8895a4f8b9..31f3c3c923 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -55,7 +55,6 @@ P transform_point( */ template class ReferenceFrameFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ReferenceFrameFactor, 3); protected: /** default constructor for serialization only */ diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index a8a4fd25ae..c3a28a0b18 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -29,7 +29,6 @@ namespace gtsam { */ template class GenericStereoFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GenericStereoFactor, 2); private: diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 922144e331..f33ba2ca22 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -31,7 +31,6 @@ namespace gtsam { */ template class TriangulationFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(TriangulationFactor, 1); public: diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index 8afe050231..de5683c9ee 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -23,7 +23,6 @@ namespace gtsam { */ template class FullIMUFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FullIMUFactor, 2); public: typedef NoiseModelFactorN Base; diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 047b4d4668..23268d966e 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -21,7 +21,6 @@ namespace gtsam { */ template class IMUFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(IMUFactor, 2); public: typedef NoiseModelFactorN Base; diff --git a/gtsam_unstable/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index 14f35f734f..27aa604ca5 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -21,7 +21,6 @@ namespace gtsam { * - For sympletic Euler method: q_{k+1} = q_k + h*v_{k+1} */ class PendulumFactor1: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactor1, 3); public: @@ -69,7 +68,6 @@ class PendulumFactor1: public NoiseModelFactorN { * - For sympletic Euler method: v_{k+1} = v_k - h*g/L*sin(q_k) */ class PendulumFactor2: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactor2, 3); public: @@ -118,7 +116,6 @@ class PendulumFactor2: public NoiseModelFactorN { * \f$ = (1/h)mr^2 (q_{k+1}-q_k) + mgrh(1-alpha) sin ((1-alpha)q_k+\alpha q_{k+1}) \f$ */ class PendulumFactorPk: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactorPk, 3); public: @@ -176,7 +173,6 @@ class PendulumFactorPk: public NoiseModelFactorN { * \f$ = (1/h)mr^2 (q_{k+1}-q_k) - mgrh alpha sin ((1-alpha)q_k+\alpha q_{k+1}) \f$ */ class PendulumFactorPk1: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PendulumFactorPk1, 3); public: diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 6e64408f53..941b7c7acc 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -25,7 +25,6 @@ namespace gtsam { * in sequential update method. */ class Reconstruction : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Reconstruction, 3); double h_; // time step typedef NoiseModelFactorN Base; @@ -75,7 +74,6 @@ class Reconstruction : public NoiseModelFactorN { * Implement the Discrete Euler-Poincare' equation: */ class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(DiscreteEulerPoincareHelicopter, 3); double h_; /// time step Matrix Inertia_; /// Inertia tensors Inertia = [ J 0; 0 M ] diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index ea952831b9..5124f9e938 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -33,7 +33,6 @@ typedef enum { * if timesteps are small. */ class VelocityConstraint : public gtsam::NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(VelocityConstraint, 2); public: typedef gtsam::NoiseModelFactorN Base; diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index 6e2bfaa146..417837835c 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -11,7 +11,6 @@ namespace gtsam { class VelocityConstraint3 : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(VelocityConstraint3, 3); public: diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index 62bb0c155d..6f0aa605b8 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -28,7 +28,6 @@ namespace gtsam { * @ingroup slam */ class BiasedGPSFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BiasedGPSFactor, 2); private: diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index 647c9a1aaa..43001fbc2a 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -89,7 +89,6 @@ namespace gtsam { template class EquivInertialNavFactor_GlobalVel : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EquivInertialNavFactor_GlobalVel, 5); private: diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index c8dca9fd16..6423fabda3 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -88,7 +88,6 @@ namespace gtsam { template class EquivInertialNavFactor_GlobalVel_NoBias : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EquivInertialNavFactor_GlobalVel_NoBias, 4); private: diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index 5bafd3bf03..c3682e536d 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -43,7 +43,6 @@ namespace gtsam { */ template class GaussMarkov1stOrderFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GaussMarkov1stOrderFactor, 2); private: diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index 284b58b963..efaf71d229 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -78,7 +78,6 @@ namespace gtsam { */ template class InertialNavFactor_GlobalVelocity : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InertialNavFactor_GlobalVelocity, 5); private: diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 0bbd9ba912..8ba1ca79ac 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -25,7 +25,6 @@ namespace gtsam { */ template class InvDepthFactor3: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactor3, 3); protected: diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index cd860b73e0..b64c13778a 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -25,7 +25,6 @@ namespace gtsam { * Binary factor representing a visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant1: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant1, 2); protected: diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index d14f67c0f8..8ae69ea298 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -26,7 +26,6 @@ namespace gtsam { * Binary factor representing a visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant2: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant2, 2); protected: diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index ce2def7eb1..835c5ecf5b 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -25,7 +25,6 @@ namespace gtsam { * Binary factor representing the first visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant3a: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant3a, 2); protected: @@ -153,7 +152,6 @@ class InvDepthFactorVariant3a: public NoiseModelFactorN { * Ternary factor representing a visual measurement using an inverse-depth parameterization */ class InvDepthFactorVariant3b: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(InvDepthFactorVariant3b, 3); protected: diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index d97f07ed9f..97195ae11b 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h @@ -36,7 +36,6 @@ namespace gtsam { */ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(LocalOrientedPlane3Factor, 3); protected: OrientedPlane3 measured_p_; diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 24bcd86677..b49b491314 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -36,7 +36,6 @@ namespace gtsam { */ template class PartialPriorFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PartialPriorFactor, 1); public: typedef VALUE T; diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index 05ac3d454f..676e011de2 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -30,7 +30,6 @@ namespace gtsam { */ template class PoseBetweenFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseBetweenFactor, 2); private: diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index dd79f2045b..c7a094bda3 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -27,7 +27,6 @@ namespace gtsam { */ template class PosePriorFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PosePriorFactor, 1); private: diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 895551ce25..bea8be85ed 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -22,7 +22,6 @@ namespace gtsam { */ template class PoseToPointFactor : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseToPointFactor, 2); private: typedef PoseToPointFactor This; diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index 469ab831bd..b056e7f387 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -32,7 +32,6 @@ namespace gtsam { */ template class ProjectionFactorPPP: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ProjectionFactorPPP, 3); protected: diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index 963652fd91..2de3110e06 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -35,7 +35,6 @@ namespace gtsam { template class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ProjectionFactorPPPC, 4); protected: Point2 measured_; ///< 2D measurement diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 7a198d14a4..4ebcd771f8 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -43,7 +43,6 @@ namespace gtsam { class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter : public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ProjectionFactorRollingShutter, 3); protected: diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index 7f453f08d4..851ecaadc5 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -26,7 +26,6 @@ namespace gtsam { * TODO: enable use of a Pose3 for the target as well */ class GTSAM_UNSTABLE_EXPORT RelativeElevationFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(RelativeElevationFactor, 2); private: diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index d85afabce3..2e024c5bbe 100644 --- a/gtsam_unstable/slam/TSAMFactors.h +++ b/gtsam_unstable/slam/TSAMFactors.h @@ -27,7 +27,6 @@ namespace gtsam { * DeltaFactor: relative 2D measurement between Pose2 and Point2 */ class DeltaFactor: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(DeltaFactor, 2); public: typedef DeltaFactor This; @@ -57,7 +56,6 @@ class DeltaFactor: public NoiseModelFactorN { * DeltaFactorBase: relative 2D measurement between Pose2 and Point2, with Basenodes */ class DeltaFactorBase: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(DeltaFactorBase, 4); public: typedef DeltaFactorBase This; @@ -113,7 +111,6 @@ class DeltaFactorBase: public NoiseModelFactorN { * OdometryFactorBase: Pose2 odometry, with Basenodes */ class OdometryFactorBase: public NoiseModelFactorN { - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OdometryFactorBase, 4); public: typedef OdometryFactorBase This; From f5b9762a7ccc946300e9b12383b25b20ab999d36 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 4 Jan 2023 22:14:22 -0500 Subject: [PATCH 7/8] Cleaner version of deprecated alias typedefs --- gtsam/navigation/AHRSFactor.h | 5 +- gtsam/navigation/AttitudeFactor.h | 4 +- gtsam/navigation/BarometricFactor.h | 4 +- gtsam/navigation/CombinedImuFactor.h | 10 +- gtsam/navigation/ConstantVelocityFactor.h | 3 +- gtsam/navigation/GPSFactor.h | 6 +- gtsam/navigation/ImuFactor.h | 5 +- gtsam/navigation/MagFactor.h | 12 +- gtsam/navigation/MagPoseFactor.h | 3 +- gtsam/nonlinear/FunctorizedFactor.h | 6 +- gtsam/nonlinear/NonlinearEquality.h | 9 +- gtsam/nonlinear/NonlinearFactor.h | 165 +++++++----------- gtsam/nonlinear/PriorFactor.h | 3 +- gtsam/sfm/ShonanFactor.h | 3 +- gtsam/sfm/TranslationFactor.h | 3 +- gtsam/slam/BetweenFactor.h | 3 +- gtsam/slam/BoundingConstraint.h | 6 +- gtsam/slam/EssentialMatrixConstraint.h | 3 +- gtsam/slam/EssentialMatrixFactor.h | 9 +- gtsam/slam/FrobeniusFactor.h | 9 +- gtsam/slam/GeneralSFMFactor.h | 6 +- gtsam/slam/OrientedPlane3Factor.h | 6 +- gtsam/slam/PoseRotationPrior.h | 3 +- gtsam/slam/PoseTranslationPrior.h | 3 +- gtsam/slam/ProjectionFactor.h | 3 +- gtsam/slam/ReferenceFrameFactor.h | 3 +- gtsam/slam/RotateFactor.h | 6 +- gtsam/slam/StereoFactor.h | 3 +- gtsam/slam/TriangulationFactor.h | 3 +- gtsam_unstable/dynamics/FullIMUFactor.h | 3 +- gtsam_unstable/dynamics/IMUFactor.h | 3 +- gtsam_unstable/dynamics/Pendulum.h | 12 +- gtsam_unstable/dynamics/SimpleHelicopter.h | 6 +- gtsam_unstable/dynamics/VelocityConstraint3.h | 3 +- gtsam_unstable/slam/BiasedGPSFactor.h | 3 +- .../slam/EquivInertialNavFactor_GlobalVel.h | 3 +- .../EquivInertialNavFactor_GlobalVel_NoBias.h | 3 +- .../slam/GaussMarkov1stOrderFactor.h | 3 +- .../slam/InertialNavFactor_GlobalVelocity.h | 3 +- gtsam_unstable/slam/InvDepthFactor3.h | 3 +- gtsam_unstable/slam/InvDepthFactorVariant1.h | 3 +- gtsam_unstable/slam/InvDepthFactorVariant2.h | 3 +- gtsam_unstable/slam/InvDepthFactorVariant3.h | 6 +- .../slam/LocalOrientedPlane3Factor.h | 3 +- gtsam_unstable/slam/PartialPriorFactor.h | 3 +- gtsam_unstable/slam/PoseBetweenFactor.h | 3 +- gtsam_unstable/slam/PosePriorFactor.h | 3 +- gtsam_unstable/slam/PoseToPointFactor.h | 3 +- gtsam_unstable/slam/ProjectionFactorPPP.h | 3 +- gtsam_unstable/slam/ProjectionFactorPPPC.h | 3 +- .../slam/ProjectionFactorRollingShutter.h | 3 +- gtsam_unstable/slam/RelativeElevationFactor.h | 3 +- gtsam_unstable/slam/TSAMFactors.h | 9 +- 53 files changed, 219 insertions(+), 181 deletions(-) diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 77501bdef1..87bd064b11 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -128,8 +128,9 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation } }; -class GTSAM_EXPORT AHRSFactor : public NoiseModelFactorN { - +class GTSAM_EXPORT AHRSFactor + : public NoiseModelFactorN, + public DeprecatedFactorAliases { typedef AHRSFactor This; typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 25d9535d63..d08db0d74a 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -76,7 +76,8 @@ class AttitudeFactor { * Version of AttitudeFactor for Rot3 * @ingroup navigation */ -class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN, public AttitudeFactor { +class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases, public AttitudeFactor { typedef NoiseModelFactorN Base; @@ -151,6 +152,7 @@ template<> struct traits : public Testable, + public DeprecatedFactorAliases, public AttitudeFactor { typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index c9db48141c..49a018cfb8 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -31,7 +31,9 @@ namespace gtsam { * https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html * @ingroup navigation */ -class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { +class GTSAM_EXPORT BarometricFactor + : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: typedef NoiseModelFactorN Base; diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 7e8ecde41e..b32449ec1f 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -255,10 +255,12 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType * * @ingroup navigation */ -class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN { - -private: +class GTSAM_EXPORT CombinedImuFactor + : public NoiseModelFactorN, + public DeprecatedFactorAliases { + private: typedef CombinedImuFactor This; typedef NoiseModelFactorN { +class ConstantVelocityFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { double dt_; diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index e515d90122..4b366d2d2a 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -32,7 +32,8 @@ namespace gtsam { * See Farrell08book or e.g. http://www.dirsig.org/docs/new/coordinates.html * @ingroup navigation */ -class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { +class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: @@ -111,7 +112,8 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { * Version of GPSFactor for NavState * @ingroup navigation */ -class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN { +class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 74d315da3c..8d15c097b9 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -169,6 +169,8 @@ class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType { * @ingroup navigation */ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: @@ -261,7 +263,8 @@ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN { +class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 9a718a5e1a..49d5286a4e 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -30,7 +30,8 @@ namespace gtsam { * and assumes scale, direction, and the bias are given. * Rotation is around negative Z axis, i.e. positive is yaw to right! */ -class MagFactor: public NoiseModelFactorN { +class MagFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { const Point3 measured_; ///< The measured magnetometer values const Point3 nM_; ///< Local magnetic field (mag output units) @@ -87,7 +88,8 @@ class MagFactor: public NoiseModelFactorN { * This version uses model measured bM = scale * bRn * direction + bias * and assumes scale, direction, and the bias are given */ -class MagFactor1: public NoiseModelFactorN { +class MagFactor1: public NoiseModelFactorN, + public DeprecatedFactorAliases { const Point3 measured_; ///< The measured magnetometer values const Point3 nM_; ///< Local magnetic field (mag output units) @@ -125,7 +127,8 @@ class MagFactor1: public NoiseModelFactorN { * This version uses model measured bM = bRn * nM + bias * and optimizes for both nM and the bias, where nM is in units defined by magnetometer */ -class MagFactor2: public NoiseModelFactorN { +class MagFactor2: public NoiseModelFactorN, + public DeprecatedFactorAliases { const Point3 measured_; ///< The measured magnetometer values const Rot3 bRn_; ///< The assumed known rotation from nav to body @@ -166,7 +169,8 @@ class MagFactor2: public NoiseModelFactorN { * This version uses model measured bM = scale * bRn * direction + bias * and optimizes for both scale, direction, and the bias. */ -class MagFactor3: public NoiseModelFactorN { +class MagFactor3: public NoiseModelFactorN, + public DeprecatedFactorAliases { const Point3 measured_; ///< The measured magnetometer values const Rot3 bRn_; ///< The assumed known rotation from nav to body diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index eeb4224f92..9c32e2ac41 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -25,7 +25,8 @@ namespace gtsam { * expressed in the sensor frame. */ template -class MagPoseFactor: public NoiseModelFactorN { +class MagPoseFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: using This = MagPoseFactor; diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 50c1885105..3818758084 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -56,7 +56,8 @@ namespace gtsam { * MultiplyFunctor(multiplier)); */ template -class FunctorizedFactor : public NoiseModelFactorN { +class FunctorizedFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: using Base = NoiseModelFactorN; @@ -157,7 +158,8 @@ FunctorizedFactor MakeFunctorizedFactor(Key key, const R &z, * @param T2: The second argument type for the functor. */ template -class FunctorizedFactor2 : public NoiseModelFactorN { +class FunctorizedFactor2 : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: using Base = NoiseModelFactorN; diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index b7cd655521..0ad311ac58 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -42,7 +42,8 @@ namespace gtsam { * \nosubgrouping */ template -class NonlinearEquality: public NoiseModelFactorN { +class NonlinearEquality: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef VALUE T; @@ -204,7 +205,8 @@ struct traits> : Testable> {}; * Simple unary equality constraint - fixes a value for a variable */ template -class NonlinearEquality1: public NoiseModelFactorN { +class NonlinearEquality1: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef VALUE X; @@ -292,7 +294,8 @@ struct traits > * be the same. */ template -class NonlinearEquality2 : public NoiseModelFactorN { +class NonlinearEquality2 : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactorN; diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 0c090a87db..acd674c731 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -599,15 +599,15 @@ class NoiseModelFactorN : public NoiseModelFactor { * DEFINITIONS. DO NOT USE THESE FOR NEW CODE * ******************************************************************************/ -/** Convenience macros to add deprecated typedefs `X1`, `X2`, ..., `X6`. +/** Convenience base class to add deprecated typedefs `X1`, `X2`, ..., `X6`. * This was only used to maintain backwards compatibility of existing factors! * Do NOT use for new factors! - * When transitioning from NoiseModelFactor1 to NoiseModelFactorN, this macro + * When transitioning from NoiseModelFactor1 to NoiseModelFactorN, this struct * was used to add deprecated typedefs for the old NoiseModelFactor1. * Usage example: * ``` - * class MyFactor : public NoiseModelFactorN { - * ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MyFactor, 2); + * class MyFactor : public NoiseModelFactorN, + * public DeprecatedFactorAliases { * // class implementation ... * }; * @@ -615,29 +615,48 @@ class NoiseModelFactorN : public NoiseModelFactor { * // MyFactor::X2 == Point3 * ``` */ -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<1> X; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1_(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<1> X1; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS2(CLASS) \ - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS1_(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<2> X2; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS3(CLASS) \ - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS2(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<3> X3; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS4(CLASS) \ - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS3(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<4> X4; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS5(CLASS) \ - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS4(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<5> X5; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS6(CLASS) \ - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS5(CLASS) \ - typedef GTSAM_DEPRECATED typename CLASS::template ValueType<6> X6; -#define ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(CLASS, N) \ - public: \ - ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS##N(CLASS); \ - private: +template +struct DeprecatedFactorAliases {}; +template +struct DeprecatedFactorAliases { + typedef GTSAM_DEPRECATED T1 X; +}; +template +struct DeprecatedFactorAliases { + typedef GTSAM_DEPRECATED T1 X1; + typedef GTSAM_DEPRECATED T2 X2; +}; +template +struct DeprecatedFactorAliases { + typedef GTSAM_DEPRECATED T1 X1; + typedef GTSAM_DEPRECATED T2 X2; + typedef GTSAM_DEPRECATED T3 X3; +}; +template +struct DeprecatedFactorAliases { + typedef GTSAM_DEPRECATED T1 X1; + typedef GTSAM_DEPRECATED T2 X2; + typedef GTSAM_DEPRECATED T3 X3; + typedef GTSAM_DEPRECATED T4 X4; +}; +template +struct DeprecatedFactorAliases { + typedef GTSAM_DEPRECATED T1 X1; + typedef GTSAM_DEPRECATED T2 X2; + typedef GTSAM_DEPRECATED T3 X3; + typedef GTSAM_DEPRECATED T4 X4; + typedef GTSAM_DEPRECATED T5 X5; +}; +template +struct DeprecatedFactorAliases { + typedef GTSAM_DEPRECATED T1 X1; + typedef GTSAM_DEPRECATED T2 X2; + typedef GTSAM_DEPRECATED T3 X3; + typedef GTSAM_DEPRECATED T4 X4; + typedef GTSAM_DEPRECATED T5 X5; + typedef GTSAM_DEPRECATED T6 X6; +}; /* ************************************************************************* */ /** @deprecated: use NoiseModelFactorN, replacing .key() with .key<1>() and X1 @@ -653,16 +672,9 @@ CLANG_DIAGNOSTIC_PUSH_IGNORE("-Wdeprecated-declarations") // Silence warnings GCC_DIAGNOSTIC_PUSH_IGNORE("-Wdeprecated-declarations") // while we define MSVC_DIAGNOSTIC_PUSH_IGNORE(4996) // deprecated classes template -class GTSAM_DEPRECATED NoiseModelFactor1 : public NoiseModelFactorN { - public: - /** Aliases for value types pulled from keys, for backwards compatibility. - * Note: in your code you can probably just do: - * `using X = ValueType<1>;` - * but this class is uglier due to dependent types. - * See e.g. testNonlinearFactor.cpp:TestFactorN. - */ - using X = typename NoiseModelFactor1::template ValueType<1>; - +class GTSAM_DEPRECATED NoiseModelFactor1 + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactor; // grandparent, for backwards compatibility using This = NoiseModelFactor1; @@ -694,17 +706,8 @@ class GTSAM_DEPRECATED NoiseModelFactor1 : public NoiseModelFactorN { */ template class GTSAM_DEPRECATED NoiseModelFactor2 - : public NoiseModelFactorN { - public: - /** Aliases for value types pulled from keys. - * Note: in your code you can probably just do: - * `using X1 = ValueType<1>;` - * but this class is uglier due to dependent types. - * See e.g. testNonlinearFactor.cpp:TestFactorN. - */ - using X1 = typename NoiseModelFactor2::template ValueType<1>; - using X2 = typename NoiseModelFactor2::template ValueType<2>; - + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactor; using This = NoiseModelFactor2; @@ -736,18 +739,8 @@ class GTSAM_DEPRECATED NoiseModelFactor2 */ template class GTSAM_DEPRECATED NoiseModelFactor3 - : public NoiseModelFactorN { - public: - /** Aliases for value types pulled from keys. - * Note: in your code you can probably just do: - * `using X1 = ValueType<1>;` - * but this class is uglier due to dependent types. - * See e.g. testNonlinearFactor.cpp:TestFactorN. - */ - using X1 = typename NoiseModelFactor3::template ValueType<1>; - using X2 = typename NoiseModelFactor3::template ValueType<2>; - using X3 = typename NoiseModelFactor3::template ValueType<3>; - + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactor; using This = NoiseModelFactor3; @@ -779,19 +772,8 @@ class GTSAM_DEPRECATED NoiseModelFactor3 */ template class GTSAM_DEPRECATED NoiseModelFactor4 - : public NoiseModelFactorN { - public: - /** Aliases for value types pulled from keys. - * Note: in your code you can probably just do: - * `using X1 = ValueType<1>;` - * but this class is uglier due to dependent types. - * See e.g. testNonlinearFactor.cpp:TestFactorN. - */ - using X1 = typename NoiseModelFactor4::template ValueType<1>; - using X2 = typename NoiseModelFactor4::template ValueType<2>; - using X3 = typename NoiseModelFactor4::template ValueType<3>; - using X4 = typename NoiseModelFactor4::template ValueType<4>; - + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactor; using This = NoiseModelFactor4; @@ -823,20 +805,8 @@ class GTSAM_DEPRECATED NoiseModelFactor4 */ template class GTSAM_DEPRECATED NoiseModelFactor5 - : public NoiseModelFactorN { - public: - /** Aliases for value types pulled from keys. - * Note: in your code you can probably just do: - * `using X1 = ValueType<1>;` - * but this class is uglier due to dependent types. - * See e.g. testNonlinearFactor.cpp:TestFactorN. - */ - using X1 = typename NoiseModelFactor5::template ValueType<1>; - using X2 = typename NoiseModelFactor5::template ValueType<2>; - using X3 = typename NoiseModelFactor5::template ValueType<3>; - using X4 = typename NoiseModelFactor5::template ValueType<4>; - using X5 = typename NoiseModelFactor5::template ValueType<5>; - + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactor; using This = NoiseModelFactor5; @@ -870,21 +840,9 @@ class GTSAM_DEPRECATED NoiseModelFactor5 template class GTSAM_DEPRECATED NoiseModelFactor6 - : public NoiseModelFactorN { - public: - /** Aliases for value types pulled from keys. - * Note: in your code you can probably just do: - * `using X1 = ValueType<1>;` - * but this class is uglier due to dependent types. - * See e.g. testNonlinearFactor.cpp:TestFactorN. - */ - using X1 = typename NoiseModelFactor6::template ValueType<1>; - using X2 = typename NoiseModelFactor6::template ValueType<2>; - using X3 = typename NoiseModelFactor6::template ValueType<3>; - using X4 = typename NoiseModelFactor6::template ValueType<4>; - using X5 = typename NoiseModelFactor6::template ValueType<5>; - using X6 = typename NoiseModelFactor6::template ValueType<6>; - + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: using Base = NoiseModelFactor; using This = @@ -905,6 +863,7 @@ class GTSAM_DEPRECATED NoiseModelFactor6 "NoiseModelFactor", boost::serialization::base_object(*this)); } }; // \class NoiseModelFactor6 -DIAGNOSTIC_POP() // Finish silencing warnings + +DIAGNOSTIC_POP() // Finish silencing warnings } // \namespace gtsam diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index d81ffbd319..5cf0606e90 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -27,7 +27,8 @@ namespace gtsam { * @ingroup nonlinear */ template - class PriorFactor: public NoiseModelFactorN { + class PriorFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef VALUE T; diff --git a/gtsam/sfm/ShonanFactor.h b/gtsam/sfm/ShonanFactor.h index e0411c8ff5..405635a773 100644 --- a/gtsam/sfm/ShonanFactor.h +++ b/gtsam/sfm/ShonanFactor.h @@ -33,7 +33,8 @@ namespace gtsam { * the SO(p) matrices down to a Stiefel manifold of p*d matrices. */ template -class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN { +class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { Matrix M_; ///< measured rotation between R1 and R2 size_t p_, pp_; ///< dimensionality constants diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index e87a1159a6..dab8ba72de 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -39,7 +39,8 @@ namespace gtsam { * * */ -class TranslationFactor : public NoiseModelFactorN { +class TranslationFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: typedef NoiseModelFactorN Base; diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index f2b41e0a1c..12a1a1d3a4 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -37,7 +37,8 @@ namespace gtsam { * @ingroup slam */ template - class BetweenFactor: public NoiseModelFactorN { + class BetweenFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { // Check that VALUE type is a testable Lie group BOOST_CONCEPT_ASSERT((IsTestable)); diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 79890ec944..7b0b039021 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -30,7 +30,8 @@ namespace gtsam { * @ingroup slam */ template -struct BoundingConstraint1: public NoiseModelFactorN { +struct BoundingConstraint1: public NoiseModelFactorN, + public DeprecatedFactorAliases { typedef VALUE X; typedef NoiseModelFactorN Base; typedef boost::shared_ptr > shared_ptr; @@ -98,7 +99,8 @@ struct BoundingConstraint1: public NoiseModelFactorN { * to implement for specific systems */ template -struct BoundingConstraint2: public NoiseModelFactorN { +struct BoundingConstraint2: public NoiseModelFactorN, + public DeprecatedFactorAliases { typedef VALUE1 X1; typedef VALUE2 X2; diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 9d84dfa7be..c32ff67329 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -27,7 +27,8 @@ namespace gtsam { * Binary factor between two Pose3 variables induced by an EssentialMatrix measurement * @ingroup slam */ -class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactorN { +class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 0d02ef681b..9a834a38e0 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -31,7 +31,8 @@ namespace gtsam { /** * Factor that evaluates epipolar error p'Ep for given essential matrix */ -class EssentialMatrixFactor : public NoiseModelFactorN { +class EssentialMatrixFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { Vector3 vA_, vB_; ///< Homogeneous versions, in ideal coordinates @@ -107,7 +108,8 @@ class EssentialMatrixFactor : public NoiseModelFactorN { * in image 2 is perfect, and returns re-projection error in image 1 */ class EssentialMatrixFactor2 - : public NoiseModelFactorN { + : public NoiseModelFactorN, + public DeprecatedFactorAliases { Point3 dP1_; ///< 3D point corresponding to measurement in image 1 Point2 pn_; ///< Measurement in image 2, in ideal coordinates @@ -323,7 +325,8 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 { */ template class EssentialMatrixFactor4 - : public NoiseModelFactorN { + : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: Point2 pA_, pB_; ///< points in pixel coordinates diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index dcb8d96f9f..552a5fc133 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -48,7 +48,8 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n, * element of SO(3) or SO(4). */ template -class FrobeniusPrior : public NoiseModelFactorN { +class FrobeniusPrior : public NoiseModelFactorN, + public DeprecatedFactorAliases { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; using MatrixNN = typename Rot::MatrixNN; @@ -76,7 +77,8 @@ class FrobeniusPrior : public NoiseModelFactorN { * The template argument can be any fixed-size SO. */ template -class FrobeniusFactor : public NoiseModelFactorN { +class FrobeniusFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; @@ -103,7 +105,8 @@ class FrobeniusFactor : public NoiseModelFactorN { * and in fact only SO3 and SO4 really work, as we need SO::AdjointMap. */ template -class FrobeniusBetweenFactor : public NoiseModelFactorN { +class FrobeniusBetweenFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { Rot R12_; ///< measured rotation between R1 and R2 Eigen::Matrix diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index f3089bd71f..e2b30adff2 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -57,7 +57,8 @@ namespace gtsam { * @ingroup slam */ template -class GeneralSFMFactor: public NoiseModelFactorN { +class GeneralSFMFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA) GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK) @@ -201,7 +202,8 @@ struct traits > : Testable< * Compared to GeneralSFMFactor, it is a ternary-factor because the calibration is isolated from camera.. */ template -class GeneralSFMFactor2: public NoiseModelFactorN { +class GeneralSFMFactor2: public NoiseModelFactorN, + public DeprecatedFactorAliases { GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) static const int DimK = FixedDimension::value; diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index 0ef9fd91bc..2c2ca57d37 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -15,7 +15,8 @@ namespace gtsam { /** * Factor to measure a planar landmark from a given pose */ -class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN { +class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: OrientedPlane3 measured_p_; @@ -50,7 +51,8 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN { +class GTSAM_EXPORT OrientedPlane3DirectionPrior : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: OrientedPlane3 measured_p_; /// measured plane parameters diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index aaa7e780af..fc622c2c3f 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -16,7 +16,8 @@ namespace gtsam { template -class PoseRotationPrior : public NoiseModelFactorN { +class PoseRotationPrior : public NoiseModelFactorN, + public DeprecatedFactorAliases { public: diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index 68c9f69cad..9823907a58 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -18,7 +18,8 @@ namespace gtsam { * A prior on the translation part of a pose */ template -class PoseTranslationPrior : public NoiseModelFactorN { +class PoseTranslationPrior : public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef PoseTranslationPrior This; diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 23b6d3dad4..bcfaad6680 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -37,7 +37,8 @@ namespace gtsam { */ template - class GenericProjectionFactor: public NoiseModelFactorN { + class GenericProjectionFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index 31f3c3c923..5dd12d94d5 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -54,7 +54,8 @@ P transform_point( * specific classes of landmarks */ template -class ReferenceFrameFactor : public NoiseModelFactorN { +class ReferenceFrameFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: /** default constructor for serialization only */ diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index af44de5a5b..f0ee85f72b 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -20,7 +20,8 @@ namespace gtsam { * with z and p measured and predicted angular velocities, and hence * p = iRc * z */ -class RotateFactor: public NoiseModelFactorN { +class RotateFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(RotateFactor, 1); Point3 p_, z_; ///< Predicted and measured directions, p = iRc * z @@ -65,7 +66,8 @@ class RotateFactor: public NoiseModelFactorN { * Factor on unknown rotation iRc that relates two directions c * Directions provide less constraints than a full rotation */ -class RotateDirectionsFactor: public NoiseModelFactorN { +class RotateDirectionsFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(RotateDirectionsFactor, 1); Unit3 i_p_, c_z_; ///< Predicted and measured directions, i_p = iRc * c_z diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index c3a28a0b18..55ae387843 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -28,7 +28,8 @@ namespace gtsam { * @ingroup slam */ template -class GenericStereoFactor: public NoiseModelFactorN { +class GenericStereoFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index f33ba2ca22..2085871a10 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -30,7 +30,8 @@ namespace gtsam { * @ingroup slam */ template -class TriangulationFactor: public NoiseModelFactorN { +class TriangulationFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index de5683c9ee..d7bcee61e4 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -22,7 +22,8 @@ namespace gtsam { * assumed to be PoseRTV */ template -class FullIMUFactor : public NoiseModelFactorN { +class FullIMUFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef NoiseModelFactorN Base; diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 23268d966e..068b19d1c7 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -20,7 +20,8 @@ namespace gtsam { * assumed to be PoseRTV */ template -class IMUFactor : public NoiseModelFactorN { +class IMUFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef NoiseModelFactorN Base; diff --git a/gtsam_unstable/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index 27aa604ca5..1ea9cc4729 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -20,7 +20,8 @@ namespace gtsam { * - For implicit Euler method: q_{k+1} = q_k + h*v_{k+1} * - For sympletic Euler method: q_{k+1} = q_k + h*v_{k+1} */ -class PendulumFactor1: public NoiseModelFactorN { +class PendulumFactor1: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: @@ -67,7 +68,8 @@ class PendulumFactor1: public NoiseModelFactorN { * - For implicit Euler method: v_{k+1} = v_k - h*g/L*sin(q_{k+1}) * - For sympletic Euler method: v_{k+1} = v_k - h*g/L*sin(q_k) */ -class PendulumFactor2: public NoiseModelFactorN { +class PendulumFactor2: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: @@ -115,7 +117,8 @@ class PendulumFactor2: public NoiseModelFactorN { * \f$ p_k = -D_1 L_d(q_k,q_{k+1},h) = \frac{1}{h}mr^{2}\left(q_{k+1}-q_{k}\right)+mgrh(1-\alpha)\,\sin\left((1-\alpha)q_{k}+\alpha q_{k+1}\right) \f$ * \f$ = (1/h)mr^2 (q_{k+1}-q_k) + mgrh(1-alpha) sin ((1-alpha)q_k+\alpha q_{k+1}) \f$ */ -class PendulumFactorPk: public NoiseModelFactorN { +class PendulumFactorPk: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: @@ -172,7 +175,8 @@ class PendulumFactorPk: public NoiseModelFactorN { * \f$ p_k1 = D_2 L_d(q_k,q_{k+1},h) = \frac{1}{h}mr^{2}\left(q_{k+1}-q_{k}\right)-mgrh\alpha\sin\left((1-\alpha)q_{k}+\alpha q_{k+1}\right) \f$ * \f$ = (1/h)mr^2 (q_{k+1}-q_k) - mgrh alpha sin ((1-alpha)q_k+\alpha q_{k+1}) \f$ */ -class PendulumFactorPk1: public NoiseModelFactorN { +class PendulumFactorPk1: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 941b7c7acc..42721576ba 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -24,7 +24,8 @@ namespace gtsam { * Note: this factor is necessary if one needs to smooth the entire graph. It's not needed * in sequential update method. */ -class Reconstruction : public NoiseModelFactorN { +class Reconstruction : public NoiseModelFactorN, + public DeprecatedFactorAliases { double h_; // time step typedef NoiseModelFactorN Base; @@ -73,7 +74,8 @@ class Reconstruction : public NoiseModelFactorN { /** * Implement the Discrete Euler-Poincare' equation: */ -class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN { +class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN, + public DeprecatedFactorAliases { double h_; /// time step Matrix Inertia_; /// Inertia tensors Inertia = [ J 0; 0 M ] diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index 417837835c..928cae7cb5 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -10,7 +10,8 @@ namespace gtsam { -class VelocityConstraint3 : public NoiseModelFactorN { +class VelocityConstraint3 : public NoiseModelFactorN, + public DeprecatedFactorAliases { public: diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index 6f0aa605b8..29bef3939c 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -27,7 +27,8 @@ namespace gtsam { * common-mode errors and that can be partially corrected if other sensors are used * @ingroup slam */ - class BiasedGPSFactor: public NoiseModelFactorN { + class BiasedGPSFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index 43001fbc2a..3765e0c1ca 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -88,7 +88,8 @@ namespace gtsam { */ template -class EquivInertialNavFactor_GlobalVel : public NoiseModelFactorN { +class EquivInertialNavFactor_GlobalVel : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 6423fabda3..4972f9bc91 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -87,7 +87,8 @@ namespace gtsam { */ template -class EquivInertialNavFactor_GlobalVel_NoBias : public NoiseModelFactorN { +class EquivInertialNavFactor_GlobalVel_NoBias : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index c3682e536d..ee85c1e119 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -42,7 +42,8 @@ namespace gtsam { * T is the measurement type, by default the same */ template -class GaussMarkov1stOrderFactor: public NoiseModelFactorN { +class GaussMarkov1stOrderFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index efaf71d229..329a1cbc56 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -77,7 +77,8 @@ namespace gtsam { * vehicle */ template -class InertialNavFactor_GlobalVelocity : public NoiseModelFactorN { +class InertialNavFactor_GlobalVelocity : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 8ba1ca79ac..e8707071c2 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -24,7 +24,8 @@ namespace gtsam { * Ternary factor representing a visual measurement that includes inverse depth */ template -class InvDepthFactor3: public NoiseModelFactorN { +class InvDepthFactor3: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index b64c13778a..4faf3fa923 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -24,7 +24,8 @@ namespace gtsam { /** * Binary factor representing a visual measurement using an inverse-depth parameterization */ -class InvDepthFactorVariant1: public NoiseModelFactorN { +class InvDepthFactorVariant1: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index 8ae69ea298..fa13b83d3c 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -25,7 +25,8 @@ namespace gtsam { /** * Binary factor representing a visual measurement using an inverse-depth parameterization */ -class InvDepthFactorVariant2: public NoiseModelFactorN { +class InvDepthFactorVariant2: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index 835c5ecf5b..53e650777f 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -24,7 +24,8 @@ namespace gtsam { /** * Binary factor representing the first visual measurement using an inverse-depth parameterization */ -class InvDepthFactorVariant3a: public NoiseModelFactorN { +class InvDepthFactorVariant3a: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: @@ -151,7 +152,8 @@ class InvDepthFactorVariant3a: public NoiseModelFactorN { /** * Ternary factor representing a visual measurement using an inverse-depth parameterization */ -class InvDepthFactorVariant3b: public NoiseModelFactorN { +class InvDepthFactorVariant3b: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index 97195ae11b..a6fee20701 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h @@ -35,7 +35,8 @@ namespace gtsam { * optimized in x1 frame in the optimization. */ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor - : public NoiseModelFactorN { + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: OrientedPlane3 measured_p_; diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index b49b491314..16045b106e 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -35,7 +35,8 @@ namespace gtsam { * @tparam VALUE is the type of variable the prior effects */ template - class PartialPriorFactor: public NoiseModelFactorN { + class PartialPriorFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef VALUE T; diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index 676e011de2..10ab7e07ea 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -29,7 +29,8 @@ namespace gtsam { * @ingroup slam */ template - class PoseBetweenFactor: public NoiseModelFactorN { + class PoseBetweenFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index c7a094bda3..bf5ae37b5a 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -26,7 +26,8 @@ namespace gtsam { * @ingroup slam */ template - class PosePriorFactor: public NoiseModelFactorN { + class PosePriorFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index bea8be85ed..4dff6dc6ec 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -21,7 +21,8 @@ namespace gtsam { * @ingroup slam */ template -class PoseToPointFactor : public NoiseModelFactorN { +class PoseToPointFactor : public NoiseModelFactorN, + public DeprecatedFactorAliases { private: typedef PoseToPointFactor This; diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index b056e7f387..8c83dd0b4e 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -31,7 +31,8 @@ namespace gtsam { * @ingroup slam */ template - class ProjectionFactorPPP: public NoiseModelFactorN { + class ProjectionFactorPPP: public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index 2de3110e06..dcb621804a 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -34,7 +34,8 @@ namespace gtsam { */ template class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC - : public NoiseModelFactorN { + : public NoiseModelFactorN, + public DeprecatedFactorAliases { protected: Point2 measured_; ///< 2D measurement diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 4ebcd771f8..6e01eb3f4d 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -42,7 +42,8 @@ namespace gtsam { */ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter - : public NoiseModelFactorN { + : public NoiseModelFactorN, + public DeprecatedFactorAliases { 3); protected: diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index 851ecaadc5..588be082e7 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -25,7 +25,8 @@ namespace gtsam { * * TODO: enable use of a Pose3 for the target as well */ -class GTSAM_UNSTABLE_EXPORT RelativeElevationFactor: public NoiseModelFactorN { +class GTSAM_UNSTABLE_EXPORT RelativeElevationFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { private: diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index 2e024c5bbe..ef435c956b 100644 --- a/gtsam_unstable/slam/TSAMFactors.h +++ b/gtsam_unstable/slam/TSAMFactors.h @@ -26,7 +26,8 @@ namespace gtsam { /** * DeltaFactor: relative 2D measurement between Pose2 and Point2 */ -class DeltaFactor: public NoiseModelFactorN { +class DeltaFactor: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef DeltaFactor This; @@ -55,7 +56,8 @@ class DeltaFactor: public NoiseModelFactorN { /** * DeltaFactorBase: relative 2D measurement between Pose2 and Point2, with Basenodes */ -class DeltaFactorBase: public NoiseModelFactorN { +class DeltaFactorBase: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef DeltaFactorBase This; @@ -110,7 +112,8 @@ class DeltaFactorBase: public NoiseModelFactorN { /** * OdometryFactorBase: Pose2 odometry, with Basenodes */ -class OdometryFactorBase: public NoiseModelFactorN { +class OdometryFactorBase: public NoiseModelFactorN, + public DeprecatedFactorAliases { public: typedef OdometryFactorBase This; From cf6f2d6ea0a66252aa3643877b75892b79c45b62 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 4 Jan 2023 23:14:51 -0500 Subject: [PATCH 8/8] fix typo --- gtsam_unstable/slam/ProjectionFactorRollingShutter.h | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 6e01eb3f4d..441d045304 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -44,7 +44,6 @@ namespace gtsam { class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter : public NoiseModelFactorN, public DeprecatedFactorAliases { - 3); protected: // Keep a copy of measurement and calibration for I/O