AP_NavEKF2: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:13:15 +09:00 committed by Randy Mackay
parent e3c317b96b
commit 8d882b06dd
2 changed files with 3 additions and 3 deletions

View File

@ -320,7 +320,7 @@ void NavEKF2_core::readIMUData()
dtIMUavg = 1.0f/ins.get_sample_rate();
// the imu sample time is used as a common time reference throughout the filter
imuSampleTime_ms = hal.scheduler->millis();
imuSampleTime_ms = AP_HAL::millis();
// use the nominated imu or primary if not available
if (ins.use_accel(imu_index)) {

View File

@ -98,7 +98,7 @@ void NavEKF2_core::InitialiseVariables()
localFilterTimeStep_ms = max(localFilterTimeStep_ms,10);
// initialise time stamps
imuSampleTime_ms = hal.scheduler->millis();
imuSampleTime_ms = AP_HAL::millis();
lastHealthyMagTime_ms = imuSampleTime_ms;
prevTasStep_ms = imuSampleTime_ms;
prevBetaStep_ms = imuSampleTime_ms;
@ -393,7 +393,7 @@ void NavEKF2_core::UpdateFilter(bool predict)
// TODO - in-flight restart method
//get starting time for update step
imuSampleTime_ms = hal.scheduler->millis();
imuSampleTime_ms = AP_HAL::millis();
// Check arm status and perform required checks and mode changes
controlFilterModes();