mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Send FS state to gcs for AP
This commit is contained in:
parent
582d1c47b3
commit
88840eb759
@ -28,6 +28,10 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
uint8_t system_status = MAV_STATE_ACTIVE;
|
||||
uint32_t custom_mode = control_mode;
|
||||
|
||||
if (failsafe != FAILSAFE_NONE) {
|
||||
system_status = MAV_STATE_CRITICAL;
|
||||
}
|
||||
|
||||
// work out the base_mode. This value is not very useful
|
||||
// for APM, but we calculate it as best we can so a generic
|
||||
// MAVLink enabled ground station can work out something about
|
||||
|
Loading…
Reference in New Issue
Block a user