From fbe8166c7128e25df7b1f576921e2de9feefa308 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2018 15:48:43 +1100 Subject: [PATCH] HAL_ChibiOS: auto-generate AnalogIn pin table --- libraries/AP_HAL_ChibiOS/AnalogIn.cpp | 21 +----- .../AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat | 12 ++-- .../hwdef/scripts/chibios_hwdef.py | 65 +++++++++++++++---- 3 files changed, 63 insertions(+), 35 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index c5eaa94032..11a1ad0f75 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -38,25 +38,11 @@ extern const AP_HAL::HAL& hal; using namespace ChibiOS; -// pin number for VCC rail -#define ANALOG_VCC_5V_PIN 4 - /* scaling table between ADC count and actual input voltage, to account for voltage dividers on the board. */ -const AnalogIn::pin_info AnalogIn::pin_config[] = { -#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 - { ANALOG_VCC_5V_PIN, 0.007734 }, // VCC 5V rail sense -#else - { ANALOG_VCC_5V_PIN, 6.6f/4096 }, // VCC 5V rail sense -#endif - { 2, VOLTAGE_SCALING }, // 3DR Brick voltage - { 3, VOLTAGE_SCALING }, // 3DR Brick current - { 13, VOLTAGE_SCALING }, // AUX ADC pin 4 - { 14, VOLTAGE_SCALING }, // AUX ADC pin 3 - { 15, VOLTAGE_SCALING*2 }, // analog airspeed sensor, 2:1 scaling -}; +const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS; #define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(AnalogIn::pin_config) @@ -65,9 +51,6 @@ adcsample_t AnalogIn::samples[ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS]; uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS]; uint32_t AnalogIn::sample_count; -// special pin numbers -#define ANALOG_VCC_5V_PIN 4 - AnalogSource::AnalogSource(int16_t pin, float initial_value) : _pin(pin), _value(initial_value), @@ -266,11 +249,13 @@ void AnalogIn::_timer_tick(void) // match the incoming channels to the currently active pins for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) { +#ifdef ANALOG_VCC_5V_PIN if (pin_config[i].channel == ANALOG_VCC_5V_PIN) { // record the Vcc value for later use in // voltage_average_ratiometric() _board_voltage = buf_adc[i] * pin_config[i].scaling; } +#endif } for (uint8_t i=0; i