diff --git a/ArduPlane/events.pde b/ArduPlane/events.pde index 1ca5b4a4ca..e4ea0b4f0c 100644 --- a/ArduPlane/events.pde +++ b/ArduPlane/events.pde @@ -6,7 +6,7 @@ static void failsafe_short_on_event() // This is how to handle a short loss of control signal failsafe. failsafe = FAILSAFE_SHORT; ch3_failsafe_timer = millis(); - gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event on")); + gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event on, ")); switch(control_mode) { case MANUAL: @@ -35,7 +35,7 @@ static void failsafe_short_on_event() static void failsafe_long_on_event() { // This is how to handle a long loss of control signal failsafe. - gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on")); + gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on, ")); APM_RC.clearOverride(); // If the GCS is locked up we allow control to revert to RC switch(control_mode) { @@ -59,6 +59,7 @@ static void failsafe_long_on_event() default: break; } + gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode); } static void failsafe_short_off_event()