AP_HAL_Linux: add semaphore to AnalogIn::channel to make it thread safe
This commit is contained in:
parent
7c96522e44
commit
4315a69b9d
@ -49,6 +49,7 @@ AnalogIn_ADS1115::AnalogIn_ADS1115()
|
||||
|
||||
AP_HAL::AnalogSource* AnalogIn_ADS1115::channel(int16_t pin)
|
||||
{
|
||||
WITH_SEMAPHORE(_semaphore);
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource_ADS1115(pin);
|
||||
|
@ -37,4 +37,5 @@ private:
|
||||
AP_ADC_ADS1115 *_adc;
|
||||
AnalogSource_ADS1115 *_channels[ADS1115_ADC_MAX_CHANNELS];
|
||||
uint32_t _last_update_timestamp;
|
||||
HAL_Semaphore _semaphore;
|
||||
};
|
||||
|
@ -107,6 +107,7 @@ float AnalogIn_Navio2::servorail_voltage(void)
|
||||
|
||||
AP_HAL::AnalogSource *AnalogIn_Navio2::channel(int16_t pin)
|
||||
{
|
||||
WITH_SEMAPHORE(_semaphore);
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource_Navio2(pin);
|
||||
|
@ -36,4 +36,5 @@ private:
|
||||
uint8_t _channels_number = NAVIO_ADC_MAX_CHANNELS;
|
||||
AP_HAL::AnalogSource *_board_voltage_pin = nullptr;
|
||||
AP_HAL::AnalogSource *_servorail_pin = nullptr;
|
||||
HAL_Semaphore _semaphore;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user