From 5ba363b007c8f6931869b1fc00ef3bc03858e372 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Thu, 20 Dec 2012 15:54:19 +0900 Subject: [PATCH] ArduCopter: move gcs_check function (which sends to ground station) to run when 50hz loop is not running Also removed redundant heartbeat message --- ArduCopter/ArduCopter.pde | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 145bf4e12b..8e881f971d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -978,6 +978,9 @@ void loop() gps_fix_count = 0; perf_mon_counter = 0; } + }else{ + // process communications with the GCS + gcs_check(); } } else { if (timer - fast_loopTimer < 9000) { @@ -991,11 +994,6 @@ void loop() compass.accumulate(); } } - - // process communications with the GCS - if (timer - fast_loopTimer < 6000) { - gcs_check(); - } } } @@ -1330,8 +1328,7 @@ static void super_slow_loop() auto_disarming_counter = 0; } - gcs_send_message(MSG_HEARTBEAT); - + // agmatthews - USERHOOKS #ifdef USERHOOK_SUPERSLOWLOOP USERHOOK_SUPERSLOWLOOP #endif