Rover: send both SYS_STATUS or POWER_STATUS or neither
This commit is contained in:
parent
0bdeccb568
commit
a5b5688960
@ -319,9 +319,11 @@ bool GCS_MAVLINK_Rover::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 (initialised) {
|
if (initialised) {
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
if (PAYLOAD_SIZE(chan, SYS_STATUS) +
|
||||||
|
PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
rover.send_sys_status(chan);
|
rover.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