Send FS state to gcs for AC

This commit is contained in:
Michael Oborne 2013-02-09 10:11:36 +08:00
parent 88840eb759
commit 61e5b09f28
1 changed files with 5 additions and 1 deletions

View File

@ -68,6 +68,10 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
uint8_t system_status = MAV_STATE_ACTIVE;
uint32_t custom_mode = control_mode;
if (ap.failsafe == true) {
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