mirror of https://github.com/ArduPilot/ardupilot
AP_ADC: AP_ADC_ADS1115: release bus lock as soon as possible
This commit is contained in:
parent
85c0c98194
commit
e5d519edec
|
@ -223,6 +223,7 @@ void AP_ADC_ADS1115::_update()
|
|||
return;
|
||||
}
|
||||
|
||||
_dev->get_semaphore()->give();
|
||||
|
||||
float sample = _convert_register_data_to_mv(be16toh(val));
|
||||
|
||||
|
@ -233,7 +234,5 @@ void AP_ADC_ADS1115::_update()
|
|||
_channel_to_read = (_channel_to_read + 1) % _channels_number;
|
||||
_start_conversion(_channel_to_read);
|
||||
|
||||
_dev->get_semaphore()->give();
|
||||
|
||||
_last_update_timestamp = AP_HAL::micros();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue