mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: correct out-of-space-to-send count
This commit is contained in:
parent
02219ba3e5
commit
2d96842490
|
@ -120,6 +120,7 @@ void comm_send_lock(mavlink_channel_t chan_m, uint16_t size)
|
|||
chan_locks[chan].take_blocking();
|
||||
if (mavlink_comm_port[chan]->txspace() < size) {
|
||||
chan_discard[chan] = true;
|
||||
gcs_out_of_space_to_send_count(chan_m);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue