1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Fix incorrect Vref calibration

The formula used to compute VREF from VREFINT and VREFINTCAL was incorrect.

Also, as correct formulae for VREF and TEMPSENSOR incorporate lots of
MCU dependent variables and constants, a new driver level service was
added to convert ADC values to VREF voltage or temperature.
This commit is contained in:
jflyper 2019-07-21 02:09:39 +09:00
parent d8b74db2dc
commit 9d7cfb1e79
6 changed files with 71 additions and 37 deletions

View file

@ -80,6 +80,13 @@ typedef struct adcDevice_s {
#endif
} adcDevice_t;
#ifdef USE_ADC_INTERNAL
extern int32_t adcVREFINTCAL; // ADC value (12-bit) of band gap with Vref = VREFINTCAL_VREF
extern int32_t adcTSCAL1;
extern int32_t adcTSCAL2;
extern int32_t adcTSSlopeK;
#endif
extern const adcDevice_t adcHardware[];
extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
extern adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
@ -92,3 +99,40 @@ bool adcVerifyPin(ioTag_t tag, ADCDevice device);
// Marshall values in DMA instance/channel based order to adcChannel based order.
// Required for multi DMA instance implementation
void adcGetChannelValues(void);
//
// VREFINT and TEMPSENSOR related definitions
// These are shared among common adc.c and MCU dependent adc_stm32XXX.c
//
#ifdef STM32F7
// STM32F7 HAL library V1.12.0 defines VREFINT and TEMPSENSOR in stm32f7xx_ll_adc.h,
// which is not included from stm32f7xx_hal_adc.h
// We manually copy required lines here.
// XXX V1.14.0 may solve this problem
#define VREFINT_CAL_VREF ( 3300U) /* Analog voltage reference (Vref+) value with which temperature sensor has been calibrated in production (tolerance: +-10 mV) (unit: mV). */
#define TEMPSENSOR_CAL1_TEMP (( int32_t) 30) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL1_ADDR (tolerance: +-5 DegC) (unit: DegC). */
#define TEMPSENSOR_CAL2_TEMP (( int32_t) 110) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL2_ADDR (tolerance: +-5 DegC) (unit: DegC). */
#define TEMPSENSOR_CAL_VREFANALOG ( 3300U) /* Analog voltage reference (Vref+) voltage with which temperature sensor has been calibrated in production (+-10 mV) (unit: mV). */
// These addresses are incorrectly defined in stm32f7xx_ll_adc.h
#if defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx)
// F745xx_F746xx and F765xx_F767xx_F769xx
#define VREFINT_CAL_ADDR ((uint16_t*) (0x1FF0F44A))
#define TEMPSENSOR_CAL1_ADDR ((uint16_t*) (0x1FF0F44C))
#define TEMPSENSOR_CAL2_ADDR ((uint16_t*) (0x1FF0F44E))
#elif defined(STM32F722xx)
// F72x_F73x
#define VREFINT_CAL_ADDR ((uint16_t*) (0x1FF07A2A))
#define TEMPSENSOR_CAL1_ADDR ((uint16_t*) (0x1FF07A2C))
#define TEMPSENSOR_CAL2_ADDR ((uint16_t*) (0x1FF07A2E))
#endif
#endif // STM32F7
#ifdef STM32F4
// STM32F4 stdlib does not define any of these
#define VREFINT_CAL_VREF (3300U)
#define TEMPSENSOR_CAL_VREFANALOG (3300U)
#define TEMPSENSOR_CAL1_TEMP ((int32_t) 30)
#define TEMPSENSOR_CAL2_TEMP ((int32_t) 110)
#endif