From 24dc4391bb765490dc98c7d82d544751926d9750 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Nov 2013 17:20:39 +0900 Subject: [PATCH] Copter: display pre-arm check failure reason every 30sec --- ArduCopter/ArduCopter.pde | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 9b4618656c..f72cd710f1 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1219,8 +1219,15 @@ static void one_hz_loop() if ((g.log_bitmask & MASK_LOG_CURRENT) && motors.armed()) Log_Write_Current(); - // perform pre-arm checks - pre_arm_checks(false); + // perform pre-arm checks & display failures every 30 seconds + static uint8_t pre_arm_display_counter = 15; + pre_arm_display_counter++; + if (pre_arm_display_counter >= 30) { + pre_arm_checks(true); + pre_arm_display_counter = 0; + }else{ + pre_arm_checks(false); + } // auto disarm checks auto_disarm_check();