mirror of https://github.com/ArduPilot/ardupilot
Copter: use new scheduler API
This commit is contained in:
parent
19651373d0
commit
a0f9055a9d
|
@ -31,8 +31,10 @@ void failsafe_disable()
|
|||
//
|
||||
// failsafe_check - this function is called from the core timer interrupt at 1kHz.
|
||||
//
|
||||
void failsafe_check(uint32_t tnow)
|
||||
void failsafe_check(void *arg)
|
||||
{
|
||||
uint32_t tnow = hal.scheduler->micros();
|
||||
|
||||
if (mainLoop_count != failsafe_last_mainLoop_count) {
|
||||
// the main loop is running, all is OK
|
||||
failsafe_last_mainLoop_count = mainLoop_count;
|
||||
|
|
Loading…
Reference in New Issue