mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_HAL_ChibiOS: add semaphore to AnalogIn::channel to make it thread safe
This commit is contained in:
parent
f2c2e8c1eb
commit
7c96522e44
@ -357,6 +357,7 @@ void AnalogIn::_timer_tick(void)
|
||||
|
||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin)
|
||||
{
|
||||
WITH_SEMAPHORE(_semaphore);
|
||||
for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource(pin);
|
||||
|
@ -88,6 +88,7 @@ private:
|
||||
static adcsample_t *samples;
|
||||
static uint32_t sample_sum[];
|
||||
static uint32_t sample_count;
|
||||
HAL_Semaphore _semaphore;
|
||||
};
|
||||
|
||||
#endif // HAL_USE_ADC
|
||||
|
Loading…
Reference in New Issue
Block a user