ArduCopter: added message to console when entering ESC Calibration on startup

This commit is contained in:
rmackay9 2012-10-09 12:31:05 +09:00
parent 0050232ae2
commit 04b50af6e1
1 changed files with 3 additions and 2 deletions

View File

@ -90,14 +90,15 @@ static void init_rc_out()
g.esc_calibrate.set_and_save(1); g.esc_calibrate.set_and_save(1);
// send miinimum throttle out to ESC // send miinimum throttle out to ESC
motors.output_min(); motors.output_min();
// display message on console
Serial.printf_P(PSTR("Entering ESC Calibration: please restart APM.\n"));
// block until we restart // block until we restart
while(1) { while(1) {
//Serial.println("esc");
delay(200); delay(200);
dancing_light(); dancing_light();
} }
}else{ }else{
//Serial.println("esc init"); Serial.printf_P(PSTR("ESC Calibration active: passing throttle through to ESCs.\n"));
// clear esc flag // clear esc flag
g.esc_calibrate.set_and_save(0); g.esc_calibrate.set_and_save(0);
// block until we restart // block until we restart