mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-22 21:17:34 +08:00
MAVLink: Only update rx count on successful read
This commit is contained in:
@@ -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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user