Browse Source

Send FS state to gcs for AC

mission-4.1.18
Michael Oborne 12 years ago
parent
commit
61e5b09f28
  1. 4
      ArduCopter/GCS_Mavlink.pde

4
ArduCopter/GCS_Mavlink.pde

@ -68,6 +68,10 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan) @@ -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

Loading…
Cancel
Save