mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 04:28:30 -04:00
AP_Notify: 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
b89c241329
commit
0d44d666d0
@ -68,9 +68,10 @@ bool Display_SH1106_I2C::hw_init()
|
||||
memset(_displaybuffer, 0, SH1106_COLUMNS * SH1106_ROWS_PER_PAGE);
|
||||
|
||||
// take i2c bus semaphore
|
||||
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (!_dev) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// init display
|
||||
bool success = _dev->transfer((uint8_t *)&init_seq, sizeof(init_seq), nullptr, 0);
|
||||
|
@ -76,9 +76,10 @@ bool Display_SSD1306_I2C::hw_init()
|
||||
memset(_displaybuffer, 0, SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE);
|
||||
|
||||
// take i2c bus semaphore
|
||||
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (!_dev) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// init display
|
||||
bool success = _dev->transfer((uint8_t *)&init_seq, sizeof(init_seq), nullptr, 0);
|
||||
|
Loading…
Reference in New Issue
Block a user