Skip to content
Snippets Groups Projects
Commit e9773ea0 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

APM: use set_blocking_writes(false) when we have done ground start

parent 09853273
No related branches found
No related tags found
No related merge requests found
...@@ -340,6 +340,14 @@ static void startup_ground(void) ...@@ -340,6 +340,14 @@ static void startup_ground(void)
// ----------------------- // -----------------------
demo_servos(3); demo_servos(3);
// 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
Serial.set_blocking_writes(false);
if (gcs3.initialised) {
Serial3.set_blocking_writes(false);
}
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY.")); gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment