From 340f1b43e65ece6d321263ee458b6abb8def353d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 15 Sep 2018 15:43:54 +1000 Subject: [PATCH] HAL_ChibiOS: fixed RSSI voltage from IOMCU --- libraries/AP_HAL_ChibiOS/AnalogIn.cpp | 32 ++++++++++++++------------- libraries/AP_HAL_ChibiOS/AnalogIn.h | 2 +- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index e6aaafa52f..7ffff1e8bb 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -51,6 +51,9 @@ extern const AP_HAL::HAL& hal; using namespace ChibiOS; +// special pins +#define ANALOG_SERVO_VRSSI_PIN 103 + /* scaling table between ADC count and actual input voltage, to account for voltage dividers on the board. @@ -183,13 +186,6 @@ void AnalogSource::_add_value(float v, float vcc5V) } -AnalogIn::AnalogIn() : - _board_voltage(0), - _servorail_voltage(0), - _power_flags(0) -{ -} - /* callback from ADC driver when sample buffer is filled */ @@ -290,24 +286,30 @@ void AnalogIn::_timer_tick(void) } #endif } + +#if HAL_WITH_IO_MCU + // now handle special inputs from IOMCU + _servorail_voltage = iomcu.get_vservo(); + _rssi_voltage = iomcu.get_vrssi(); +#endif + for (uint8_t i=0; i_pin) { - // add a value - c->_add_value(buf_adc[i], _board_voltage); + if (c != nullptr) { + if (pin_config[i].channel == c->_pin) { + // add a value + c->_add_value(buf_adc[i], _board_voltage); + } else if (c->_pin == ANALOG_SERVO_VRSSI_PIN) { + c->_add_value(_rssi_voltage / VOLTAGE_SCALING, 0); + } } } } -#if HAL_WITH_IO_MCU - // now handle special inputs from IOMCU - _servorail_voltage = iomcu.get_vservo(); -#endif - #if CHIBIOS_ADC_MAVLINK_DEBUG static uint8_t count; if (AP_HAL::millis() > 5000 && count++ == 10) { diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.h b/libraries/AP_HAL_ChibiOS/AnalogIn.h index 95bd88d21a..c4da3f156d 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.h +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.h @@ -57,7 +57,6 @@ class ChibiOS::AnalogIn : public AP_HAL::AnalogIn { public: friend class AnalogSource; - AnalogIn(); void init() override; AP_HAL::AnalogSource* channel(int16_t pin) override; void _timer_tick(void); @@ -80,6 +79,7 @@ private: uint32_t _last_run; float _board_voltage; float _servorail_voltage; + float _rssi_voltage; uint16_t _power_flags; ADCConversionGroup adcgrpcfg;