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
4 changes: 2 additions & 2 deletions doc/Code/LocalizationFactor.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
class UnaryFactor: public NoiseModelFactor1<Pose2> {
class UnaryFactor: public NoiseModelFactorN<Pose2> {
double mx_, my_; ///< X and Y measurements

public:
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}
NoiseModelFactorN<Pose2>(model, j), mx_(x), my_(y) {}

Vector evaluateError(const Pose2& q,
boost::optional<Matrix&> H = boost::none) const override {
Expand Down
5 changes: 3 additions & 2 deletions gtsam/navigation/AHRSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,8 +128,9 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
}
};

class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {

class GTSAM_EXPORT AHRSFactor
: public NoiseModelFactorN<Rot3, Rot3, Vector3>,
public DeprecatedFactorAliases<Rot3, Rot3, Vector3> {
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 DeprecatedFactorAliases<Rot3>, public AttitudeFactor {

typedef NoiseModelFactorN<Rot3> Base;

Expand Down Expand Up @@ -151,6 +152,7 @@ template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFacto
* @ingroup navigation
*/
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,
public DeprecatedFactorAliases<Pose3>,
public AttitudeFactor {

typedef NoiseModelFactorN<Pose3> Base;
Expand Down
5 changes: 4 additions & 1 deletion gtsam/navigation/BarometricFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,10 @@ namespace gtsam {
* https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html
* @ingroup navigation
*/
class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
class GTSAM_EXPORT BarometricFactor
: public NoiseModelFactorN<Pose3, double>,
public DeprecatedFactorAliases<Pose3, double> {

private:
typedef NoiseModelFactorN<Pose3, double> Base;

Expand Down
11 changes: 6 additions & 5 deletions gtsam/navigation/CombinedImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -255,11 +255,12 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType
*
* @ingroup navigation
*/
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3,
Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
public:

private:
class GTSAM_EXPORT CombinedImuFactor
: public NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias, imuBias::ConstantBias>,
public DeprecatedFactorAliases<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias, imuBias::ConstantBias> {
private:

typedef CombinedImuFactor This;
typedef NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
Expand Down
4 changes: 3 additions & 1 deletion gtsam/navigation/ConstantVelocityFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,9 @@ namespace gtsam {
* Binary factor for applying a constant velocity model to a moving body represented as a NavState.
* The only measurement is dt, the time delta between the states.
*/
class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState> {
class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState>,
public DeprecatedFactorAliases<NavState, NavState> {

double dt_;

public:
Expand Down
6 changes: 4 additions & 2 deletions gtsam/navigation/GPSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<Pose3> {
class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN<Pose3>,
public DeprecatedFactorAliases<Pose3> {

private:

Expand Down Expand Up @@ -111,7 +112,8 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN<Pose3> {
* Version of GPSFactor for NavState
* @ingroup navigation
*/
class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN<NavState> {
class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN<NavState>,
public DeprecatedFactorAliases<NavState> {

private:

Expand Down
7 changes: 6 additions & 1 deletion gtsam/navigation/ImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,10 @@ class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
* @ingroup navigation
*/
class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias>,
public DeprecatedFactorAliases<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias> {

private:

typedef ImuFactor This;
Expand Down Expand Up @@ -260,7 +263,9 @@ class GTSAM_EXPORT ImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3, Ve
* ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity.
* @ingroup navigation
*/
class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactorN<NavState, NavState, imuBias::ConstantBias> {
class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactorN<NavState, NavState, imuBias::ConstantBias>,
public DeprecatedFactorAliases<NavState, NavState, imuBias::ConstantBias> {

private:

typedef ImuFactor2 This;
Expand Down
12 changes: 8 additions & 4 deletions gtsam/navigation/MagFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<Rot2> {
class MagFactor: public NoiseModelFactorN<Rot2>,
public DeprecatedFactorAliases<Rot2> {

const Point3 measured_; ///< The measured magnetometer values
const Point3 nM_; ///< Local magnetic field (mag output units)
Expand Down Expand Up @@ -87,7 +88,8 @@ class MagFactor: public NoiseModelFactorN<Rot2> {
* This version uses model measured bM = scale * bRn * direction + bias
* and assumes scale, direction, and the bias are given
*/
class MagFactor1: public NoiseModelFactorN<Rot3> {
class MagFactor1: public NoiseModelFactorN<Rot3>,
public DeprecatedFactorAliases<Rot3> {

const Point3 measured_; ///< The measured magnetometer values
const Point3 nM_; ///< Local magnetic field (mag output units)
Expand Down Expand Up @@ -125,7 +127,8 @@ class MagFactor1: public NoiseModelFactorN<Rot3> {
* 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<Point3, Point3> {
class MagFactor2: public NoiseModelFactorN<Point3, Point3>,
public DeprecatedFactorAliases<Point3, Point3> {

const Point3 measured_; ///< The measured magnetometer values
const Rot3 bRn_; ///< The assumed known rotation from nav to body
Expand Down Expand Up @@ -166,7 +169,8 @@ class MagFactor2: public NoiseModelFactorN<Point3, Point3> {
* This version uses model measured bM = scale * bRn * direction + bias
* and optimizes for both scale, direction, and the bias.
*/
class MagFactor3: public NoiseModelFactorN<double, Unit3, Point3> {
class MagFactor3: public NoiseModelFactorN<double, Unit3, Point3>,
public DeprecatedFactorAliases<double, Unit3, Point3> {

const Point3 measured_; ///< The measured magnetometer values
const Rot3 bRn_; ///< The assumed known rotation from nav to body
Expand Down
4 changes: 3 additions & 1 deletion gtsam/navigation/MagPoseFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ namespace gtsam {
* expressed in the sensor frame.
*/
template <class POSE>
class MagPoseFactor: public NoiseModelFactorN<POSE> {
class MagPoseFactor: public NoiseModelFactorN<POSE>,
public DeprecatedFactorAliases<POSE> {

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
8 changes: 6 additions & 2 deletions gtsam/nonlinear/FunctorizedFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,9 @@ namespace gtsam {
* MultiplyFunctor(multiplier));
*/
template <typename R, typename T>
class FunctorizedFactor : public NoiseModelFactorN<T> {
class FunctorizedFactor : public NoiseModelFactorN<T>,
public DeprecatedFactorAliases<T> {

private:
using Base = NoiseModelFactorN<T>;

Expand Down Expand Up @@ -156,7 +158,9 @@ FunctorizedFactor<R, T> MakeFunctorizedFactor(Key key, const R &z,
* @param T2: The second argument type for the functor.
*/
template <typename R, typename T1, typename T2>
class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2>,
public DeprecatedFactorAliases<T1, T2> {

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

Expand Down
10 changes: 7 additions & 3 deletions gtsam/nonlinear/NonlinearEquality.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@ namespace gtsam {
* \nosubgrouping
*/
template<class VALUE>
class NonlinearEquality: public NoiseModelFactorN<VALUE> {
class NonlinearEquality: public NoiseModelFactorN<VALUE>,
public DeprecatedFactorAliases<VALUE> {

public:
typedef VALUE T;
Expand Down Expand Up @@ -204,7 +205,8 @@ struct traits<NonlinearEquality<VALUE>> : Testable<NonlinearEquality<VALUE>> {};
* Simple unary equality constraint - fixes a value for a variable
*/
template<class VALUE>
class NonlinearEquality1: public NoiseModelFactorN<VALUE> {
class NonlinearEquality1: public NoiseModelFactorN<VALUE>,
public DeprecatedFactorAliases<VALUE> {

public:
typedef VALUE X;
Expand Down Expand Up @@ -292,7 +294,9 @@ struct traits<NonlinearEquality1<VALUE> >
* be the same.
*/
template <class T>
class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
class NonlinearEquality2 : public NoiseModelFactorN<T, T>,
public DeprecatedFactorAliases<T, T> {

protected:
using Base = NoiseModelFactorN<T, T>;
using This = NonlinearEquality2<T>;
Expand Down
Loading