From b9b988fff407090860350df5516d119f4bc8df07 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Thu, 8 Jul 2021 13:54:25 +0200 Subject: [PATCH] AP_FETtecOneWire: Do not write to the UART buffer if the previous transfer did not complete yet Required for stable operation on F4 processors --- libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp index e5d8a92209..9a5a2dc5b1 100644 --- a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp +++ b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp @@ -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) {