Simplified deprecated methods
parent
042d874f08
commit
7b02a01a44
|
|
@ -277,19 +277,13 @@ CombinedImuFactor::CombinedImuFactor(
|
||||||
void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
|
void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
|
||||||
Pose3& pose_j, Vector3& vel_j,
|
Pose3& pose_j, Vector3& vel_j,
|
||||||
const imuBias::ConstantBias& bias_i,
|
const imuBias::ConstantBias& bias_i,
|
||||||
const CombinedPreintegratedMeasurements& pim,
|
CombinedPreintegratedMeasurements& pim,
|
||||||
const Vector3& gravity,
|
const Vector3& gravity,
|
||||||
const Vector3& omegaCoriolis,
|
const Vector3& omegaCoriolis,
|
||||||
const bool use2ndOrderCoriolis) {
|
const bool use2ndOrderCoriolis) {
|
||||||
// NOTE(frank): hack below only for backward compatibility
|
// use deprecated predict
|
||||||
boost::shared_ptr<CombinedPreintegratedMeasurements::Params> p =
|
PoseVelocityBias pvb = pim.predict(pose_i, vel_i, bias_i, gravity,
|
||||||
boost::make_shared<CombinedPreintegratedMeasurements::Params>(pim.p());
|
omegaCoriolis, use2ndOrderCoriolis);
|
||||||
p->gravity = gravity;
|
|
||||||
p->omegaCoriolis = omegaCoriolis;
|
|
||||||
p->use2ndOrderCoriolis = use2ndOrderCoriolis;
|
|
||||||
CombinedPreintegratedMeasurements newPim = pim;
|
|
||||||
newPim.p_ = p;
|
|
||||||
PoseVelocityBias pvb = newPim.predict(pose_i, vel_i, bias_i);
|
|
||||||
pose_j = pvb.pose;
|
pose_j = pvb.pose;
|
||||||
vel_j = pvb.velocity;
|
vel_j = pvb.velocity;
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -245,7 +245,7 @@ public:
|
||||||
// @deprecated use PreintegrationBase::predict
|
// @deprecated use PreintegrationBase::predict
|
||||||
static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j,
|
static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j,
|
||||||
Vector3& vel_j, const imuBias::ConstantBias& bias_i,
|
Vector3& vel_j, const imuBias::ConstantBias& bias_i,
|
||||||
const CombinedPreintegratedMeasurements& pim,
|
CombinedPreintegratedMeasurements& pim,
|
||||||
const Vector3& gravity, const Vector3& omegaCoriolis,
|
const Vector3& gravity, const Vector3& omegaCoriolis,
|
||||||
const bool use2ndOrderCoriolis = false);
|
const bool use2ndOrderCoriolis = false);
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -195,18 +195,12 @@ ImuFactor::ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
|
||||||
void ImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
|
void ImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i,
|
||||||
Pose3& pose_j, Vector3& vel_j,
|
Pose3& pose_j, Vector3& vel_j,
|
||||||
const imuBias::ConstantBias& bias_i,
|
const imuBias::ConstantBias& bias_i,
|
||||||
const PreintegratedMeasurements& pim,
|
PreintegratedMeasurements& pim,
|
||||||
const Vector3& gravity, const Vector3& omegaCoriolis,
|
const Vector3& gravity, const Vector3& omegaCoriolis,
|
||||||
const bool use2ndOrderCoriolis) {
|
const bool use2ndOrderCoriolis) {
|
||||||
// NOTE(frank): hack below only for backward compatibility
|
// use deprecated predict
|
||||||
boost::shared_ptr<PreintegratedMeasurements::Params> p =
|
PoseVelocityBias pvb = pim.predict(pose_i, vel_i, bias_i, gravity,
|
||||||
boost::make_shared<PreintegratedMeasurements::Params>(pim.p());
|
omegaCoriolis, use2ndOrderCoriolis);
|
||||||
p->gravity = gravity;
|
|
||||||
p->omegaCoriolis = omegaCoriolis;
|
|
||||||
p->use2ndOrderCoriolis = use2ndOrderCoriolis;
|
|
||||||
PreintegratedMeasurements newPim = pim;
|
|
||||||
newPim.p_ = p;
|
|
||||||
PoseVelocityBias pvb = newPim.predict(pose_i, vel_i, bias_i);
|
|
||||||
pose_j = pvb.pose;
|
pose_j = pvb.pose;
|
||||||
vel_j = pvb.velocity;
|
vel_j = pvb.velocity;
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -212,7 +212,7 @@ public:
|
||||||
/// @deprecated use PreintegrationBase::predict
|
/// @deprecated use PreintegrationBase::predict
|
||||||
static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j,
|
static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j,
|
||||||
Vector3& vel_j, const imuBias::ConstantBias& bias_i,
|
Vector3& vel_j, const imuBias::ConstantBias& bias_i,
|
||||||
const PreintegratedMeasurements& pim, const Vector3& gravity,
|
PreintegratedMeasurements& pim, const Vector3& gravity,
|
||||||
const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false);
|
const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue