mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
8c563ef1bf
commit
8f867ddb2b
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue