|
|
|
@ -1,6 +1,7 @@
@@ -1,6 +1,7 @@
|
|
|
|
|
#include "AnalogIn_IIO.h" |
|
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
#include <AP_Common/Semaphore.h> |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
|
|
|
|
|
@ -23,7 +24,6 @@ AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float volta
@@ -23,7 +24,6 @@ AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float volta
|
|
|
|
|
_sum_count(0), |
|
|
|
|
_pin_fd(-1) |
|
|
|
|
{ |
|
|
|
|
_semaphore = hal.util->new_semaphore(); |
|
|
|
|
init_pins(); |
|
|
|
|
select_pin(); |
|
|
|
|
} |
|
|
|
@ -51,16 +51,16 @@ void AnalogSource_IIO::select_pin(void)
@@ -51,16 +51,16 @@ void AnalogSource_IIO::select_pin(void)
|
|
|
|
|
float AnalogSource_IIO::read_average() |
|
|
|
|
{ |
|
|
|
|
read_latest(); |
|
|
|
|
if (_semaphore->take(1)) { |
|
|
|
|
if (_sum_count == 0) { |
|
|
|
|
_semaphore->give(); |
|
|
|
|
return _value; |
|
|
|
|
} |
|
|
|
|
_value = _sum_value / _sum_count; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
_semaphore->give(); |
|
|
|
|
WITH_SEMAPHORE(_semaphore); |
|
|
|
|
|
|
|
|
|
if (_sum_count == 0) { |
|
|
|
|
return _value; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_value = _sum_value / _sum_count; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
|
|
|
|
|
return _value; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -78,12 +78,11 @@ float AnalogSource_IIO::read_latest()
@@ -78,12 +78,11 @@ float AnalogSource_IIO::read_latest()
|
|
|
|
|
_latest = 0; |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
if (_semaphore->take(1)) { |
|
|
|
|
_latest = atoi(sbuf) * _voltage_scaling; |
|
|
|
|
_sum_value += _latest; |
|
|
|
|
_sum_count++; |
|
|
|
|
_semaphore->give(); |
|
|
|
|
} |
|
|
|
|
WITH_SEMAPHORE(_semaphore); |
|
|
|
|
|
|
|
|
|
_latest = atoi(sbuf) * _voltage_scaling; |
|
|
|
|
_sum_value += _latest; |
|
|
|
|
_sum_count++; |
|
|
|
|
|
|
|
|
|
return _latest; |
|
|
|
|
} |
|
|
|
@ -106,15 +105,14 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
@@ -106,15 +105,14 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_semaphore->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { |
|
|
|
|
_pin = pin; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
_latest = 0; |
|
|
|
|
_value = 0; |
|
|
|
|
select_pin(); |
|
|
|
|
_semaphore->give(); |
|
|
|
|
} |
|
|
|
|
WITH_SEMAPHORE(_semaphore); |
|
|
|
|
|
|
|
|
|
_pin = pin; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
_latest = 0; |
|
|
|
|
_value = 0; |
|
|
|
|
select_pin(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AnalogSource_IIO::set_stop_pin(uint8_t p) |
|
|
|
|