AP_FETtecOneWire: Do not write to the UART buffer if the previous transfer did not complete yet

Required for stable operation on F4 processors
This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-07-08 13:54:25 +02:00 committed by Randy Mackay
parent 98c03b498d
commit b9b988fff4
1 changed files with 9 additions and 0 deletions

View File

@ -798,6 +798,15 @@ void AP_FETtecOneWire::update()
return;
}
#if defined(STM32F4)
if (_uart->tx_pending()) {
// there is unsent data in the send buffer,
// do not send more data because FETtec needs a time gap between frames
_period_too_short++;
return;
}
#endif
#if HAL_AP_FETTEC_CONFIGURE_ESCS
// run ESC configuration state machines if needed
if (_running_mask != _motor_mask) {