GCS_MAVLink: tidy sending of queued mcu status messages
This commit is contained in:
parent
71c1886c74
commit
ec69867102
@ -5883,12 +5883,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
send_power_status();
|
||||
break;
|
||||
|
||||
case MSG_MCU_STATUS:
|
||||
#if HAL_WITH_MCU_MONITORING
|
||||
case MSG_MCU_STATUS:
|
||||
CHECK_PAYLOAD_SIZE(MCU_STATUS);
|
||||
send_mcu_status();
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSG_RC_CHANNELS:
|
||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS);
|
||||
|
Loading…
Reference in New Issue
Block a user