Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add deprecated aliases for X1 = ValueType<1>, ... #1350

Closed
wants to merge 8 commits into from
3 changes: 2 additions & 1 deletion gtsam/navigation/AHRSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,8 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
}
};

class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {
class GTSAM_EXPORT AHRSFactor : public NoiseModelFactorN<Rot3, Rot3, Vector3> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(AHRSFactor, 3);

typedef AHRSFactor This;
typedef NoiseModelFactorN<Rot3, Rot3, Vector3> Base;
Expand Down
4 changes: 3 additions & 1 deletion gtsam/navigation/AttitudeFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,8 @@ class AttitudeFactor {
* Version of AttitudeFactor for Rot3
* @ingroup navigation
*/
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN<Rot3>, public AttitudeFactor {
class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN<Rot3>, public AttitudeFactor {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Rot3AttitudeFactor, 1);

typedef NoiseModelFactorN<Rot3> Base;

Expand Down Expand Up @@ -152,6 +153,7 @@ template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFacto
*/
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,
public AttitudeFactor {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(Pose3AttitudeFactor, 1);

typedef NoiseModelFactorN<Pose3> Base;

Expand Down
2 changes: 2 additions & 0 deletions gtsam/navigation/BarometricFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ namespace gtsam {
* @ingroup navigation
*/
class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BarometricFactor, 2);

private:
typedef NoiseModelFactorN<Pose3, double> Base;

Expand Down
2 changes: 1 addition & 1 deletion gtsam/navigation/CombinedImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -257,7 +257,7 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType
*/
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3,
Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
public:
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(CombinedImuFactor, 6);

private:

Expand Down
2 changes: 2 additions & 0 deletions gtsam/navigation/ConstantVelocityFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ namespace gtsam {
* The only measurement is dt, the time delta between the states.
*/
class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ConstantVelocityFactor, 2);

double dt_;

public:
Expand Down
2 changes: 2 additions & 0 deletions gtsam/navigation/GPSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ namespace gtsam {
* @ingroup navigation
*/
class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN<Pose3> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GPSFactor, 1);

private:

Expand Down Expand Up @@ -112,6 +113,7 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN<Pose3> {
* @ingroup navigation
*/
class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN<NavState> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GPSFactor2, 1);

private:

Expand Down
4 changes: 4 additions & 0 deletions gtsam/navigation/ImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,8 @@ class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
*/
class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ImuFactor, 5);

private:

typedef ImuFactor This;
Expand Down Expand Up @@ -261,6 +263,8 @@ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3, Ve
* @ingroup navigation
*/
class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactorN<NavState, NavState, imuBias::ConstantBias> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(ImuFactor2, 3);

private:

typedef ImuFactor2 This;
Expand Down
4 changes: 4 additions & 0 deletions gtsam/navigation/MagFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ namespace gtsam {
* Rotation is around negative Z axis, i.e. positive is yaw to right!
*/
class MagFactor: public NoiseModelFactorN<Rot2> {
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)
Expand Down Expand Up @@ -88,6 +89,7 @@ class MagFactor: public NoiseModelFactorN<Rot2> {
* and assumes scale, direction, and the bias are given
*/
class MagFactor1: public NoiseModelFactorN<Rot3> {
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)
Expand Down Expand Up @@ -126,6 +128,7 @@ class MagFactor1: public NoiseModelFactorN<Rot3> {
* and optimizes for both nM and the bias, where nM is in units defined by magnetometer
*/
class MagFactor2: public NoiseModelFactorN<Point3, Point3> {
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
Expand Down Expand Up @@ -167,6 +170,7 @@ class MagFactor2: public NoiseModelFactorN<Point3, Point3> {
* and optimizes for both scale, direction, and the bias.
*/
class MagFactor3: public NoiseModelFactorN<double, Unit3, Point3> {
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
Expand Down
2 changes: 2 additions & 0 deletions gtsam/navigation/MagPoseFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ namespace gtsam {
*/
template <class POSE>
class MagPoseFactor: public NoiseModelFactorN<POSE> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(MagPoseFactor, 1);

private:
using This = MagPoseFactor<POSE>;
using Base = NoiseModelFactorN<POSE>;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/nonlinear/ExtendedKalmanFilter.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<VALUE, VALUE> MotionFactor;
typedef NoiseModelFactorN<VALUE> MeasurementFactor;
typedef NoiseModelFactor2<VALUE, VALUE> MotionFactor;
typedef NoiseModelFactor1<VALUE> MeasurementFactor;
#endif

protected:
Expand Down
4 changes: 4 additions & 0 deletions gtsam/nonlinear/FunctorizedFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ namespace gtsam {
*/
template <typename R, typename T>
class FunctorizedFactor : public NoiseModelFactorN<T> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FunctorizedFactor, 1);

private:
using Base = NoiseModelFactorN<T>;

Expand Down Expand Up @@ -157,6 +159,8 @@ FunctorizedFactor<R, T> MakeFunctorizedFactor(Key key, const R &z,
*/
template <typename R, typename T1, typename T2>
class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FunctorizedFactor2, 2);

private:
using Base = NoiseModelFactorN<T1, T2>;

Expand Down
3 changes: 3 additions & 0 deletions gtsam/nonlinear/NonlinearEquality.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ namespace gtsam {
*/
template<class VALUE>
class NonlinearEquality: public NoiseModelFactorN<VALUE> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(NonlinearEquality, 1);

public:
typedef VALUE T;
Expand Down Expand Up @@ -293,6 +294,8 @@ struct traits<NonlinearEquality1<VALUE> >
*/
template <class T>
class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(NonlinearEquality2, 2);

protected:
using Base = NoiseModelFactorN<T, T>;
using This = NonlinearEquality2<T>;
Expand Down
49 changes: 49 additions & 0 deletions gtsam/nonlinear/NonlinearFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<Pose3, Point3> {
* 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>.
Expand All @@ -604,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 VALUE>
class GTSAM_DEPRECATED NoiseModelFactor1 : public NoiseModelFactorN<VALUE> {
public:
Expand Down Expand Up @@ -857,5 +905,6 @@ class GTSAM_DEPRECATED NoiseModelFactor6
"NoiseModelFactor", boost::serialization::base_object<Base>(*this));
}
}; // \class NoiseModelFactor6
DIAGNOSTIC_POP() // Finish silencing warnings

} // \namespace gtsam
1 change: 1 addition & 0 deletions gtsam/nonlinear/PriorFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ namespace gtsam {
*/
template<class VALUE>
class PriorFactor: public NoiseModelFactorN<VALUE> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PriorFactor, 1);

public:
typedef VALUE T;
Expand Down
2 changes: 2 additions & 0 deletions gtsam/sfm/ShonanFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@ namespace gtsam {
*/
template <size_t d>
class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN<SOn, SOn> {
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<Matrix> G_; ///< matrix of vectorized generators
Expand Down
2 changes: 2 additions & 0 deletions gtsam/sfm/TranslationFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ namespace gtsam {
*
*/
class TranslationFactor : public NoiseModelFactorN<Point3, Point3> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(TranslationFactor, 2);

private:
typedef NoiseModelFactorN<Point3, Point3> Base;
Point3 measured_w_aZb_;
Expand Down
1 change: 1 addition & 0 deletions gtsam/slam/BetweenFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ namespace gtsam {
*/
template<class VALUE>
class BetweenFactor: public NoiseModelFactorN<VALUE, VALUE> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(BetweenFactor, 2);

// Check that VALUE type is a testable Lie group
BOOST_CONCEPT_ASSERT((IsTestable<VALUE>));
Expand Down
1 change: 1 addition & 0 deletions gtsam/slam/EssentialMatrixConstraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ namespace gtsam {
* @ingroup slam
*/
class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactorN<Pose3, Pose3> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixConstraint, 2);

private:

Expand Down
6 changes: 6 additions & 0 deletions gtsam/slam/EssentialMatrixFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ namespace gtsam {
* Factor that evaluates epipolar error p'Ep for given essential matrix
*/
class EssentialMatrixFactor : public NoiseModelFactorN<EssentialMatrix> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor, 1);

Vector3 vA_, vB_; ///< Homogeneous versions, in ideal coordinates

typedef NoiseModelFactorN<EssentialMatrix> Base;
Expand Down Expand Up @@ -107,6 +109,8 @@ class EssentialMatrixFactor : public NoiseModelFactorN<EssentialMatrix> {
*/
class EssentialMatrixFactor2
: public NoiseModelFactorN<EssentialMatrix, double> {
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
Expand Down Expand Up @@ -322,6 +326,8 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 {
template <class CALIBRATION>
class EssentialMatrixFactor4
: public NoiseModelFactorN<EssentialMatrix, CALIBRATION> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(EssentialMatrixFactor4, 2);

private:
Point2 pA_, pB_; ///< points in pixel coordinates

Expand Down
6 changes: 6 additions & 0 deletions gtsam/slam/FrobeniusFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n,
*/
template <class Rot>
class FrobeniusPrior : public NoiseModelFactorN<Rot> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusPrior, 1);

enum { Dim = Rot::VectorN2::RowsAtCompileTime };
using MatrixNN = typename Rot::MatrixNN;
Eigen::Matrix<double, Dim, 1> vecM_; ///< vectorized matrix to approximate
Expand Down Expand Up @@ -76,6 +78,8 @@ class FrobeniusPrior : public NoiseModelFactorN<Rot> {
*/
template <class Rot>
class FrobeniusFactor : public NoiseModelFactorN<Rot, Rot> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusFactor, 2);

enum { Dim = Rot::VectorN2::RowsAtCompileTime };

public:
Expand All @@ -102,6 +106,8 @@ class FrobeniusFactor : public NoiseModelFactorN<Rot, Rot> {
*/
template <class Rot>
class FrobeniusBetweenFactor : public NoiseModelFactorN<Rot, Rot> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(FrobeniusBetweenFactor, 2);

Rot R12_; ///< measured rotation between R1 and R2
Eigen::Matrix<double, Rot::dimension, Rot::dimension>
R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1
Expand Down
2 changes: 2 additions & 0 deletions gtsam/slam/GeneralSFMFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ namespace gtsam {
*/
template<class CAMERA, class LANDMARK>
class GeneralSFMFactor: public NoiseModelFactorN<CAMERA, LANDMARK> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GeneralSFMFactor, 2);

GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA)
GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK)
Expand Down Expand Up @@ -202,6 +203,7 @@ struct traits<GeneralSFMFactor<CAMERA, LANDMARK> > : Testable<
*/
template<class CALIBRATION>
class GeneralSFMFactor2: public NoiseModelFactorN<Pose3, Point3, CALIBRATION> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(GeneralSFMFactor2, 3);

GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION)
static const int DimK = FixedDimension<CALIBRATION>::value;
Expand Down
4 changes: 4 additions & 0 deletions gtsam/slam/OrientedPlane3Factor.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ namespace gtsam {
* Factor to measure a planar landmark from a given pose
*/
class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN<Pose3, OrientedPlane3> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OrientedPlane3Factor, 2);

protected:
OrientedPlane3 measured_p_;
typedef NoiseModelFactorN<Pose3, OrientedPlane3> Base;
Expand Down Expand Up @@ -50,6 +52,8 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN<Pose3, Oriente

// TODO: Convert this factor to dimension two, three dimensions is redundant for direction prior
class GTSAM_EXPORT OrientedPlane3DirectionPrior : public NoiseModelFactorN<OrientedPlane3> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(OrientedPlane3DirectionPrior, 1);

protected:
OrientedPlane3 measured_p_; /// measured plane parameters
typedef NoiseModelFactorN<OrientedPlane3> Base;
Expand Down
2 changes: 2 additions & 0 deletions gtsam/slam/PoseRotationPrior.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ namespace gtsam {

template<class POSE>
class PoseRotationPrior : public NoiseModelFactorN<POSE> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseRotationPrior, 1);

public:

typedef PoseRotationPrior<POSE> This;
Expand Down
2 changes: 2 additions & 0 deletions gtsam/slam/PoseTranslationPrior.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@ namespace gtsam {
*/
template<class POSE>
class PoseTranslationPrior : public NoiseModelFactorN<POSE> {
ADD_NOISE_MODEL_FACTOR_N_DEPRECATED_TYPEDEFS(PoseTranslationPrior, 1);

public:
typedef PoseTranslationPrior<POSE> This;
typedef NoiseModelFactorN<POSE> Base;
Expand Down
Loading