AP_HAL_QURT: use HAL_SEMAPHORE_BLOCK_FOREVER macro

This commit is contained in:
Peter Barker 2017-05-02 16:07:39 +10:00 committed by Randy Mackay
parent 7ce353e652
commit 6bb75a730f
4 changed files with 9 additions and 9 deletions

View File

@ -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();

View File

@ -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);

View File

@ -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);

View File

@ -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;