48 #define CR_CLEAR_MASK ((uint32_t)0x00000FFE) 51 #define DUAL_SWTRIG_SET ((uint32_t)0x00000003) 52 #define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) 55 #define DHR12R1_OFFSET ((uint32_t)0x00000008) 56 #define DHR12R2_OFFSET ((uint32_t)0x00000014) 57 #define DHR12RD_OFFSET ((uint32_t)0x00000020) 60 #define DOR_OFFSET ((uint32_t)0x0000002C) 119 uint32_t tmpreg1 = 0, tmpreg2 = 0;
139 tmpreg1 |= tmpreg2 << DAC_Channel;
189 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) 213 DAC->CR |= (DAC_IT << DAC_Channel);
218 DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel));
323 DAC->CR |= DAC_Wave << DAC_Channel;
328 DAC->CR &= ~(DAC_Wave << DAC_Channel);
344 __IO uint32_t tmp = 0;
354 *(
__IO uint32_t *) tmp = Data;
369 __IO uint32_t tmp = 0;
379 *(
__IO uint32_t *)tmp = Data;
398 uint32_t data = 0, tmp = 0;
408 data = ((uint32_t)Data2 << 8) | Data1;
412 data = ((uint32_t)Data2 << 16) | Data1;
419 *(
__IO uint32_t *)tmp = data;
432 __IO uint32_t tmp = 0;
438 tmp +=
DOR_OFFSET + ((uint32_t)DAC_Channel >> 2);
441 return (uint16_t) (*(
__IO uint32_t*) tmp);
444 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) 464 if ((
DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)
RESET)
496 DAC->SR = (DAC_FLAG << DAC_Channel);
513 uint32_t enablestatus = 0;
520 enablestatus = (
DAC->CR & (DAC_IT << DAC_Channel)) ;
523 if (((
DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)
RESET) && enablestatus)
555 DAC->SR = (DAC_IT << DAC_Channel);
void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
Set the specified data holding register value for dual channel DAC.
void DAC_DeInit(void)
Deinitializes the DAC peripheral registers to their default reset values.
void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)
Enables or disables the specified DAC interrupts.
FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG)
Checks whether the specified DAC flag is set or not.
void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
Enables or disables the selected DAC channel wave generation.
uint32_t DAC_OutputBuffer
#define DAC_OutputBuffer_Enable
void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
Enables or disables simultaneously the two DAC channels software triggers.
#define DAC_SWTRIGR_SWTRIG1
#define IS_DAC_FLAG(FLAG)
#define IS_DAC_OUTPUT_BUFFER_STATE(STATE)
void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState)
Enables or disables the specified DAC channel.
void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG)
Clears the DAC channel's pending flags.
void assert_param(int val)
#define IS_DAC_WAVE(WAVE)
#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE)
#define IS_FUNCTIONAL_STATE(STATE)
#define RCC_APB1Periph_DAC
This file contains all the functions prototypes for the DAC firmware library.
void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef *DAC_InitStruct)
Initializes the DAC peripheral according to the specified parameters in the DAC_InitStruct.
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState)
Enables or disables the selected DAC channel software trigger.
void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data)
Set the specified data holding register value for DAC channel1.
ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT)
Checks whether the specified DAC interrupt has occurred or not.
#define DAC_LFSRUnmask_Bit0
This file contains all the functions prototypes for the RCC firmware library.
void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data)
Set the specified data holding register value for DAC channel2.
uint32_t DAC_LFSRUnmask_TriangleAmplitude
#define DUAL_SWTRIG_RESET
#define IS_DAC_ALIGN(ALIGN)
#define IS_DAC_GENERATE_WAVE(WAVE)
void DAC_StructInit(DAC_InitTypeDef *DAC_InitStruct)
Fills each DAC_InitStruct member with its default value.
#define IS_DAC_DATA(DATA)
DAC Init structure definition.
#define IS_DAC_CHANNEL(CHANNEL)
uint32_t DAC_WaveGeneration
void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT)
Clears the DAC channel's interrupt pending bits.
#define IS_DAC_TRIGGER(TRIGGER)
uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel)
Returns the last data output value of the selected DAC channel.
#define DAC_WaveGeneration_None
void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState)
Enables or disables the specified DAC channel DMA request.