mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: fixed problem with slow ground station connects
don't trigger the "scheduler out of time" code when in the delay callback Thanks to Marijm Slootweg for noticing this!
This commit is contained in:
parent
bd6a60f28b
commit
e79023ceee
@ -546,7 +546,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||
// if we don't have at least 1ms remaining before the main loop
|
||||
// wants to fire then don't send a mavlink message. We want to
|
||||
// prioritise the main flight control loop over communications
|
||||
if (scheduler.time_available_usec() < 1200) {
|
||||
if (!in_mavlink_delay && scheduler.time_available_usec() < 1200) {
|
||||
gcs_out_of_time = true;
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user