Browse Source

Copter: set GPS non-blocking

the new GPS driver only ever needs a non-blocking port
master
Andrew Tridgell 11 years ago
parent
commit
90f306cd3c
  1. 1
      ArduCopter/system.pde

1
ArduCopter/system.pde

@ -288,6 +288,7 @@ static void init_ardupilot() @@ -288,6 +288,7 @@ static void init_ardupilot()
// mid-flight, so set the serial ports non-blocking once we are
// ready to fly
hal.uartA->set_blocking_writes(false);
hal.uartB->set_blocking_writes(false);
hal.uartC->set_blocking_writes(false);
if (hal.uartD != NULL) {
hal.uartD->set_blocking_writes(false);

Loading…
Cancel
Save