mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLINK: avoid pushing partial RC_CHANNEL message into uart
In the case we do not send RC_CHANNELS_RAW, we will not check to see if RC_CHANNELS will fit. RC_CHANNELS is larger than RC_CHANNELS_RAW, so the check in the caller is insufficient.
This commit is contained in:
parent
b615677223
commit
0baee6f82b
|
@ -1014,10 +1014,10 @@ void GCS_MAVLINK::send_radio_in()
|
|||
values[6],
|
||||
values[7],
|
||||
receiver_rssi);
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) {
|
||||
// can't fit RC_CHANNELS
|
||||
return;
|
||||
}
|
||||
}
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) {
|
||||
// can't fit RC_CHANNELS
|
||||
return;
|
||||
}
|
||||
mavlink_msg_rc_channels_send(
|
||||
chan,
|
||||
|
|
Loading…
Reference in New Issue