mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: use new scheduler API
This commit is contained in:
parent
a0f9055a9d
commit
88959004d7
@ -13,11 +13,12 @@
|
||||
* this failsafe_check function is called from the core timer interrupt
|
||||
* at 1kHz.
|
||||
*/
|
||||
void failsafe_check(uint32_t tnow)
|
||||
void failsafe_check(void *arg)
|
||||
{
|
||||
static uint16_t last_mainLoop_count;
|
||||
static uint32_t last_timestamp;
|
||||
static bool in_failsafe;
|
||||
uint32_t tnow = hal.scheduler->micros();
|
||||
|
||||
if (mainLoop_count != last_mainLoop_count) {
|
||||
// the main loop is running, all is OK
|
||||
|
Loading…
Reference in New Issue
Block a user