Skip to content

Commit

Permalink
[H7][ADC] Migration to V1.4.0 library
Browse files Browse the repository at this point in the history
- VRef and Temperature sensor calibration constants defined in "stm32h7xx_ll_adc.h" are now included via “stm32h7xx_hal_adc.h”.
- Boostmode is now handled by HAL_ADC_Init using clock configuration parameters to cope with Rev.V.

- Channel specifier (ADC_CHANNEL_x) was a simple integer with V1.3.0, is now an bit field encoded value.
adcTagMap had this value, but adcChannel field in adcOperationConfig was not big enough to store it.
The adcChannel field is modified to hold 32-bit value.

- Rank for channel configuration was a integer, now a bit field encoded value (ADC_RANK_x).
adcRegularRankMap array was added to translate rank number to rank value.

- Other Rev.V changes also seem to be handled within HAL.
  • Loading branch information
ezshinoda committed Jul 8, 2019
1 parent 6fbc0f4 commit f693a6d
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 20 deletions.
4 changes: 3 additions & 1 deletion src/main/drivers/adc.h
Expand Up @@ -77,8 +77,10 @@ typedef struct adcOperatingConfig_s {
ioTag_t tag;
#ifdef STM32H7
ADCDevice adcDevice; // ADCDEV_x for this input
#endif
uint32_t adcChannel; // ADCy_INxx channel ID for this input
#else
uint8_t adcChannel; // ADCy_INxx channel number for this input
#endif
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
bool enabled;
uint8_t sampleTime;
Expand Down
46 changes: 27 additions & 19 deletions src/main/drivers/adc_stm32h7xx.c
Expand Up @@ -42,22 +42,6 @@

#include "pg/adc.h"

// Copied from stm32f7xx_ll_adc.h

#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). */

// Calibration data address for STM32H743.
// Source: STM32H743xI Datasheet DS12110 Rev 5
// p.104 Table.28 Internal reference voltage calibration values
// p.170 Table 91. Temperature sensor calibration values
// Note that values are in 16-bit resolution, unlike 12-bit used in F-Series.
#define VREFINT_CAL_ADDR ((uint16_t*) (0x1FF1E860))
#define TEMPSENSOR_CAL1_ADDR ((uint16_t*) (0x1FF1E820))
#define TEMPSENSOR_CAL2_ADDR ((uint16_t*) (0x1FF1E840))

// XXX Instance and DMA stream defs will be gone in unified target

#ifndef ADC1_INSTANCE
Expand Down Expand Up @@ -153,6 +137,31 @@ const adcTagMap_t adcTagMap[] = {
#endif
};

// Translate rank number x to ADC_REGULAR_RANK_x (Note that array index is 0-origin)

#define RANK(n) ADC_REGULAR_RANK_ ## n

static uint32_t adcRegularRankMap[] = {
RANK(1),
RANK(2),
RANK(3),
RANK(4),
RANK(5),
RANK(6),
RANK(7),
RANK(8),
RANK(9),
RANK(10),
RANK(11),
RANK(12),
RANK(13),
RANK(14),
RANK(15),
RANK(16),
};

#undef RANK

static void Error_Handler(void) { while (1) { } }

// Note on sampling time.
Expand Down Expand Up @@ -185,7 +194,6 @@ void adcInitDevice(adcDevice_t *adcdev, int channelCount)
hadc->Init.ConversionDataManagement = ADC_CONVERSIONDATA_DMA_CIRCULAR;
hadc->Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
hadc->Init.OversamplingMode = DISABLE;
hadc->Init.BoostMode = ENABLE; // Enable Boost mode as ADC clock frequency is bigger than 20 MHz */

// Initialize this ADC peripheral

Expand Down Expand Up @@ -338,7 +346,7 @@ void adcInit(const adcConfig_t *config)

// Configure channels

int rank = 1;
int rank = 0;

for (int adcChan = 0; adcChan < ADC_CHANNEL_COUNT; adcChan++) {

Expand All @@ -355,7 +363,7 @@ void adcInit(const adcConfig_t *config)
ADC_ChannelConfTypeDef sConfig;

sConfig.Channel = adcOperatingConfig[adcChan].adcChannel; /* Sampled channel number */
sConfig.Rank = rank++; /* Rank of sampled channel number ADCx_CHANNEL */
sConfig.Rank = adcRegularRankMap[rank++]; /* Rank of sampled channel number ADCx_CHANNEL */
sConfig.SamplingTime = ADC_SAMPLETIME_387CYCLES_5; /* Sampling time (number of clock cycles unit) */
sConfig.SingleDiff = ADC_SINGLE_ENDED; /* Single-ended input channel */
sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
Expand Down

0 comments on commit f693a6d

Please sign in to comment.