mirror of https://github.com/ArduPilot/ardupilot
AP_FETtecOneWire: reset buf_used
if byte is missing due to electrical noise it can now resync
This commit is contained in:
parent
2bf777ccb7
commit
61b5d372c1
|
@ -606,6 +606,7 @@ void AP_FETtecOneWire::escs_set_values(const uint16_t* motor_values)
|
|||
// No command was yet sent, so no reply is expected and all information
|
||||
// on the receive buffer is either garbage or noise. Discard it
|
||||
_uart->discard_input();
|
||||
_receive_buf_used = 0;
|
||||
|
||||
// send throttle commands to all configured ESCs in a single packet transfer
|
||||
if (transmit(fast_throttle_command, sizeof(fast_throttle_command))) {
|
||||
|
|
Loading…
Reference in New Issue