From fdf6aa5492534150b7e42fa98f6f4caaf5e88ac6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 23 Oct 2014 21:03:50 +0900 Subject: [PATCH] Copter: shorten ESC calibration message --- ArduCopter/radio.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index f4853f3bf1..0a274e1a83 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -62,13 +62,13 @@ static void init_rc_out() // we will enter esc_calibrate mode on next reboot g.esc_calibrate.set_and_save(1); // display message on console - cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n")); + cliSerial->printf_P(PSTR("Entering ESC Cal: restart APM.\n")); // turn on esc calibration notification AP_Notify::flags.esc_calibration = true; // block until we restart while(1) { delay(5); } }else{ - cliSerial->printf_P(PSTR("ESC Calibration active: passing throttle through to ESCs.\n")); + cliSerial->printf_P(PSTR("ESC Cal: passing throttle through to ESCs.\n")); // clear esc flag g.esc_calibrate.set_and_save(0); // pass through user throttle to escs