Plane: send both SYS_STATUS or POWER_STATUS or neither

This commit is contained in:
Peter Barker 2018-12-04 16:08:15 +11:00 committed by Randy Mackay
parent 3d8588a636
commit 67042d39d1
1 changed files with 4 additions and 2 deletions

View File

@ -434,9 +434,11 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
switch (id) { switch (id) {
case MSG_EXTENDED_STATUS1: case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS); if (PAYLOAD_SIZE(chan, SYS_STATUS) +
PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) {
return false;
}
plane.send_sys_status(chan); plane.send_sys_status(chan);
CHECK_PAYLOAD_SIZE2(POWER_STATUS);
send_power_status(); send_power_status();
break; break;