mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AC: if vehicle is !flying show hb state as MAV_STATE_STANDBY
This helps GCSes determine the appropriate UI for the current vehicle mode.
This commit is contained in:
parent
43c4ba304d
commit
240a9ccaf0
@ -44,7 +44,7 @@ static void gcs_send_deferred(void)
|
||||
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
{
|
||||
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
uint8_t system_status = MAV_STATE_ACTIVE;
|
||||
uint8_t system_status = ap.land_complete ? MAV_STATE_STANDBY : MAV_STATE_ACTIVE;
|
||||
uint32_t custom_mode = control_mode;
|
||||
|
||||
if (ap.failsafe_radio == true) {
|
||||
|
Loading…
Reference in New Issue
Block a user