mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: send both SYS_STATUS or POWER_STATUS or neither
This commit is contained in:
parent
a5b5688960
commit
3d8588a636
@ -277,9 +277,11 @@ bool GCS_MAVLINK_Copter::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 (copter.ap.initialised) {
|
if (copter.ap.initialised) {
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
if (PAYLOAD_SIZE(chan, SYS_STATUS) +
|
||||||
|
PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
copter.send_sys_status(chan);
|
copter.send_sys_status(chan);
|
||||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
|
||||||
send_power_status();
|
send_power_status();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user