mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_TemperatureSensor: 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
7dcb5c60b0
commit
7bc364a338
@ -21,9 +21,7 @@ bool TSYS01::init(uint8_t bus)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
_dev->get_semaphore()->take_blocking();
|
||||||
AP_HAL::panic("PANIC: TSYS01: failed to take serial semaphore for init");
|
|
||||||
}
|
|
||||||
|
|
||||||
_dev->set_retries(10);
|
_dev->set_retries(10);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user