mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: avoid use if int16-t read call
This commit is contained in:
parent
85f89812d5
commit
f3a75661d9
|
@ -43,7 +43,10 @@ void AP_Frsky_SPort::send(void)
|
|||
}
|
||||
|
||||
for (int16_t i = 0; i < numc; i++) {
|
||||
int16_t readbyte = _port->read();
|
||||
uint8_t readbyte;
|
||||
if (!_port->read(readbyte)) {
|
||||
break;
|
||||
}
|
||||
if (_SPort.sport_status == false) {
|
||||
if (readbyte == FRAME_HEAD) {
|
||||
_SPort.sport_status = true;
|
||||
|
|
Loading…
Reference in New Issue