mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: remove separate calls to get delta-times for vel and ang
This commit is contained in:
parent
5c31238f28
commit
5dff32422d
@ -475,8 +475,8 @@ bool NavEKF2_core::readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &d
|
|||||||
const auto &ins = dal.ins();
|
const auto &ins = dal.ins();
|
||||||
|
|
||||||
if (ins_index < ins.get_accel_count()) {
|
if (ins_index < ins.get_accel_count()) {
|
||||||
ins.get_delta_velocity(ins_index,dVel);
|
ins.get_delta_velocity(ins_index,dVel, dVel_dt);
|
||||||
dVel_dt = MAX(ins.get_delta_velocity_dt(ins_index),1.0e-4f);
|
dVel_dt = MAX(dVel_dt,1.0e-4f);
|
||||||
dVel_dt = MIN(dVel_dt,1.0e-1f);
|
dVel_dt = MIN(dVel_dt,1.0e-1f);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -647,8 +647,8 @@ bool NavEKF2_core::readDeltaAngle(uint8_t ins_index, Vector3f &dAng, float &dAng
|
|||||||
const auto &ins = dal.ins();
|
const auto &ins = dal.ins();
|
||||||
|
|
||||||
if (ins_index < ins.get_gyro_count()) {
|
if (ins_index < ins.get_gyro_count()) {
|
||||||
ins.get_delta_angle(ins_index,dAng);
|
ins.get_delta_angle(ins_index, dAng, dAng_dt);
|
||||||
dAng_dt = MAX(ins.get_delta_angle_dt(ins_index),1.0e-4f);
|
dAng_dt = MAX(dAng_dt,1.0e-4f);
|
||||||
dAng_dt = MIN(dAng_dt,1.0e-1f);
|
dAng_dt = MIN(dAng_dt,1.0e-1f);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user