mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_HAL_Linux: SPIUARTDriver: initialize device once
This commit is contained in:
parent
418cc817a3
commit
e3c0476b8a
@ -59,6 +59,12 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
if (txS < 1024) {
|
if (txS < 1024) {
|
||||||
txS = 2048;
|
txS = 2048;
|
||||||
}
|
}
|
||||||
|
if (!is_initialized()) {
|
||||||
|
_dev = hal.spi->get_device("ublox");
|
||||||
|
if (!_dev) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
allocate the read buffer
|
allocate the read buffer
|
||||||
|
Loading…
Reference in New Issue
Block a user