mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: use get_loop_delta_t() from INS
This commit is contained in:
parent
17fc58f3cd
commit
28a684ea03
|
@ -226,7 +226,7 @@ bool NavEKF_core::InitialiseFilterDynamic(void)
|
|||
InitialiseVariables();
|
||||
|
||||
// get initial time deltat between IMU measurements (sec)
|
||||
dtDelAng = dtIMUavg = 1.0f/_ahrs->get_ins().get_sample_rate();
|
||||
dtDelAng = dtIMUavg = _ahrs->get_ins().get_loop_delta_t();
|
||||
|
||||
// set number of updates over which gps and baro measurements are applied to the velocity and position states
|
||||
gpsUpdateCountMaxInv = (dtIMUavg * 1000.0f)/float(msecGpsAvg);
|
||||
|
@ -288,7 +288,7 @@ bool NavEKF_core::InitialiseFilterBootstrap(void)
|
|||
InitialiseVariables();
|
||||
|
||||
// get initial time deltat between IMU measurements (sec)
|
||||
dtDelAng = dtIMUavg = 1.0f/_ahrs->get_ins().get_sample_rate();
|
||||
dtDelAng = dtIMUavg = _ahrs->get_ins().get_loop_delta_t();
|
||||
|
||||
// set number of updates over which gps and baro measurements are applied to the velocity and position states
|
||||
gpsUpdateCountMaxInv = (dtIMUavg * 1000.0f)/float(msecGpsAvg);
|
||||
|
@ -3824,7 +3824,7 @@ void NavEKF_core::readIMUData()
|
|||
const AP_InertialSensor &ins = _ahrs->get_ins();
|
||||
|
||||
// calculate the average time between IMU updates
|
||||
dtIMUavg = 1.0f/(float)ins.get_sample_rate();
|
||||
dtIMUavg = ins.get_loop_delta_t();
|
||||
|
||||
// calculate the most recent time between gyro delta angle updates
|
||||
if (ins.get_delta_time() > 0.0f) {
|
||||
|
|
Loading…
Reference in New Issue