diff --git a/libraries/AP_HAL_QURT/Storage.cpp b/libraries/AP_HAL_QURT/Storage.cpp index 11bdc9bd3f..d9d1f74fd8 100644 --- a/libraries/AP_HAL_QURT/Storage.cpp +++ b/libraries/AP_HAL_QURT/Storage.cpp @@ -39,7 +39,7 @@ void Storage::write_block(uint16_t loc, const void *src, size_t n) return; } if (memcmp(src, &buffer[loc], n) != 0) { - lock.take(0); + lock.take(HAL_SEMAPHORE_BLOCK_FOREVER); memcpy(&buffer[loc], src, n); dirty = true; lock.give(); diff --git a/libraries/AP_HAL_QURT/UARTDriver.cpp b/libraries/AP_HAL_QURT/UARTDriver.cpp index a555a9af72..ee0fd00e30 100644 --- a/libraries/AP_HAL_QURT/UARTDriver.cpp +++ b/libraries/AP_HAL_QURT/UARTDriver.cpp @@ -206,7 +206,7 @@ int16_t UARTDriver::read() if (!initialised) { return -1; } - if (!lock.take(0)) { + if (!lock.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { return 0; } if (readbuf->empty()) { @@ -224,7 +224,7 @@ size_t UARTDriver::write(uint8_t c) if (!initialised) { return 0; } - if (!lock.take(0)) { + if (!lock.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { return 0; } @@ -257,7 +257,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size) return ret; } - if (!lock.take(0)) { + if (!lock.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { return 0; } size_t ret = writebuf->write(buffer, size); diff --git a/libraries/AP_HAL_QURT/UDPDriver.cpp b/libraries/AP_HAL_QURT/UDPDriver.cpp index bd1241273a..90434fe441 100644 --- a/libraries/AP_HAL_QURT/UDPDriver.cpp +++ b/libraries/AP_HAL_QURT/UDPDriver.cpp @@ -120,7 +120,7 @@ int16_t UDPDriver::read() if (!initialised) { return -1; } - if (!lock.take(0)) { + if (!lock.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { return 0; } if (readbuf->empty()) { @@ -138,7 +138,7 @@ size_t UDPDriver::write(uint8_t c) if (!initialised) { return 0; } - if (!lock.take(0)) { + if (!lock.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { return 0; } @@ -171,7 +171,7 @@ size_t UDPDriver::write(const uint8_t *buffer, size_t size) return ret; } - if (!lock.take(0)) { + if (!lock.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { return 0; } size_t ret = writebuf->write(buffer, size); diff --git a/libraries/AP_HAL_QURT/dsp_main.cpp b/libraries/AP_HAL_QURT/dsp_main.cpp index d57b2635c8..8349dfa03b 100644 --- a/libraries/AP_HAL_QURT/dsp_main.cpp +++ b/libraries/AP_HAL_QURT/dsp_main.cpp @@ -74,7 +74,7 @@ uint32_t ardupilot_set_storage(const uint8_t *buf, int len) HAP_PRINTF("Incorrect storage size %u", len); return 1; } - QURT::Storage::lock.take(0); + QURT::Storage::lock.take(HAL_SEMAPHORE_BLOCK_FOREVER); memcpy(QURT::Storage::buffer, buf, len); QURT::Storage::lock.give(); return 0; @@ -89,7 +89,7 @@ uint32_t ardupilot_get_storage(uint8_t *buf, int len) if (!QURT::Storage::dirty) { return 1; } - QURT::Storage::lock.take(0); + QURT::Storage::lock.take(HAL_SEMAPHORE_BLOCK_FOREVER); memcpy(buf, QURT::Storage::buffer, len); QURT::Storage::lock.give(); return 0;