mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: fixed passthru for SITL
prevent panic when we expect zero writes
This commit is contained in:
parent
f77f8e5ad7
commit
1d6f1b9d8f
@ -140,7 +140,7 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
|||||||
}
|
}
|
||||||
const size_t written = mavlink_comm_port[chan]->write(buf, len);
|
const size_t written = mavlink_comm_port[chan]->write(buf, len);
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
if (written < len) {
|
if (written < len && !mavlink_comm_port[chan]->is_write_locked()) {
|
||||||
AP_HAL::panic("Short write on UART: %lu < %u", (unsigned long)written, len);
|
AP_HAL::panic("Short write on UART: %lu < %u", (unsigned long)written, len);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
Loading…
Reference in New Issue
Block a user