Copter: set GPS non-blocking
the new GPS driver only ever needs a non-blocking port
This commit is contained in:
parent
57956dbda2
commit
ecd73413db
@ -288,6 +288,7 @@ static void init_ardupilot()
|
|||||||
// mid-flight, so set the serial ports non-blocking once we are
|
// mid-flight, so set the serial ports non-blocking once we are
|
||||||
// ready to fly
|
// ready to fly
|
||||||
hal.uartA->set_blocking_writes(false);
|
hal.uartA->set_blocking_writes(false);
|
||||||
|
hal.uartB->set_blocking_writes(false);
|
||||||
hal.uartC->set_blocking_writes(false);
|
hal.uartC->set_blocking_writes(false);
|
||||||
if (hal.uartD != NULL) {
|
if (hal.uartD != NULL) {
|
||||||
hal.uartD->set_blocking_writes(false);
|
hal.uartD->set_blocking_writes(false);
|
||||||
|
Loading…
Reference in New Issue
Block a user