mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_HAL_ChibiOS: fix race condition on analog reading
This commit is contained in:
parent
80d1a1de9a
commit
a832bdfd04
@ -73,19 +73,24 @@ AnalogSource::AnalogSource(int16_t pin, float initial_value) :
|
|||||||
_sum_value(0),
|
_sum_value(0),
|
||||||
_sum_ratiometric(0)
|
_sum_ratiometric(0)
|
||||||
{
|
{
|
||||||
|
_semaphore = hal.util->new_semaphore();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
float AnalogSource::read_average()
|
float AnalogSource::read_average()
|
||||||
{
|
{
|
||||||
if (_sum_count == 0) {
|
if (_semaphore->take(1)) {
|
||||||
return _value;
|
if (_sum_count == 0) {
|
||||||
|
_semaphore->give();
|
||||||
|
return _value;
|
||||||
|
}
|
||||||
|
_value = _sum_value / _sum_count;
|
||||||
|
_value_ratiometric = _sum_ratiometric / _sum_count;
|
||||||
|
_sum_value = 0;
|
||||||
|
_sum_ratiometric = 0;
|
||||||
|
_sum_count = 0;
|
||||||
|
_semaphore->give();
|
||||||
}
|
}
|
||||||
_value = _sum_value / _sum_count;
|
|
||||||
_value_ratiometric = _sum_ratiometric / _sum_count;
|
|
||||||
_sum_value = 0;
|
|
||||||
_sum_ratiometric = 0;
|
|
||||||
_sum_count = 0;
|
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -140,13 +145,16 @@ void AnalogSource::set_pin(uint8_t pin)
|
|||||||
if (_pin == pin) {
|
if (_pin == pin) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_pin = pin;
|
if (_semaphore->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||||
_sum_value = 0;
|
_pin = pin;
|
||||||
_sum_ratiometric = 0;
|
_sum_value = 0;
|
||||||
_sum_count = 0;
|
_sum_ratiometric = 0;
|
||||||
_latest_value = 0;
|
_sum_count = 0;
|
||||||
_value = 0;
|
_latest_value = 0;
|
||||||
_value_ratiometric = 0;
|
_value = 0;
|
||||||
|
_value_ratiometric = 0;
|
||||||
|
_semaphore->give();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -154,20 +162,23 @@ void AnalogSource::set_pin(uint8_t pin)
|
|||||||
*/
|
*/
|
||||||
void AnalogSource::_add_value(float v, float vcc5V)
|
void AnalogSource::_add_value(float v, float vcc5V)
|
||||||
{
|
{
|
||||||
_latest_value = v;
|
if (_semaphore->take(1)) {
|
||||||
_sum_value += v;
|
_latest_value = v;
|
||||||
if (vcc5V < 3.0f) {
|
_sum_value += v;
|
||||||
_sum_ratiometric += v;
|
if (vcc5V < 3.0f) {
|
||||||
} else {
|
_sum_ratiometric += v;
|
||||||
// this compensates for changes in the 5V rail relative to the
|
} else {
|
||||||
// 3.3V reference used by the ADC.
|
// this compensates for changes in the 5V rail relative to the
|
||||||
_sum_ratiometric += v * 5.0f / vcc5V;
|
// 3.3V reference used by the ADC.
|
||||||
}
|
_sum_ratiometric += v * 5.0f / vcc5V;
|
||||||
_sum_count++;
|
}
|
||||||
if (_sum_count == 254) {
|
_sum_count++;
|
||||||
_sum_value /= 2;
|
if (_sum_count == 254) {
|
||||||
_sum_ratiometric /= 2;
|
_sum_value /= 2;
|
||||||
_sum_count /= 2;
|
_sum_ratiometric /= 2;
|
||||||
|
_sum_count /= 2;
|
||||||
|
}
|
||||||
|
_semaphore->give();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -50,6 +50,7 @@ private:
|
|||||||
float _sum_ratiometric;
|
float _sum_ratiometric;
|
||||||
void _add_value(float v, float vcc5V);
|
void _add_value(float v, float vcc5V);
|
||||||
float _pin_scaler();
|
float _pin_scaler();
|
||||||
|
AP_HAL::Semaphore *_semaphore;
|
||||||
};
|
};
|
||||||
|
|
||||||
class ChibiOS::AnalogIn : public AP_HAL::AnalogIn {
|
class ChibiOS::AnalogIn : public AP_HAL::AnalogIn {
|
||||||
|
Loading…
Reference in New Issue
Block a user