compiler directives

release/4.3a0
Frank Dellaert 2015-12-27 18:41:50 -08:00
parent 2578a7098f
commit 05df0ca0cc
6 changed files with 21 additions and 5 deletions

View File

@ -238,6 +238,7 @@ Vector CombinedImuFactor::evaluateError(const Pose3& pose_i,
}
//------------------------------------------------------------------------------
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
CombinedImuFactor::CombinedImuFactor(
Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j,
const CombinedPreintegratedMeasurements& pim, const Vector3& n_gravity,
@ -254,7 +255,7 @@ CombinedImuFactor::CombinedImuFactor(
p->use2ndOrderCoriolis = use2ndOrderCoriolis;
_PIM_.p_ = p;
}
//------------------------------------------------------------------------------
void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
Pose3& pose_j, Vector3& vel_j,
const imuBias::ConstantBias& bias_i,
@ -268,6 +269,7 @@ void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
pose_j = pvb.pose;
vel_j = pvb.velocity;
}
#endif
} /// namespace gtsam

View File

@ -281,6 +281,7 @@ public:
/// @deprecated typename
typedef gtsam::PreintegratedCombinedMeasurements CombinedPreintegratedMeasurements;
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
/// @deprecated constructor
CombinedImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i,
Key bias_j, const CombinedPreintegratedMeasurements& pim,
@ -294,6 +295,7 @@ public:
CombinedPreintegratedMeasurements& pim,
const Vector3& n_gravity, const Vector3& omegaCoriolis,
const bool use2ndOrderCoriolis = false);
#endif
private:

View File

@ -85,6 +85,7 @@ void PreintegratedImuMeasurements::integrateMeasurement(
}
//------------------------------------------------------------------------------
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
PreintegratedImuMeasurements::PreintegratedImuMeasurements(
const imuBias::ConstantBias& biasHat, const Matrix3& measuredAccCovariance,
const Matrix3& measuredOmegaCovariance,
@ -100,7 +101,6 @@ PreintegratedImuMeasurements::PreintegratedImuMeasurements(
resetIntegration();
}
//------------------------------------------------------------------------------
void PreintegratedImuMeasurements::integrateMeasurement(
const Vector3& measuredAcc, const Vector3& measuredOmega, double deltaT,
boost::optional<Pose3> body_P_sensor) {
@ -108,6 +108,7 @@ void PreintegratedImuMeasurements::integrateMeasurement(
p_->body_P_sensor = body_P_sensor;
integrateMeasurement(measuredAcc, measuredOmega, deltaT);
}
#endif
//------------------------------------------------------------------------------
// ImuFactor methods
@ -171,6 +172,7 @@ ImuFactor::ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
}
//------------------------------------------------------------------------------
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
void ImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
Pose3& pose_j, Vector3& vel_j, const imuBias::ConstantBias& bias_i,
PreintegratedMeasurements& pim, const Vector3& n_gravity,
@ -181,5 +183,5 @@ void ImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
pose_j = pvb.pose;
vel_j = pvb.velocity;
}
#endif
} // namespace gtsam

View File

@ -118,6 +118,7 @@ public:
/// Return pre-integrated measurement covariance
Matrix preintMeasCov() const { return preintMeasCov_; }
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
/// @deprecated constructor
/// NOTE(frank): assumes Z-Down convention, only second order integration supported
PreintegratedImuMeasurements(const imuBias::ConstantBias& biasHat,
@ -131,6 +132,7 @@ public:
void integrateMeasurement(const Vector3& measuredAcc,
const Vector3& measuredOmega, double dt,
boost::optional<Pose3> body_P_sensor);
#endif
private:

View File

@ -295,6 +295,7 @@ Vector9 PreintegrationBase::computeErrorAndJacobians(const Pose3& pose_i,
}
//------------------------------------------------------------------------------
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
PoseVelocityBias PreintegrationBase::predict(const Pose3& pose_i,
const Vector3& vel_i, const imuBias::ConstantBias& bias_i,
const Vector3& n_gravity, const Vector3& omegaCoriolis,
@ -307,7 +308,7 @@ PoseVelocityBias PreintegrationBase::predict(const Pose3& pose_i,
p_ = q;
return PoseVelocityBias(predict(NavState(pose_i, vel_i), bias_i), bias_i);
}
#endif
//------------------------------------------------------------------------------
}/// namespace gtsam

View File

@ -28,6 +28,7 @@
namespace gtsam {
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
/// @deprecated
struct PoseVelocityBias {
Pose3 pose;
@ -44,6 +45,7 @@ struct PoseVelocityBias {
return NavState(pose, velocity);
}
};
#endif
/**
* PreintegrationBase is the base class for PreintegratedMeasurements
@ -101,7 +103,10 @@ public:
protected:
/// Parameters. Declared mutable only for deprecated predict method.
mutable boost::shared_ptr<Params> p_;
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
mutable
#endif
boost::shared_ptr<Params> p_;
/// Acceleration and gyro bias used for preintegration
imuBias::ConstantBias biasHat_;
@ -277,6 +282,7 @@ public:
/// @}
#ifdef ALLOW_DEPRECATED_IN_GTSAM4
/// @name Deprecated
/// @{
@ -286,6 +292,7 @@ public:
const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false) const;
/// @}
#endif
private:
/** Serialization function */