AP_NavEKF2: fixed use of old irqsave() API

This commit is contained in:
Andrew Tridgell 2019-09-21 12:20:45 +10:00
parent d7ee622edc
commit 1d47f9186e

View File

@ -525,7 +525,7 @@ void NavEKF2_core::UpdateFilter(bool predict)
// start the timer used for load measurement
#if EK2_DISABLE_INTERRUPTS
irqstate_t istate = irqsave();
void *istate = hal.scheduler->disable_interrupts_save();
#endif
hal.util->perf_begin(_perf_UpdateFilter);
@ -576,7 +576,7 @@ void NavEKF2_core::UpdateFilter(bool predict)
// stop the timer used for load measurement
hal.util->perf_end(_perf_UpdateFilter);
#if EK2_DISABLE_INTERRUPTS
irqrestore(istate);
hal.scheduler->restore_interrupts(istate);
#endif
/*