From a0f9055a9d70f0cf98cd543803ddefbd4a3a660e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Sep 2013 16:31:01 +1000 Subject: [PATCH] Copter: use new scheduler API --- ArduCopter/failsafe.pde | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/failsafe.pde b/ArduCopter/failsafe.pde index be76f79ce3..40441daf1d 100644 --- a/ArduCopter/failsafe.pde +++ b/ArduCopter/failsafe.pde @@ -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; @@ -56,4 +58,4 @@ void failsafe_check(uint32_t tnow) motors.output(); } } -} \ No newline at end of file +}