diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index eeda99a12a..8e5216b621 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -139,15 +139,6 @@ static void init_arm_motors() gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS")); #endif - // we don't want writes to the serial port to cause us to pause - // mid-flight, so set the serial ports non-blocking once we arm - // the motors - hal.uartA->set_blocking_writes(false); - hal.uartC->set_blocking_writes(false); - if (hal.uartD != NULL) { - hal.uartD->set_blocking_writes(false); - } - // Remember Orientation // -------------------- init_simple_bearing(); diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 8356b14e4d..76f1bc2503 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -278,6 +278,15 @@ static void init_ardupilot() Log_Write_Startup(); #endif + // we don't want writes to the serial port to cause us to pause + // mid-flight, so set the serial ports non-blocking once we are + // ready to fly + hal.uartA->set_blocking_writes(false); + hal.uartC->set_blocking_writes(false); + if (hal.uartD != NULL) { + hal.uartD->set_blocking_writes(false); + } + cliSerial->print_P(PSTR("\nReady to FLY ")); }