mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: fixed txsize check for airspeed info
prevent underflow
This commit is contained in:
parent
6f538aa556
commit
43b2e34242
@ -1612,8 +1612,8 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
|||||||
static void gcs_send_airspeed_calibration(const Vector3f &vg)
|
static void gcs_send_airspeed_calibration(const Vector3f &vg)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
if (comm_get_txspace((mavlink_channel_t)i) - MAVLINK_NUM_NON_PAYLOAD_BYTES >=
|
if (comm_get_txspace((mavlink_channel_t)i) >=
|
||||||
MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN) {
|
MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN) {
|
||||||
airspeed.log_mavlink_send((mavlink_channel_t)i, vg);
|
airspeed.log_mavlink_send((mavlink_channel_t)i, vg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user