Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / lib / main / STM32F1 / Drivers / STM32F10x_StdPeriph_Driver / src / stm32f10x_dac.c
blob1cfc71ded26a8189cc531005282693f75cd4e0fd
1 /**
2 ******************************************************************************
3 * @file stm32f10x_dac.c
4 * @author MCD Application Team
5 * @version V3.5.0
6 * @date 11-March-2011
7 * @brief This file provides all the DAC firmware functions.
8 ******************************************************************************
9 * @attention
11 * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
12 * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
13 * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
14 * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
15 * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
16 * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
18 * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
19 ******************************************************************************
22 /* Includes ------------------------------------------------------------------*/
23 #include "stm32f10x_dac.h"
24 #include "stm32f10x_rcc.h"
26 /** @addtogroup STM32F10x_StdPeriph_Driver
27 * @{
30 /** @defgroup DAC
31 * @brief DAC driver modules
32 * @{
33 */
35 /** @defgroup DAC_Private_TypesDefinitions
36 * @{
39 /**
40 * @}
43 /** @defgroup DAC_Private_Defines
44 * @{
47 /* CR register Mask */
48 #define CR_CLEAR_MASK ((uint32_t)0x00000FFE)
50 /* DAC Dual Channels SWTRIG masks */
51 #define DUAL_SWTRIG_SET ((uint32_t)0x00000003)
52 #define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC)
54 /* DHR registers offsets */
55 #define DHR12R1_OFFSET ((uint32_t)0x00000008)
56 #define DHR12R2_OFFSET ((uint32_t)0x00000014)
57 #define DHR12RD_OFFSET ((uint32_t)0x00000020)
59 /* DOR register offset */
60 #define DOR_OFFSET ((uint32_t)0x0000002C)
61 /**
62 * @}
65 /** @defgroup DAC_Private_Macros
66 * @{
69 /**
70 * @}
73 /** @defgroup DAC_Private_Variables
74 * @{
77 /**
78 * @}
81 /** @defgroup DAC_Private_FunctionPrototypes
82 * @{
85 /**
86 * @}
89 /** @defgroup DAC_Private_Functions
90 * @{
93 /**
94 * @brief Deinitializes the DAC peripheral registers to their default reset values.
95 * @param None
96 * @retval None
98 void DAC_DeInit(void)
100 /* Enable DAC reset state */
101 RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
102 /* Release DAC from reset state */
103 RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
107 * @brief Initializes the DAC peripheral according to the specified
108 * parameters in the DAC_InitStruct.
109 * @param DAC_Channel: the selected DAC channel.
110 * This parameter can be one of the following values:
111 * @arg DAC_Channel_1: DAC Channel1 selected
112 * @arg DAC_Channel_2: DAC Channel2 selected
113 * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
114 * contains the configuration information for the specified DAC channel.
115 * @retval None
117 void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
119 uint32_t tmpreg1 = 0, tmpreg2 = 0;
120 /* Check the DAC parameters */
121 assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
122 assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
123 assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
124 assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
125 /*---------------------------- DAC CR Configuration --------------------------*/
126 /* Get the DAC CR value */
127 tmpreg1 = DAC->CR;
128 /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
129 tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel);
130 /* Configure for the selected DAC channel: buffer output, trigger, wave generation,
131 mask/amplitude for wave generation */
132 /* Set TSELx and TENx bits according to DAC_Trigger value */
133 /* Set WAVEx bits according to DAC_WaveGeneration value */
134 /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
135 /* Set BOFFx bit according to DAC_OutputBuffer value */
136 tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
137 DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer);
138 /* Calculate CR register value depending on DAC_Channel */
139 tmpreg1 |= tmpreg2 << DAC_Channel;
140 /* Write to DAC CR */
141 DAC->CR = tmpreg1;
145 * @brief Fills each DAC_InitStruct member with its default value.
146 * @param DAC_InitStruct : pointer to a DAC_InitTypeDef structure which will
147 * be initialized.
148 * @retval None
150 void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
152 /*--------------- Reset DAC init structure parameters values -----------------*/
153 /* Initialize the DAC_Trigger member */
154 DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
155 /* Initialize the DAC_WaveGeneration member */
156 DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
157 /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
158 DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
159 /* Initialize the DAC_OutputBuffer member */
160 DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
164 * @brief Enables or disables the specified DAC channel.
165 * @param DAC_Channel: the selected DAC channel.
166 * This parameter can be one of the following values:
167 * @arg DAC_Channel_1: DAC Channel1 selected
168 * @arg DAC_Channel_2: DAC Channel2 selected
169 * @param NewState: new state of the DAC channel.
170 * This parameter can be: ENABLE or DISABLE.
171 * @retval None
173 void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState)
175 /* Check the parameters */
176 assert_param(IS_DAC_CHANNEL(DAC_Channel));
177 assert_param(IS_FUNCTIONAL_STATE(NewState));
178 if (NewState != DISABLE)
180 /* Enable the selected DAC channel */
181 DAC->CR |= (DAC_CR_EN1 << DAC_Channel);
183 else
185 /* Disable the selected DAC channel */
186 DAC->CR &= ~(DAC_CR_EN1 << DAC_Channel);
189 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
191 * @brief Enables or disables the specified DAC interrupts.
192 * @param DAC_Channel: the selected DAC channel.
193 * This parameter can be one of the following values:
194 * @arg DAC_Channel_1: DAC Channel1 selected
195 * @arg DAC_Channel_2: DAC Channel2 selected
196 * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled.
197 * This parameter can be the following values:
198 * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
199 * @param NewState: new state of the specified DAC interrupts.
200 * This parameter can be: ENABLE or DISABLE.
201 * @retval None
203 void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)
205 /* Check the parameters */
206 assert_param(IS_DAC_CHANNEL(DAC_Channel));
207 assert_param(IS_FUNCTIONAL_STATE(NewState));
208 assert_param(IS_DAC_IT(DAC_IT));
210 if (NewState != DISABLE)
212 /* Enable the selected DAC interrupts */
213 DAC->CR |= (DAC_IT << DAC_Channel);
215 else
217 /* Disable the selected DAC interrupts */
218 DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel));
221 #endif
224 * @brief Enables or disables the specified DAC channel DMA request.
225 * @param DAC_Channel: the selected DAC channel.
226 * This parameter can be one of the following values:
227 * @arg DAC_Channel_1: DAC Channel1 selected
228 * @arg DAC_Channel_2: DAC Channel2 selected
229 * @param NewState: new state of the selected DAC channel DMA request.
230 * This parameter can be: ENABLE or DISABLE.
231 * @retval None
233 void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState)
235 /* Check the parameters */
236 assert_param(IS_DAC_CHANNEL(DAC_Channel));
237 assert_param(IS_FUNCTIONAL_STATE(NewState));
238 if (NewState != DISABLE)
240 /* Enable the selected DAC channel DMA request */
241 DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel);
243 else
245 /* Disable the selected DAC channel DMA request */
246 DAC->CR &= ~(DAC_CR_DMAEN1 << DAC_Channel);
251 * @brief Enables or disables the selected DAC channel software trigger.
252 * @param DAC_Channel: the selected DAC channel.
253 * This parameter can be one of the following values:
254 * @arg DAC_Channel_1: DAC Channel1 selected
255 * @arg DAC_Channel_2: DAC Channel2 selected
256 * @param NewState: new state of the selected DAC channel software trigger.
257 * This parameter can be: ENABLE or DISABLE.
258 * @retval None
260 void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState)
262 /* Check the parameters */
263 assert_param(IS_DAC_CHANNEL(DAC_Channel));
264 assert_param(IS_FUNCTIONAL_STATE(NewState));
265 if (NewState != DISABLE)
267 /* Enable software trigger for the selected DAC channel */
268 DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4);
270 else
272 /* Disable software trigger for the selected DAC channel */
273 DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4));
278 * @brief Enables or disables simultaneously the two DAC channels software
279 * triggers.
280 * @param NewState: new state of the DAC channels software triggers.
281 * This parameter can be: ENABLE or DISABLE.
282 * @retval None
284 void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
286 /* Check the parameters */
287 assert_param(IS_FUNCTIONAL_STATE(NewState));
288 if (NewState != DISABLE)
290 /* Enable software trigger for both DAC channels */
291 DAC->SWTRIGR |= DUAL_SWTRIG_SET ;
293 else
295 /* Disable software trigger for both DAC channels */
296 DAC->SWTRIGR &= DUAL_SWTRIG_RESET;
301 * @brief Enables or disables the selected DAC channel wave generation.
302 * @param DAC_Channel: the selected DAC channel.
303 * This parameter can be one of the following values:
304 * @arg DAC_Channel_1: DAC Channel1 selected
305 * @arg DAC_Channel_2: DAC Channel2 selected
306 * @param DAC_Wave: Specifies the wave type to enable or disable.
307 * This parameter can be one of the following values:
308 * @arg DAC_Wave_Noise: noise wave generation
309 * @arg DAC_Wave_Triangle: triangle wave generation
310 * @param NewState: new state of the selected DAC channel wave generation.
311 * This parameter can be: ENABLE or DISABLE.
312 * @retval None
314 void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
316 /* Check the parameters */
317 assert_param(IS_DAC_CHANNEL(DAC_Channel));
318 assert_param(IS_DAC_WAVE(DAC_Wave));
319 assert_param(IS_FUNCTIONAL_STATE(NewState));
320 if (NewState != DISABLE)
322 /* Enable the selected wave generation for the selected DAC channel */
323 DAC->CR |= DAC_Wave << DAC_Channel;
325 else
327 /* Disable the selected wave generation for the selected DAC channel */
328 DAC->CR &= ~(DAC_Wave << DAC_Channel);
333 * @brief Set the specified data holding register value for DAC channel1.
334 * @param DAC_Align: Specifies the data alignment for DAC channel1.
335 * This parameter can be one of the following values:
336 * @arg DAC_Align_8b_R: 8bit right data alignment selected
337 * @arg DAC_Align_12b_L: 12bit left data alignment selected
338 * @arg DAC_Align_12b_R: 12bit right data alignment selected
339 * @param Data : Data to be loaded in the selected data holding register.
340 * @retval None
342 void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data)
344 __IO uint32_t tmp = 0;
346 /* Check the parameters */
347 assert_param(IS_DAC_ALIGN(DAC_Align));
348 assert_param(IS_DAC_DATA(Data));
350 tmp = (uint32_t)DAC_BASE;
351 tmp += DHR12R1_OFFSET + DAC_Align;
353 /* Set the DAC channel1 selected data holding register */
354 *(__IO uint32_t *) tmp = Data;
358 * @brief Set the specified data holding register value for DAC channel2.
359 * @param DAC_Align: Specifies the data alignment for DAC channel2.
360 * This parameter can be one of the following values:
361 * @arg DAC_Align_8b_R: 8bit right data alignment selected
362 * @arg DAC_Align_12b_L: 12bit left data alignment selected
363 * @arg DAC_Align_12b_R: 12bit right data alignment selected
364 * @param Data : Data to be loaded in the selected data holding register.
365 * @retval None
367 void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data)
369 __IO uint32_t tmp = 0;
371 /* Check the parameters */
372 assert_param(IS_DAC_ALIGN(DAC_Align));
373 assert_param(IS_DAC_DATA(Data));
375 tmp = (uint32_t)DAC_BASE;
376 tmp += DHR12R2_OFFSET + DAC_Align;
378 /* Set the DAC channel2 selected data holding register */
379 *(__IO uint32_t *)tmp = Data;
383 * @brief Set the specified data holding register value for dual channel
384 * DAC.
385 * @param DAC_Align: Specifies the data alignment for dual channel DAC.
386 * This parameter can be one of the following values:
387 * @arg DAC_Align_8b_R: 8bit right data alignment selected
388 * @arg DAC_Align_12b_L: 12bit left data alignment selected
389 * @arg DAC_Align_12b_R: 12bit right data alignment selected
390 * @param Data2: Data for DAC Channel2 to be loaded in the selected data
391 * holding register.
392 * @param Data1: Data for DAC Channel1 to be loaded in the selected data
393 * holding register.
394 * @retval None
396 void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
398 uint32_t data = 0, tmp = 0;
400 /* Check the parameters */
401 assert_param(IS_DAC_ALIGN(DAC_Align));
402 assert_param(IS_DAC_DATA(Data1));
403 assert_param(IS_DAC_DATA(Data2));
405 /* Calculate and set dual DAC data holding register value */
406 if (DAC_Align == DAC_Align_8b_R)
408 data = ((uint32_t)Data2 << 8) | Data1;
410 else
412 data = ((uint32_t)Data2 << 16) | Data1;
415 tmp = (uint32_t)DAC_BASE;
416 tmp += DHR12RD_OFFSET + DAC_Align;
418 /* Set the dual DAC selected data holding register */
419 *(__IO uint32_t *)tmp = data;
423 * @brief Returns the last data output value of the selected DAC channel.
424 * @param DAC_Channel: the selected DAC channel.
425 * This parameter can be one of the following values:
426 * @arg DAC_Channel_1: DAC Channel1 selected
427 * @arg DAC_Channel_2: DAC Channel2 selected
428 * @retval The selected DAC channel data output value.
430 uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel)
432 __IO uint32_t tmp = 0;
434 /* Check the parameters */
435 assert_param(IS_DAC_CHANNEL(DAC_Channel));
437 tmp = (uint32_t) DAC_BASE ;
438 tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2);
440 /* Returns the DAC channel data output register value */
441 return (uint16_t) (*(__IO uint32_t*) tmp);
444 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
446 * @brief Checks whether the specified DAC flag is set or not.
447 * @param DAC_Channel: thee selected DAC channel.
448 * This parameter can be one of the following values:
449 * @arg DAC_Channel_1: DAC Channel1 selected
450 * @arg DAC_Channel_2: DAC Channel2 selected
451 * @param DAC_FLAG: specifies the flag to check.
452 * This parameter can be only of the following value:
453 * @arg DAC_FLAG_DMAUDR: DMA underrun flag
454 * @retval The new state of DAC_FLAG (SET or RESET).
456 FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG)
458 FlagStatus bitstatus = RESET;
459 /* Check the parameters */
460 assert_param(IS_DAC_CHANNEL(DAC_Channel));
461 assert_param(IS_DAC_FLAG(DAC_FLAG));
463 /* Check the status of the specified DAC flag */
464 if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET)
466 /* DAC_FLAG is set */
467 bitstatus = SET;
469 else
471 /* DAC_FLAG is reset */
472 bitstatus = RESET;
474 /* Return the DAC_FLAG status */
475 return bitstatus;
479 * @brief Clears the DAC channelx's pending flags.
480 * @param DAC_Channel: the selected DAC channel.
481 * This parameter can be one of the following values:
482 * @arg DAC_Channel_1: DAC Channel1 selected
483 * @arg DAC_Channel_2: DAC Channel2 selected
484 * @param DAC_FLAG: specifies the flag to clear.
485 * This parameter can be of the following value:
486 * @arg DAC_FLAG_DMAUDR: DMA underrun flag
487 * @retval None
489 void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG)
491 /* Check the parameters */
492 assert_param(IS_DAC_CHANNEL(DAC_Channel));
493 assert_param(IS_DAC_FLAG(DAC_FLAG));
495 /* Clear the selected DAC flags */
496 DAC->SR = (DAC_FLAG << DAC_Channel);
500 * @brief Checks whether the specified DAC interrupt has occurred or not.
501 * @param DAC_Channel: the selected DAC channel.
502 * This parameter can be one of the following values:
503 * @arg DAC_Channel_1: DAC Channel1 selected
504 * @arg DAC_Channel_2: DAC Channel2 selected
505 * @param DAC_IT: specifies the DAC interrupt source to check.
506 * This parameter can be the following values:
507 * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
508 * @retval The new state of DAC_IT (SET or RESET).
510 ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT)
512 ITStatus bitstatus = RESET;
513 uint32_t enablestatus = 0;
515 /* Check the parameters */
516 assert_param(IS_DAC_CHANNEL(DAC_Channel));
517 assert_param(IS_DAC_IT(DAC_IT));
519 /* Get the DAC_IT enable bit status */
520 enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ;
522 /* Check the status of the specified DAC interrupt */
523 if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus)
525 /* DAC_IT is set */
526 bitstatus = SET;
528 else
530 /* DAC_IT is reset */
531 bitstatus = RESET;
533 /* Return the DAC_IT status */
534 return bitstatus;
538 * @brief Clears the DAC channelx's interrupt pending bits.
539 * @param DAC_Channel: the selected DAC channel.
540 * This parameter can be one of the following values:
541 * @arg DAC_Channel_1: DAC Channel1 selected
542 * @arg DAC_Channel_2: DAC Channel2 selected
543 * @param DAC_IT: specifies the DAC interrupt pending bit to clear.
544 * This parameter can be the following values:
545 * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
546 * @retval None
548 void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT)
550 /* Check the parameters */
551 assert_param(IS_DAC_CHANNEL(DAC_Channel));
552 assert_param(IS_DAC_IT(DAC_IT));
554 /* Clear the selected DAC interrupt pending bits */
555 DAC->SR = (DAC_IT << DAC_Channel);
557 #endif
560 * @}
564 * @}
568 * @}
571 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/