Send FS state to gcs for AR

This commit is contained in:
Michael Oborne 2013-02-09 10:11:43 +08:00
parent 61e5b09f28
commit c2fd7617e1
1 changed files with 4 additions and 0 deletions

View File

@ -27,6 +27,10 @@ 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;
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