Skip to content
Snippets Groups Projects
Commit 93063a81 authored by rmackay9's avatar rmackay9
Browse files

ArduCopter: move gcs_check function (which sends to ground station) to run...

ArduCopter: move gcs_check function (which sends to ground station) to run when 50hz loop is not running

Also removed redundant heartbeat message
parent 6fceb278
No related branches found
No related tags found
No related merge requests found
...@@ -1001,6 +1001,9 @@ void loop() ...@@ -1001,6 +1001,9 @@ void loop()
gps_fix_count = 0; gps_fix_count = 0;
perf_mon_counter = 0; perf_mon_counter = 0;
} }
}else{
// process communications with the GCS
gcs_check();
} }
} else { } else {
#ifdef DESKTOP_BUILD #ifdef DESKTOP_BUILD
...@@ -1017,11 +1020,6 @@ void loop() ...@@ -1017,11 +1020,6 @@ void loop()
compass.accumulate(); compass.accumulate();
} }
} }
// process communications with the GCS
if (timer - fast_loopTimer < 6000) {
gcs_check();
}
} }
} }
...@@ -1359,8 +1357,6 @@ static void super_slow_loop() ...@@ -1359,8 +1357,6 @@ static void super_slow_loop()
auto_disarming_counter = 0; auto_disarming_counter = 0;
} }
gcs_send_message(MSG_HEARTBEAT);
// agmatthews - USERHOOKS // agmatthews - USERHOOKS
#ifdef USERHOOK_SUPERSLOWLOOP #ifdef USERHOOK_SUPERSLOWLOOP
USERHOOK_SUPERSLOWLOOP USERHOOK_SUPERSLOWLOOP
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment