From 7142bacfaa789be31bb1c50f4af838764d4cd24f Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 10 May 2016 22:18:28 -0700 Subject: [PATCH] Plane: improve user friendliness of throttle fs msg --- ArduPlane/radio.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 66abcbeef1..d31ce03eb9 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -253,7 +253,7 @@ void Plane::control_failsafe(uint16_t pwm) // throttle has dropped below the mark failsafe.ch3_counter++; if (failsafe.ch3_counter == 10) { - gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MSG FS ON %u", (unsigned)pwm); + gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Throttle failsafe on %u", (unsigned)pwm); failsafe.ch3_failsafe = true; AP_Notify::flags.failsafe_radio = true; } @@ -269,7 +269,7 @@ void Plane::control_failsafe(uint16_t pwm) failsafe.ch3_counter = 3; } if (failsafe.ch3_counter == 1) { - gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MSG FS OFF %u", (unsigned)pwm); + gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Throttle failsafe off %u", (unsigned)pwm); } else if(failsafe.ch3_counter == 0) { failsafe.ch3_failsafe = false; AP_Notify::flags.failsafe_radio = false;