mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
ArduCopter: move gcs_check function (which sends to ground station) to run when 50hz loop is not running
Also removed redundant heartbeat message
This commit is contained in:
parent
6fceb278b0
commit
93063a812a
@ -1001,6 +1001,9 @@ void loop()
|
||||
gps_fix_count = 0;
|
||||
perf_mon_counter = 0;
|
||||
}
|
||||
}else{
|
||||
// process communications with the GCS
|
||||
gcs_check();
|
||||
}
|
||||
} else {
|
||||
#ifdef DESKTOP_BUILD
|
||||
@ -1017,11 +1020,6 @@ void loop()
|
||||
compass.accumulate();
|
||||
}
|
||||
}
|
||||
|
||||
// process communications with the GCS
|
||||
if (timer - fast_loopTimer < 6000) {
|
||||
gcs_check();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
@ -1359,8 +1357,6 @@ static void super_slow_loop()
|
||||
auto_disarming_counter = 0;
|
||||
}
|
||||
|
||||
gcs_send_message(MSG_HEARTBEAT);
|
||||
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_SUPERSLOWLOOP
|
||||
USERHOOK_SUPERSLOWLOOP
|
||||
|
Loading…
Reference in New Issue
Block a user