mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_RangeFinder: 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
1cee9bea28
commit
7dcb5c60b0
@ -75,9 +75,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeF
|
||||
*/
|
||||
bool AP_RangeFinder_MaxsonarI2CXL::_init(void)
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
if (!start_reading()) {
|
||||
_dev->get_semaphore()->give();
|
||||
|
@ -159,9 +159,10 @@ static const struct settings_table settings_v3hp[] = {
|
||||
*/
|
||||
bool AP_RangeFinder_PulsedLightLRF::init(void)
|
||||
{
|
||||
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (!_dev) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
_dev->set_retries(3);
|
||||
|
||||
// LidarLite needs split transfers
|
||||
|
@ -72,9 +72,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(RangeFinder::RangeF
|
||||
*/
|
||||
bool AP_RangeFinder_TeraRangerI2C::init(void)
|
||||
{
|
||||
if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
dev->get_semaphore()->take_blocking();
|
||||
|
||||
dev->set_retries(10);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user