|
|
|
@ -17,6 +17,7 @@
@@ -17,6 +17,7 @@
|
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h> |
|
|
|
|
#include <errno.h> |
|
|
|
|
#include "GPIO.h" |
|
|
|
|
#include <AP_Common/Semaphore.h> |
|
|
|
|
|
|
|
|
|
#define ANLOGIN_DEBUGGING 0 |
|
|
|
|
|
|
|
|
@ -79,7 +80,6 @@ PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value) :
@@ -79,7 +80,6 @@ PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value) :
|
|
|
|
|
_sum_value(0), |
|
|
|
|
_sum_ratiometric(0) |
|
|
|
|
{ |
|
|
|
|
_semaphore = hal.util->new_semaphore(); |
|
|
|
|
#ifdef PX4_ANALOG_VCC_5V_PIN |
|
|
|
|
if (_pin == ANALOG_INPUT_BOARD_VCC) { |
|
|
|
|
_pin = PX4_ANALOG_VCC_5V_PIN; |
|
|
|
@ -94,19 +94,17 @@ void PX4AnalogSource::set_stop_pin(uint8_t p)
@@ -94,19 +94,17 @@ void PX4AnalogSource::set_stop_pin(uint8_t p)
|
|
|
|
|
|
|
|
|
|
float PX4AnalogSource::read_average()
|
|
|
|
|
{ |
|
|
|
|
if (_semaphore->take(1)) { |
|
|
|
|
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(); |
|
|
|
|
WITH_SEMAPHORE(_semaphore); |
|
|
|
|
|
|
|
|
|
if (_sum_count == 0) { |
|
|
|
|
return _value; |
|
|
|
|
} |
|
|
|
|
_value = _sum_value / _sum_count; |
|
|
|
|
_value_ratiometric = _sum_ratiometric / _sum_count; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_ratiometric = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
|
|
|
|
|
return _value; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -162,16 +160,15 @@ void PX4AnalogSource::set_pin(uint8_t pin)
@@ -162,16 +160,15 @@ void PX4AnalogSource::set_pin(uint8_t pin)
|
|
|
|
|
if (_pin == pin) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
if (_semaphore->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { |
|
|
|
|
_pin = pin; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_ratiometric = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
_latest_value = 0; |
|
|
|
|
_value = 0; |
|
|
|
|
_value_ratiometric = 0; |
|
|
|
|
_semaphore->give(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
WITH_SEMAPHORE(_semaphore); |
|
|
|
|
_pin = pin; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
_sum_ratiometric = 0; |
|
|
|
|
_sum_count = 0; |
|
|
|
|
_latest_value = 0; |
|
|
|
|
_value = 0; |
|
|
|
|
_value_ratiometric = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
@ -179,23 +176,22 @@ void PX4AnalogSource::set_pin(uint8_t pin)
@@ -179,23 +176,22 @@ void PX4AnalogSource::set_pin(uint8_t pin)
|
|
|
|
|
*/ |
|
|
|
|
void PX4AnalogSource::_add_value(float v, float vcc5V) |
|
|
|
|
{ |
|
|
|
|
if (_semaphore->take(1)) { |
|
|
|
|
_latest_value = v; |
|
|
|
|
_sum_value += v; |
|
|
|
|
if (vcc5V < 3.0f) { |
|
|
|
|
_sum_ratiometric += v; |
|
|
|
|
} else { |
|
|
|
|
// this compensates for changes in the 5V rail relative to the
|
|
|
|
|
// 3.3V reference used by the ADC.
|
|
|
|
|
_sum_ratiometric += v * 5.0f / vcc5V; |
|
|
|
|
} |
|
|
|
|
_sum_count++; |
|
|
|
|
if (_sum_count == 254) { |
|
|
|
|
_sum_value /= 2; |
|
|
|
|
_sum_ratiometric /= 2; |
|
|
|
|
_sum_count /= 2; |
|
|
|
|
} |
|
|
|
|
_semaphore->give(); |
|
|
|
|
WITH_SEMAPHORE(_semaphore); |
|
|
|
|
|
|
|
|
|
_latest_value = v; |
|
|
|
|
_sum_value += v; |
|
|
|
|
if (vcc5V < 3.0f) { |
|
|
|
|
_sum_ratiometric += v; |
|
|
|
|
} else { |
|
|
|
|
// this compensates for changes in the 5V rail relative to the
|
|
|
|
|
// 3.3V reference used by the ADC.
|
|
|
|
|
_sum_ratiometric += v * 5.0f / vcc5V; |
|
|
|
|
} |
|
|
|
|
_sum_count++; |
|
|
|
|
if (_sum_count == 254) { |
|
|
|
|
_sum_value /= 2; |
|
|
|
|
_sum_ratiometric /= 2; |
|
|
|
|
_sum_count /= 2; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|