mirror of https://github.com/ArduPilot/ardupilot
Copter: set UARTs non-blocking at end of initialisation
Previously we were setting to non-block after arming but this reduce the chance of bumping into a NuttX USB driver issue that can cause the uart to become unresponsive and also makes Copter consistent with Plane
This commit is contained in:
parent
34bc136a6c
commit
7f9cd20377
|
@ -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();
|
||||
|
|
|
@ -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 "));
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue