mirror of https://github.com/ArduPilot/ardupilot
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:
parent
98c03b498d
commit
b9b988fff4
|
@ -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) {
|
||||
|
|
Loading…
Reference in New Issue