Browse Source

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

Also removed redundant heartbeat message
mission-4.1.18
rmackay9 12 years ago committed by Andrew Tridgell
parent
commit
5ba363b007
  1. 11
      ArduCopter/ArduCopter.pde

11
ArduCopter/ArduCopter.pde

@ -978,6 +978,9 @@ void loop() @@ -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() @@ -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() @@ -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

Loading…
Cancel
Save