stm32f30x_dac.c
Go to the documentation of this file.
1 
119 /* Includes ------------------------------------------------------------------*/
120 #include "stm32f30x_dac.h"
121 #include "stm32f30x_rcc.h"
122 
132 /* Private typedef -----------------------------------------------------------*/
133 /* Private define ------------------------------------------------------------*/
134 
135 /* CR register Mask */
136 #define CR_CLEAR_MASK ((uint32_t)0x00000FFE)
137 
138 /* DAC Dual Channels SWTRIG masks */
139 #define DUAL_SWTRIG_SET ((uint32_t)0x00000003)
140 #define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC)
141 
142 /* DHR registers offsets */
143 #define DHR12R1_OFFSET ((uint32_t)0x00000008)
144 #define DHR12R2_OFFSET ((uint32_t)0x00000014)
145 #define DHR12RD_OFFSET ((uint32_t)0x00000020)
146 
147 /* DOR register offset */
148 #define DOR_OFFSET ((uint32_t)0x0000002C)
149 
150 /* Private macro -------------------------------------------------------------*/
151 /* Private variables ---------------------------------------------------------*/
152 /* Private function prototypes -----------------------------------------------*/
153 /* Private functions ---------------------------------------------------------*/
154 
177 {
178  /* Check the parameters */
180 
181  if (DACx == DAC1)
182  {
183  /* Enable DAC1 reset state */
185  /* Release DAC1 from reset state */
187  }
188  else
189  {
190  /* Enable DAC2 reset state */
192  /* Release DAC2 from reset state */
194  }
195 }
196 
209 void DAC_Init(DAC_TypeDef* DACx, uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
210 {
211  uint32_t tmpreg1 = 0, tmpreg2 = 0;
212 
213  /* Check the DAC parameters */
215  assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
219 
220 /*---------------------------- DAC CR Configuration --------------------------*/
221  /* Get the DAC CR value */
222  tmpreg1 = DACx->CR;
223  /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
224  tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel);
225  /* Configure for the selected DAC channel: buffer output, trigger, wave generation,
226  mask/amplitude for wave generation */
227 
228  /* Set TSELx and TENx bits according to DAC_Trigger value */
229  /* Set WAVEx bits according to DAC_WaveGeneration value */
230  /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
231  /* Set BOFFx OUTENx bit according to DAC_Buffer_Switch value */
232  tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
233  DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_Buffer_Switch);
234 
235  /* Calculate CR register value depending on DAC_Channel */
236  tmpreg1 |= tmpreg2 << DAC_Channel;
237  /* Write to DAC CR */
238  DACx->CR = tmpreg1;
239 }
240 
247 void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
248 {
249 /*--------------- Reset DAC init structure parameters values -----------------*/
250  /* Initialize the DAC_Trigger member */
251  DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
252  /* Initialize the DAC_WaveGeneration member */
254  /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
256  /* Initialize the DAC_Buffer_Switch member */
257  DAC_InitStruct->DAC_Buffer_Switch = DAC_BufferSwitch_Enable;
258 }
259 
273 void DAC_Cmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState)
274 {
275  /* Check the parameters */
277  assert_param(IS_DAC_CHANNEL(DAC_Channel));
279 
280  if (NewState != DISABLE)
281  {
282  /* Enable the selected DAC channel */
283  DACx->CR |= (DAC_CR_EN1 << DAC_Channel);
284  }
285  else
286  {
287  /* Disable the selected DAC channel */
288  DACx->CR &= (~(DAC_CR_EN1 << DAC_Channel));
289  }
290 }
291 
303 void DAC_SoftwareTriggerCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState)
304 {
305  /* Check the parameters */
307  assert_param(IS_DAC_CHANNEL(DAC_Channel));
309 
310  if (NewState != DISABLE)
311  {
312  /* Enable software trigger for the selected DAC channel */
313  DACx->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4);
314  }
315  else
316  {
317  /* Disable software trigger for the selected DAC channel */
318  DACx->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4));
319  }
320 }
321 
332 {
333  /* Check the parameters */
336 
337  if (NewState != DISABLE)
338  {
339  /* Enable software trigger for both DAC channels */
340  DACx->SWTRIGR |= DUAL_SWTRIG_SET;
341  }
342  else
343  {
344  /* Disable software trigger for both DAC channels */
345  DACx->SWTRIGR &= DUAL_SWTRIG_RESET;
346  }
347 }
348 
366 void DAC_WaveGenerationCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
367 {
368  /* Check the parameters */
370  assert_param(IS_DAC_CHANNEL(DAC_Channel));
371  assert_param(IS_DAC_WAVE(DAC_Wave));
373 
374  if (NewState != DISABLE)
375  {
376  /* Enable the selected wave generation for the selected DAC channel */
377  DACx->CR |= DAC_Wave << DAC_Channel;
378  }
379  else
380  {
381  /* Disable the selected wave generation for the selected DAC channel */
382  DACx->CR &= ~(DAC_Wave << DAC_Channel);
383  }
384 }
385 
397 void DAC_SetChannel1Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data)
398 {
399  __IO uint32_t tmp = 0;
400 
401  /* Check the parameters */
403  assert_param(IS_DAC_ALIGN(DAC_Align));
404  assert_param(IS_DAC_DATA(Data));
405 
406  tmp = (uint32_t)DACx;
407  tmp += DHR12R1_OFFSET + DAC_Align;
408 
409  /* Set the DAC channel1 selected data holding register */
410  *(__IO uint32_t *) tmp = Data;
411 }
412 
425 void DAC_SetChannel2Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data)
426 {
427  __IO uint32_t tmp = 0;
428 
429  /* Check the parameters */
431  assert_param(IS_DAC_ALIGN(DAC_Align));
432  assert_param(IS_DAC_DATA(Data));
433 
434  tmp = (uint32_t)DACx;
435  tmp += DHR12R2_OFFSET + DAC_Align;
436 
437  /* Set the DAC channel2 selected data holding register */
438  *(__IO uint32_t *)tmp = Data;
439 }
440 
458 void DAC_SetDualChannelData(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
459 {
460  uint32_t data = 0, tmp = 0;
461 
462  /* Check the parameters */
464  assert_param(IS_DAC_ALIGN(DAC_Align));
465  assert_param(IS_DAC_DATA(Data1));
466  assert_param(IS_DAC_DATA(Data2));
467 
468  /* Calculate and set dual DAC data holding register value */
469  if (DAC_Align == DAC_Align_8b_R)
470  {
471  data = ((uint32_t)Data2 << 8) | Data1;
472  }
473  else
474  {
475  data = ((uint32_t)Data2 << 16) | Data1;
476  }
477 
478  tmp = (uint32_t)DACx;
479  tmp += DHR12RD_OFFSET + DAC_Align;
480 
481  /* Set the dual DAC selected data holding register */
482  *(__IO uint32_t *)tmp = data;
483 }
484 
494 uint16_t DAC_GetDataOutputValue(DAC_TypeDef* DACx, uint32_t DAC_Channel)
495 {
496  __IO uint32_t tmp = 0;
497 
498  /* Check the parameters */
500  assert_param(IS_DAC_CHANNEL(DAC_Channel));
501 
502  tmp = (uint32_t) DACx;
503  tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2);
504 
505  /* Returns the DAC channel data output register value */
506  return (uint16_t) (*(__IO uint32_t*) tmp);
507 }
508 
540 void DAC_DMACmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState)
541 {
542  /* Check the parameters */
544  assert_param(IS_DAC_CHANNEL(DAC_Channel));
546 
547  if (NewState != DISABLE)
548  {
549  /* Enable the selected DAC channel DMA request */
550  DACx->CR |= (DAC_CR_DMAEN1 << DAC_Channel);
551  }
552  else
553  {
554  /* Disable the selected DAC channel DMA request */
555  DACx->CR &= (~(DAC_CR_DMAEN1 << DAC_Channel));
556  }
557 }
558 
591 void DAC_ITConfig(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)
592 {
593  /* Check the parameters */
595  assert_param(IS_DAC_CHANNEL(DAC_Channel));
597  assert_param(IS_DAC_IT(DAC_IT));
598 
599  if (NewState != DISABLE)
600  {
601  /* Enable the selected DAC interrupts */
602  DACx->CR |= (DAC_IT << DAC_Channel);
603  }
604  else
605  {
606  /* Disable the selected DAC interrupts */
607  DACx->CR &= (~(uint32_t)(DAC_IT << DAC_Channel));
608  }
609 }
610 
625 FlagStatus DAC_GetFlagStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG)
626 {
627  FlagStatus bitstatus = RESET;
628 
629  /* Check the parameters */
631  assert_param(IS_DAC_CHANNEL(DAC_Channel));
632  assert_param(IS_DAC_FLAG(DAC_FLAG));
633 
634  /* Check the status of the specified DAC flag */
635  if ((DACx->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET)
636  {
637  /* DAC_FLAG is set */
638  bitstatus = SET;
639  }
640  else
641  {
642  /* DAC_FLAG is reset */
643  bitstatus = RESET;
644  }
645  /* Return the DAC_FLAG status */
646  return bitstatus;
647 }
648 
661 void DAC_ClearFlag(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG)
662 {
663  /* Check the parameters */
665  assert_param(IS_DAC_CHANNEL(DAC_Channel));
666  assert_param(IS_DAC_FLAG(DAC_FLAG));
667 
668  /* Clear the selected DAC flags */
669  DACx->SR = (DAC_FLAG << DAC_Channel);
670 }
671 
686 ITStatus DAC_GetITStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT)
687 {
688  ITStatus bitstatus = RESET;
689  uint32_t enablestatus = 0;
690 
691  /* Check the parameters */
693  assert_param(IS_DAC_CHANNEL(DAC_Channel));
694  assert_param(IS_DAC_IT(DAC_IT));
695 
696  /* Get the DAC_IT enable bit status */
697  enablestatus = (DACx->CR & (DAC_IT << DAC_Channel)) ;
698 
699  /* Check the status of the specified DAC interrupt */
700  if (((DACx->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus)
701  {
702  /* DAC_IT is set */
703  bitstatus = SET;
704  }
705  else
706  {
707  /* DAC_IT is reset */
708  bitstatus = RESET;
709  }
710  /* Return the DAC_IT status */
711  return bitstatus;
712 }
713 
726 void DAC_ClearITPendingBit(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT)
727 {
728  /* Check the parameters */
730  assert_param(IS_DAC_CHANNEL(DAC_Channel));
731  assert_param(IS_DAC_IT(DAC_IT));
732 
733  /* Clear the selected DAC interrupt pending bits */
734  DACx->SR = (DAC_IT << DAC_Channel);
735 }
736 
753 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
754 
FlagStatus
Definition: stm32f4xx.h:706
void DAC_SetChannel1Data(DAC_TypeDef *DACx, uint32_t DAC_Align, uint16_t Data)
Set the specified data holding register value for DAC channel1.
uint32_t DAC_Buffer_Switch
Definition: stm32f30x_dac.h:68
FunctionalState
Definition: stm32f4xx.h:708
#define DAC_Align_8b_R
#define DAC_Trigger_None
Definition: stm32f4xx_dac.h:81
#define DAC_SWTRIGR_SWTRIG1
Definition: stm32f4xx.h:3972
#define DUAL_SWTRIG_RESET
#define IS_DAC_FLAG(FLAG)
void DAC_StructInit(DAC_InitTypeDef *DAC_InitStruct)
Fills each DAC_InitStruct member with its default value.
#define DHR12R1_OFFSET
Digital to Analog Converter.
Definition: stm32f4xx.h:854
#define DUAL_SWTRIG_SET
void assert_param(int val)
#define IS_DAC_WAVE(WAVE)
#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE)
#define IS_FUNCTIONAL_STATE(STATE)
Definition: stm32f4xx.h:709
#define DAC_CR_EN1
Definition: stm32f4xx.h:3930
#define DAC_CR_DMAEN1
Definition: stm32f4xx.h:3949
uint16_t DAC_GetDataOutputValue(DAC_TypeDef *DACx, uint32_t DAC_Channel)
Returns the last data output value of the selected DAC channel.
Definition: stm32f4xx.h:706
enum FlagStatus ITStatus
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
void DAC_ClearITPendingBit(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t DAC_IT)
Clears the DAC channel&#39;s interrupt pending bits.
void DAC_SoftwareTriggerCmd(DAC_TypeDef *DACx, uint32_t DAC_Channel, FunctionalState NewState)
Enables or disables the selected DAC channel software trigger.
This file contains all the functions prototypes for the RCC firmware library.
void DAC_SetDualChannelData(DAC_TypeDef *DACx, uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
Set the specified data holding register value for dual channel DAC.
#define __IO
Definition: core_cm0.h:198
#define IS_DAC_ALL_PERIPH(PERIPH)
Definition: stm32f30x_dac.h:79
#define RCC_APB1Periph_DAC2
void DAC_DeInit(DAC_TypeDef *DACx)
Deinitializes the DAC peripheral registers to their default reset values.
void DAC_ClearFlag(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG)
Clears the DAC channel&#39;s pending flags.
void DAC_Cmd(DAC_TypeDef *DACx, uint32_t DAC_Channel, FunctionalState NewState)
Enables or disables the specified DAC channel.
#define RCC_APB1Periph_DAC1
void DAC_WaveGenerationCmd(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
Enables or disables the selected DAC channel wave generation.
This file contains all the functions prototypes for the DAC firmware library.
void DAC_Init(DAC_TypeDef *DACx, uint32_t DAC_Channel, DAC_InitTypeDef *DAC_InitStruct)
Initializes the DAC peripheral according to the specified parameters in the DAC_InitStruct.
void DAC_DualSoftwareTriggerCmd(DAC_TypeDef *DACx, FunctionalState NewState)
Enables or disables simultaneously the two DAC channels software triggers.
FlagStatus DAC_GetFlagStatus(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG)
Checks whether the specified DAC flag is set or not.
#define DAC_LFSRUnmask_Bit0
#define DOR_OFFSET
uint32_t DAC_LFSRUnmask_TriangleAmplitude
Definition: stm32f4xx_dac.h:63
#define IS_DAC_IT(IT)
void DAC_ITConfig(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)
Enables or disables the specified DAC interrupts.
#define IS_DAC_LIST1_PERIPH(PERIPH)
Definition: stm32f30x_dac.h:82
void DAC_DMACmd(DAC_TypeDef *DACx, uint32_t DAC_Channel, FunctionalState NewState)
Enables or disables the specified DAC channel DMA request. When enabled DMA1 is generated when an ext...
uint32_t DAC_Trigger
Definition: stm32f4xx_dac.h:56
#define DAC_BufferSwitch_Enable
void DAC_SetChannel2Data(DAC_TypeDef *DACx, uint32_t DAC_Align, uint16_t Data)
Set the specified data holding register value for DAC channel2.
#define IS_DAC_ALIGN(ALIGN)
#define IS_DAC_GENERATE_WAVE(WAVE)
__IO uint32_t SR
Definition: stm32f4xx.h:869
#define IS_DAC_DATA(DATA)
#define IS_DAC_BUFFER_SWITCH_STATE(STATE)
DAC Init structure definition.
Definition: stm32f4xx_dac.h:54
#define DHR12R2_OFFSET
#define DHR12RD_OFFSET
#define IS_DAC_CHANNEL(CHANNEL)
#define CR_CLEAR_MASK
uint32_t DAC_WaveGeneration
Definition: stm32f4xx_dac.h:59
__IO uint32_t CR
Definition: stm32f4xx.h:856
#define IS_DAC_TRIGGER(TRIGGER)
Definition: stm32f4xx_dac.h:94
#define DAC_WaveGeneration_None
ITStatus DAC_GetITStatus(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t DAC_IT)
Checks whether the specified DAC interrupt has occurred or not.
__IO uint32_t SWTRIGR
Definition: stm32f4xx.h:857


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:48