MAVLink: Only update rx count on successful read

This commit is contained in:
Erik de Castro Lopo 2015-11-27 15:49:26 +11:00
parent 0b3889e2e3
commit 6c2c2b19a7

View File

@ -1837,8 +1837,10 @@ MavlinkReceiver::receive_thread(void *arg)
}
}
/* count received bytes */
_mavlink->count_rxbytes(nread);
/* count received bytes (nread will be -1 on read error) */
if (nread > 0) {
_mavlink->count_rxbytes(nread);
}
}
}