Browse Source

ArduPlane: attempt to send GCS a message when the GCS heartbeat is not detected.

mission-4.1.18
Michael Day 11 years ago committed by Andrew Tridgell
parent
commit
3b62592b26
  1. 3
      ArduPlane/events.pde

3
ArduPlane/events.pde

@ -87,6 +87,9 @@ static void failsafe_long_on_event(enum failsafe_state fstype) @@ -87,6 +87,9 @@ static void failsafe_long_on_event(enum failsafe_state fstype)
default:
break;
}
if (fstype == FAILSAFE_GCS) {
gcs_send_text_P(SEVERITY_HIGH, PSTR("No GCS heartbeat."));
}
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
}

Loading…
Cancel
Save