From 8f867ddb2bc4080e001ccae148b6e2a6bf04457e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Jan 2020 08:42:32 +1100 Subject: [PATCH] AP_BoardConfig: use take_blocking instead of HAL_SEMAPHORE_BLOCK_FOREVER this makes for cleaner and smaller code as the failure case is not needed --- libraries/AP_BoardConfig/board_drivers.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/libraries/AP_BoardConfig/board_drivers.cpp b/libraries/AP_BoardConfig/board_drivers.cpp index 11cc387bf1..42b33e3ff2 100644 --- a/libraries/AP_BoardConfig/board_drivers.cpp +++ b/libraries/AP_BoardConfig/board_drivers.cpp @@ -136,9 +136,7 @@ bool AP_BoardConfig::spi_check_register(const char *devname, uint8_t regnum, uin return false; } dev->set_read_flag(read_flag); - if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - return false; - } + dev->get_semaphore()->take_blocking(); uint8_t v; if (!dev->read_registers(regnum, &v, 1)) { #if SPI_PROBE_DEBUG @@ -166,9 +164,10 @@ static bool check_ms5611(const char* devname) { AP_HAL::Semaphore *dev_sem = dev->get_semaphore(); - if (!dev_sem || !dev_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { + if (!dev_sem) { return false; } + dev_sem->take_blocking(); static const uint8_t CMD_MS56XX_RESET = 0x1E; static const uint8_t CMD_MS56XX_PROM = 0xA0;