/* * This file is free software: you can redistribute it and/or modify it * under the terms of the GNU General Public License as published by the * Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This file is distributed in the hope that it will be useful, but * WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * See the GNU General Public License for more details. * * You should have received a copy of the GNU General Public License along * with this program. If not, see . * * Code by Andrew Tridgell and Siddharth Bharat Purohit */ #include #include "ch.h" #include "hal.h" #if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER) #include "AnalogIn.h" #if HAL_WITH_IO_MCU #include extern AP_IOMCU iomcu; #endif #include "hwdef/common/stm32_util.h" // MAVLink is included as we send a mavlink message as part of debug, // and also use the MAV_POWER flags below in update_power_flags #include #define ANLOGIN_DEBUGGING 0 // base voltage scaling for 12 bit 3.3V ADC #define VOLTAGE_SCALING (3.3f / ((1 << 12) - 1)) // voltage divider is usually 1/(10/(20+10)) #ifndef HAL_IOMCU_VSERVO_SCALAR #define HAL_IOMCU_VSERVO_SCALAR 3 #endif // voltage divider is usually not present #ifndef HAL_IOMCU_VRSSI_SCALAR #define HAL_IOMCU_VRSSI_SCALAR 1 #endif #if ANLOGIN_DEBUGGING # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) #else # define Debug(fmt, args ...) #endif 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. */ const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS; #define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config) #if defined(ADC_CFGR_RES_16BITS) // on H7 we use 16 bit ADC transfers, giving us more resolution. We // need to scale by 1/16 to match the 12 bit scale factors in hwdef.dat #define ADC_BOARD_SCALING (1.0/16) #else #define ADC_BOARD_SCALING 1 #endif // samples filled in by ADC DMA engine adcsample_t *AnalogIn::samples; uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS]; uint32_t AnalogIn::sample_count; AnalogSource::AnalogSource(int16_t pin) : _pin(pin) { } float AnalogSource::read_average() { 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; } float AnalogSource::read_latest() { return _latest_value; } /* return scaling from ADC count to Volts */ float AnalogSource::_pin_scaler(void) { float scaling = VOLTAGE_SCALING; for (uint8_t i=0; imalloc_type(sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS, AP_HAL::Util::MEM_DMA_SAFE); adcStart(&ADCD1, NULL); memset(&adcgrpcfg, 0, sizeof(adcgrpcfg)); adcgrpcfg.circular = true; adcgrpcfg.num_channels = ADC_GRP1_NUM_CHANNELS; adcgrpcfg.end_cb = adccallback; #if defined(ADC_CFGR_RES_16BITS) // use 16 bit resolution adcgrpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_16BITS; #elif defined(ADC_CFGR_RES_12BITS) // use 12 bit resolution adcgrpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS; #else // use 12 bit resolution with ADCv1 or ADCv2 adcgrpcfg.sqr1 = ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS); adcgrpcfg.cr2 = ADC_CR2_SWSTART; #endif for (uint8_t i=0; i v) { sample_adc3_min[j] = v; } if (sample_adc3_max[j] == 0 || sample_adc3_max[j] < v) { sample_adc3_max[j] = v; } } } sample_adc3_count += ADC_DMA_BUF_DEPTH; } /* setup ADC3 for internal temperature and voltage monitoring */ void AnalogIn::setup_adc3(void) { samples_adc3 = (adcsample_t *)hal.util->malloc_type(sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC3_GRP1_NUM_CHANNELS, AP_HAL::Util::MEM_DMA_SAFE); if (samples_adc3 == nullptr) { // not likely, but can't setup ADC3 return; } adcStart(&ADCD3, NULL); adcSTM32EnableVREF(&ADCD3); adcSTM32EnableTS(&ADCD3); adcSTM32EnableVBAT(&ADCD3); memset(&adc3grpcfg, 0, sizeof(adc3grpcfg)); adc3grpcfg.circular = true; adc3grpcfg.num_channels = ADC3_GRP1_NUM_CHANNELS; adc3grpcfg.end_cb = adc3callback; #if defined(ADC_CFGR_RES_16BITS) // use 16 bit resolution adc3grpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_16BITS; #elif defined(ADC_CFGR_RES_12BITS) // use 12 bit resolution adc3grpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS; #else // use 12 bit resolution with ADCv1 or ADCv2 adc3grpcfg.sqr1 = ADC_SQR1_NUM_CH(ADC3_GRP1_NUM_CHANNELS); adc3grpcfg.cr2 = ADC_CR2_SWSTART; #endif const uint8_t channels[ADC3_GRP1_NUM_CHANNELS] = { ADC3_VBAT4_CHAN, ADC3_VSENSE_CHAN, ADC3_VREFINT_CHAN }; for (uint8_t i=0; i_pin) { // add a value c->_add_value(buf_adc[i] * ADC_BOARD_SCALING, _board_voltage); } else if (c->_pin == ANALOG_SERVO_VRSSI_PIN) { c->_add_value(_rssi_voltage / VOLTAGE_SCALING, 0); } } } } #if HAL_WITH_MCU_MONITORING // 20Hz temperature and ref voltage static uint32_t last_mcu_temp_us; if (now - last_mcu_temp_us > 50000 && hal.scheduler->is_system_initialized()) { last_mcu_temp_us = now; uint32_t buf_adc3[ADC3_GRP1_NUM_CHANNELS]; uint16_t min_adc3[ADC3_GRP1_NUM_CHANNELS]; uint16_t max_adc3[ADC3_GRP1_NUM_CHANNELS]; read_adc3(buf_adc3, min_adc3, max_adc3); // factory calibration values const float TS_CAL1 = *(const volatile uint16_t *)0x1FF1E820; const float TS_CAL2 = *(const volatile uint16_t *)0x1FF1E840; const float VREFINT_CAL = *(const volatile uint16_t *)0x1FF1E860; _mcu_temperature = ((110 - 30) / (TS_CAL2 - TS_CAL1)) * (float(buf_adc3[1]) - TS_CAL1) + 30; _mcu_voltage = 3.3 * VREFINT_CAL / float(buf_adc3[2]+0.001); // note min/max swap due to inversion _mcu_voltage_min = 3.3 * VREFINT_CAL / float(max_adc3[2]+0.001); _mcu_voltage_max = 3.3 * VREFINT_CAL / float(min_adc3[2]+0.001); } #endif } AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) { WITH_SEMAPHORE(_semaphore); for (uint8_t j=0; j 3000) { last_change_ms = 0; hal.console->printf("POWR: 0x%02x -> 0x%02x\n", _power_flags, flags); _power_flags = flags; } if (hal.util->get_soft_armed()) { // the power status has changed while armed flags |= MAV_POWER_STATUS_CHANGED; } return; } #endif if (_power_flags != 0 && _power_flags != flags && hal.util->get_soft_armed()) { // the power status has changed while armed flags |= MAV_POWER_STATUS_CHANGED; } _accumulated_power_flags |= flags; _power_flags = flags; } #endif // HAL_USE_ADC