mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: Change from magic number 0 to definition name.
This commit is contained in:
parent
07ab04897d
commit
af65be5aa4
|
@ -56,7 +56,7 @@ bool AP_Airspeed_MS4525::init()
|
|||
if (!_dev) {
|
||||
continue;
|
||||
}
|
||||
if (!_dev->get_semaphore()->take(0)) {
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -138,7 +138,7 @@ void AP_Airspeed_MS4525::_collect()
|
|||
|
||||
_voltage_correction(press, temp);
|
||||
|
||||
if (sem->take(0)) {
|
||||
if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_press_sum += press;
|
||||
_temp_sum += temp;
|
||||
_press_count++;
|
||||
|
@ -192,7 +192,7 @@ bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)
|
|||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||
return false;
|
||||
}
|
||||
if (sem->take(0)) {
|
||||
if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (_press_count > 0) {
|
||||
_pressure = _press_sum / _press_count;
|
||||
_press_count = 0;
|
||||
|
@ -210,7 +210,7 @@ bool AP_Airspeed_MS4525::get_temperature(float &temperature)
|
|||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||
return false;
|
||||
}
|
||||
if (sem->take(0)) {
|
||||
if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (_temp_count > 0) {
|
||||
_temperature = _temp_sum / _temp_count;
|
||||
_temp_count = 0;
|
||||
|
|
|
@ -66,7 +66,7 @@ bool AP_Airspeed_MS5525::init()
|
|||
if (!dev) {
|
||||
continue;
|
||||
}
|
||||
if (!dev->get_semaphore()->take(0)) {
|
||||
if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -213,7 +213,7 @@ void AP_Airspeed_MS5525::calculate(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (sem->take(0)) {
|
||||
if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
pressure_sum += P_Pa;
|
||||
temperature_sum += Temp_C;
|
||||
press_count++;
|
||||
|
@ -258,7 +258,7 @@ bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)
|
|||
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
||||
return false;
|
||||
}
|
||||
if (sem->take(0)) {
|
||||
if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (press_count > 0) {
|
||||
pressure = pressure_sum / press_count;
|
||||
press_count = 0;
|
||||
|
@ -276,7 +276,7 @@ bool AP_Airspeed_MS5525::get_temperature(float &_temperature)
|
|||
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
||||
return false;
|
||||
}
|
||||
if (sem->take(0)) {
|
||||
if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (temp_count > 0) {
|
||||
temperature = temperature_sum / temp_count;
|
||||
temp_count = 0;
|
||||
|
|
Loading…
Reference in New Issue