mirror of https://github.com/ArduPilot/ardupilot
Sub: send both SYS_STATUS or POWER_STATUS or neither
This commit is contained in:
parent
67042d39d1
commit
4d21630bf0
|
@ -403,9 +403,11 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||||
// send extended status only once vehicle has been initialised
|
// send extended status only once vehicle has been initialised
|
||||||
// to avoid unnecessary errors being reported to user
|
// to avoid unnecessary errors being reported to user
|
||||||
if (sub.ap.initialised) {
|
if (sub.ap.initialised) {
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
if (PAYLOAD_SIZE(chan, SYS_STATUS) +
|
||||||
|
PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
sub.send_sys_status(chan);
|
sub.send_sys_status(chan);
|
||||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
|
||||||
send_power_status();
|
send_power_status();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue