107 #include "stm32f4xx_rcc.h" 122 #define CR1_DISCNUM_RESET ((uint32_t)0xFFFF1FFF) 125 #define CR1_AWDCH_RESET ((uint32_t)0xFFFFFFE0) 128 #define CR1_AWDMode_RESET ((uint32_t)0xFF3FFDFF) 131 #define CR1_CLEAR_MASK ((uint32_t)0xFCFFFEFF) 134 #define CR2_EXTEN_RESET ((uint32_t)0xCFFFFFFF) 137 #define CR2_JEXTEN_RESET ((uint32_t)0xFFCFFFFF) 140 #define CR2_JEXTSEL_RESET ((uint32_t)0xFFF0FFFF) 143 #define CR2_CLEAR_MASK ((uint32_t)0xC0FFF7FD) 146 #define SQR3_SQ_SET ((uint32_t)0x0000001F) 147 #define SQR2_SQ_SET ((uint32_t)0x0000001F) 148 #define SQR1_SQ_SET ((uint32_t)0x0000001F) 151 #define SQR1_L_RESET ((uint32_t)0xFF0FFFFF) 154 #define JSQR_JSQ_SET ((uint32_t)0x0000001F) 157 #define JSQR_JL_SET ((uint32_t)0x00300000) 158 #define JSQR_JL_RESET ((uint32_t)0xFFCFFFFF) 161 #define SMPR1_SMP_SET ((uint32_t)0x00000007) 162 #define SMPR2_SMP_SET ((uint32_t)0x00000007) 165 #define JDR_OFFSET ((uint8_t)0x28) 168 #define CDR_ADDRESS ((uint32_t)0x40012308) 171 #define CR_CLEAR_MASK ((uint32_t)0xFFFC30E0) 237 uint32_t tmpreg1 = 0;
260 ADC_InitStruct->ADC_Resolution);
285 tmpreg1 = ADCx->
SQR1;
293 tmpreg1 |= ((uint32_t)tmpreg2 << 20);
296 ADCx->
SQR1 = tmpreg1;
343 uint32_t tmpreg1 = 0;
362 tmpreg1 |= (uint32_t)(ADC_CommonInitStruct->
ADC_Mode |
469 tmpreg |= ADC_AnalogWatchdog;
485 uint16_t LowThreshold)
493 ADCx->
HTR = HighThreshold;
496 ADCx->
LTR = LowThreshold;
539 tmpreg |= ADC_Channel;
713 uint32_t tmpreg1 = 0, tmpreg2 = 0;
724 tmpreg1 = ADCx->
SMPR1;
733 tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10));
739 ADCx->
SMPR1 = tmpreg1;
744 tmpreg1 = ADCx->
SMPR2;
753 tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
759 ADCx->
SMPR2 = tmpreg1;
765 tmpreg1 = ADCx->
SQR3;
774 tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1));
780 ADCx->
SQR3 = tmpreg1;
786 tmpreg1 = ADCx->
SQR2;
795 tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7));
801 ADCx->
SQR2 = tmpreg1;
807 tmpreg1 = ADCx->
SQR1;
816 tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13));
822 ADCx->
SQR1 = tmpreg1;
928 uint32_t tmpreg1 = 0;
929 uint32_t tmpreg2 = 0;
942 tmpreg2 = Number - 1;
943 tmpreg1 |= tmpreg2 << 13;
987 return (uint16_t) ADCx->
DR;
1188 uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0;
1198 tmpreg1 = ADCx->
SMPR1;
1202 tmpreg1 &= ~tmpreg2;
1204 tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10));
1208 ADCx->
SMPR1 = tmpreg1;
1213 tmpreg1 = ADCx->
SMPR2;
1217 tmpreg1 &= ~tmpreg2;
1219 tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
1223 ADCx->
SMPR2 = tmpreg1;
1227 tmpreg1 = ADCx->
JSQR;
1231 tmpreg2 =
JSQR_JSQ_SET << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1)));
1233 tmpreg1 &= ~tmpreg2;
1235 tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1)));
1239 ADCx->
JSQR = tmpreg1;
1251 uint32_t tmpreg1 = 0;
1252 uint32_t tmpreg2 = 0;
1258 tmpreg1 = ADCx->
JSQR;
1264 tmpreg2 = Length - 1;
1265 tmpreg1 |= tmpreg2 << 20;
1268 ADCx->
JSQR = tmpreg1;
1286 __IO uint32_t tmp = 0;
1292 tmp = (uint32_t)ADCx;
1293 tmp += ADC_InjectedChannel;
1296 *(
__IO uint32_t *) tmp = (uint32_t)Offset;
1324 uint32_t tmpreg = 0;
1336 tmpreg |= ADC_ExternalTrigInjecConv;
1358 uint32_t tmpreg = 0;
1367 tmpreg |= ADC_ExternalTrigInjecConvEdge;
1475 __IO uint32_t tmp = 0;
1481 tmp = (uint32_t)ADCx;
1485 return (uint16_t) (*(
__IO uint32_t*) tmp);
1582 uint32_t itmask = 0;
1589 itmask = (uint8_t)ADC_IT;
1590 itmask = (uint32_t)0x01 << itmask;
1595 ADCx->
CR1 |= itmask;
1600 ADCx->
CR1 &= (~(uint32_t)itmask);
1625 if ((ADCx->
SR & ADC_FLAG) != (uint8_t)
RESET)
1659 ADCx->
SR = ~(uint32_t)ADC_FLAG;
1676 uint32_t itmask = 0, enablestatus = 0;
1683 itmask = ADC_IT >> 8;
1686 enablestatus = (ADCx->
CR1 & ((uint32_t)0x01 << (uint8_t)ADC_IT)) ;
1689 if (((ADCx->
SR & itmask) != (uint32_t)
RESET) && enablestatus)
1721 itmask = (uint8_t)(ADC_IT >> 8);
1723 ADCx->
SR = ~(uint32_t)itmask;
#define IS_ADC_INJECTED_RANK(RANK)
void ADC_AnalogWatchdogCmd(ADC_TypeDef *ADCx, uint32_t ADC_AnalogWatchdog)
Enables or disables the analog watchdog on single/all regular or injected channels.
#define IS_ADC_MODE(MODE)
void ADC_DMARequestAfterLastTransferCmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the ADC DMA request after last transfer (Single-ADC mode)
FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef *ADCx)
Gets the selected ADC Software start injected conversion Status.
#define IS_ADC_INJECTED_CHANNEL(CHANNEL)
uint32_t ADC_ExternalTrigConv
#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG)
#define IS_ADC_EXT_TRIG_EDGE(EDGE)
#define IS_ADC_EXT_INJEC_TRIG_EDGE(EDGE)
void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef *ADCx, uint32_t ADC_ExternalTrigInjecConv)
Configures the ADCx external trigger for injected channels conversion.
void ADC_InjectedSequencerLengthConfig(ADC_TypeDef *ADCx, uint8_t Length)
Configures the sequencer length for injected channels.
#define CR2_JEXTSEL_RESET
ADC Init structure definition.
#define ADC_TwoSamplingDelay_5Cycles
Analog to Digital Converter.
#define ADC_Mode_Independent
#define ADC_DMAAccessMode_Disabled
FunctionalState ADC_ContinuousConvMode
void ADC_Cmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the specified ADC peripheral.
#define IS_ADC_DMA_ACCESS_MODE(MODE)
void ADC_EOCOnEachRegularChannelCmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the EOC on each regular channel conversion.
#define IS_ADC_CHANNEL(CHANNEL)
#define IS_ADC_GET_FLAG(FLAG)
#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER)
#define IS_ADC_REGULAR_RANK(RANK)
void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef *ADCx, uint16_t HighThreshold, uint16_t LowThreshold)
Configures the high and low thresholds of the analog watchdog.
void ADC_DiscModeCmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the discontinuous mode on regular group channel for the specified ADC...
void ADC_InjectedDiscModeCmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the discontinuous mode for injected group channel for the specified ADC...
void assert_param(int val)
void ADC_DiscModeChannelCountConfig(ADC_TypeDef *ADCx, uint8_t Number)
Configures the discontinuous mode for the selected ADC regular group channel.
void ADC_CommonStructInit(ADC_CommonInitTypeDef *ADC_CommonInitStruct)
Fills each ADC_CommonInitStruct member with its default value.
uint32_t ADC_GetMultiModeConversionValue(void)
Returns the last ADC1, ADC2 and ADC3 regular conversions results data in the selected multi mode...
#define IS_ADC_RESOLUTION(RESOLUTION)
void ADC_ITConfig(ADC_TypeDef *ADCx, uint16_t ADC_IT, FunctionalState NewState)
Enables or disables the specified ADC interrupts.
#define IS_ADC_THRESHOLD(THRESHOLD)
#define ADC_Prescaler_Div2
#define IS_FUNCTIONAL_STATE(STATE)
void ADC_SoftwareStartConv(ADC_TypeDef *ADCx)
Enables the selected ADC software start conversion of the regular channels.
void ADC_ClearITPendingBit(ADC_TypeDef *ADCx, uint16_t ADC_IT)
Clears the ADCx's interrupt pending bits.
This file contains all the functions prototypes for the ADC firmware library.
FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef *ADCx)
Gets the selected ADC Software start regular conversion Status.
ADC Common Init structure definition.
void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef *ADCx, uint8_t ADC_Channel)
Configures the analog watchdog guarded single channel.
void ADC_DMACmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the specified ADC DMA request.
#define CR1_AWDMode_RESET
void ADC_SoftwareStartInjectedConv(ADC_TypeDef *ADCx)
Enables the selected ADC software start conversion of the injected channels.
#define ADC_ExternalTrigConv_T1_CC1
#define IS_ADC_PRESCALER(PRESCALER)
#define IS_ADC_CLEAR_FLAG(FLAG)
FlagStatus ADC_GetFlagStatus(ADC_TypeDef *ADCx, uint8_t ADC_FLAG)
Checks whether the specified ADC flag is set or not.
#define IS_ADC_SAMPLE_TIME(TIME)
uint8_t ADC_NbrOfConversion
void ADC_InjectedChannelConfig(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime)
Configures for the selected ADC injected channel its corresponding rank in the sequencer and its samp...
uint32_t ADC_TwoSamplingDelay
#define IS_ADC_EXT_INJEC_TRIG(INJTRIG)
void ADC_DeInit(void)
Deinitializes all ADCs peripherals registers to their default reset values.
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
#define IS_ADC_OFFSET(OFFSET)
#define ADC_Resolution_12b
void ADC_StructInit(ADC_InitTypeDef *ADC_InitStruct)
Fills each ADC_InitStruct member with its default value.
#define ADC_ExternalTrigConvEdge_None
void ADC_MultiModeDMARequestAfterLastTransferCmd(FunctionalState NewState)
Enables or disables the ADC DMA request after last transfer in multi ADC mode.
#define IS_ADC_INJECTED_LENGTH(LENGTH)
FunctionalState ADC_ScanConvMode
uint32_t ADC_DMAAccessMode
ITStatus ADC_GetITStatus(ADC_TypeDef *ADCx, uint16_t ADC_IT)
Checks whether the specified ADC interrupt has occurred or not.
void ADC_SetInjectedOffset(ADC_TypeDef *ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset)
Set the injected channels conversion value offset.
void ADC_Init(ADC_TypeDef *ADCx, ADC_InitTypeDef *ADC_InitStruct)
Initializes the ADCx peripheral according to the specified parameters in the ADC_InitStruct.
void ADC_ClearFlag(ADC_TypeDef *ADCx, uint8_t ADC_FLAG)
Clears the ADCx's pending flags.
void ADC_ContinuousModeCmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the ADC continuous conversion mode.
#define IS_ADC_DATA_ALIGN(ALIGN)
uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef *ADCx, uint8_t ADC_InjectedChannel)
Returns the ADC injected channel conversion result.
#define RCC_APB2Periph_ADC
#define IS_ADC_ALL_PERIPH(PERIPH)
void ADC_TempSensorVrefintCmd(FunctionalState NewState)
Enables or disables the temperature sensor and Vrefint channels.
void ADC_RegularChannelConfig(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime)
Configures for the selected ADC regular channel its corresponding rank in the sequencer and its sampl...
void ADC_ExternalTrigInjectedConvEdgeConfig(ADC_TypeDef *ADCx, uint32_t ADC_ExternalTrigInjecConvEdge)
Configures the ADCx external trigger edge for injected channels conversion.
#define ADC_DataAlign_Right
uint32_t ADC_ExternalTrigConvEdge
uint16_t ADC_GetConversionValue(ADC_TypeDef *ADCx)
Returns the last ADCx conversion result data for regular channel.
void ADC_AutoInjectedConvCmd(ADC_TypeDef *ADCx, FunctionalState NewState)
Enables or disables the selected ADC automatic injected group conversion after regular one...
#define IS_ADC_REGULAR_LENGTH(LENGTH)
void ADC_CommonInit(ADC_CommonInitTypeDef *ADC_CommonInitStruct)
Initializes the ADCs peripherals according to the specified parameters in the ADC_CommonInitStruct.
#define CR1_DISCNUM_RESET
#define IS_ADC_SAMPLING_DELAY(DELAY)
void ADC_VBATCmd(FunctionalState NewState)
Enables or disables the VBAT (Voltage Battery) channel.
#define IS_ADC_EXT_TRIG(REGTRIG)