Updated and Validated
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Inc / stm32f3xx_hal_dac.h
blob1267f84cf01a7a242a7f6ec44d4839b1a8b3235c
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_dac.h
4 * @author MCD Application Team
5 * @brief Header file of DAC HAL module.
6 ******************************************************************************
7 * @attention
9 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
11 * Redistribution and use in source and binary forms, with or without modification,
12 * are permitted provided that the following conditions are met:
13 * 1. Redistributions of source code must retain the above copyright notice,
14 * this list of conditions and the following disclaimer.
15 * 2. Redistributions in binary form must reproduce the above copyright notice,
16 * this list of conditions and the following disclaimer in the documentation
17 * and/or other materials provided with the distribution.
18 * 3. Neither the name of STMicroelectronics nor the names of its contributors
19 * may be used to endorse or promote products derived from this software
20 * without specific prior written permission.
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 ******************************************************************************
36 /* Define to prevent recursive inclusion -------------------------------------*/
37 #ifndef __STM32F3xx_HAL_DAC_H
38 #define __STM32F3xx_HAL_DAC_H
40 #ifdef __cplusplus
41 extern "C" {
42 #endif
44 /* Includes ------------------------------------------------------------------*/
45 #include "stm32f3xx_hal_def.h"
47 /** @addtogroup STM32F3xx_HAL_Driver
48 * @{
51 /** @addtogroup DAC
52 * @{
55 /* Exported types ------------------------------------------------------------*/
57 /** @defgroup DAC_Exported_Types DAC Exported Types
58 * @{
61 /**
62 * @brief HAL State structures definition
63 */
64 typedef enum
66 HAL_DAC_STATE_RESET = 0x00U, /*!< DAC not yet initialized or disabled */
67 HAL_DAC_STATE_READY = 0x01U, /*!< DAC initialized and ready for use */
68 HAL_DAC_STATE_BUSY = 0x02U, /*!< DAC internal processing is ongoing */
69 HAL_DAC_STATE_TIMEOUT = 0x03U, /*!< DAC timeout state */
70 HAL_DAC_STATE_ERROR = 0x04 /*!< DAC error state */
72 }HAL_DAC_StateTypeDef;
74 /**
75 * @brief DAC Configuration regular Channel structure definition
76 */
77 typedef struct
79 uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel.
80 This parameter can be a value of @ref DACEx_trigger_selection */
82 uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled.
83 This parameter can be a value of @ref DAC_output_buffer
84 For a given DAC channel, is this paramater applies then DAC_OutputSwitch
85 does not apply */
87 uint32_t DAC_OutputSwitch; /*!< Specifies whether the DAC channel output switch is enabled or disabled.
88 This parameter can be a value of @ref DAC_OutputSwitch
89 For a given DAC channel, is this paramater applies then DAC_OutputBuffer
90 does not apply */
92 }DAC_ChannelConfTypeDef;
94 /**
95 * @brief DAC handle Structure definition
96 */
97 typedef struct __DAC_HandleTypeDef
99 DAC_TypeDef *Instance; /*!< Register base address */
101 __IO HAL_DAC_StateTypeDef State; /*!< DAC communication state */
103 HAL_LockTypeDef Lock; /*!< DAC locking object */
105 DMA_HandleTypeDef *DMA_Handle1; /*!< Pointer DMA handler for channel 1U */
107 DMA_HandleTypeDef *DMA_Handle2; /*!< Pointer DMA handler for channel 2U */
109 __IO uint32_t ErrorCode; /*!< DAC Error code */
111 }DAC_HandleTypeDef;
113 * @}
116 /* Exported constants --------------------------------------------------------*/
117 /** @defgroup DAC_Exported_Constants DAC Exported Constants
118 * @{
121 /** @defgroup DAC_Error_Code DAC Error Code
122 * @{
124 #define HAL_DAC_ERROR_NONE 0x00 /*!< No error */
125 #define HAL_DAC_ERROR_DMAUNDERRUNCH1 0x01 /*!< DAC channel1 DMA underrun error */
126 #define HAL_DAC_ERROR_DMAUNDERRUNCH2 0x02 /*!< DAC channel2 DMA underrun error */
127 #define HAL_DAC_ERROR_DMA 0x04 /*!< DMA error */
129 * @}
132 /** @defgroup DAC_lfsrunmask_triangleamplitude DAC lfsrunmask triangleamplitude
133 * @{
135 #define DAC_LFSRUNMASK_BIT0 (0x00000000U) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */
136 #define DAC_LFSRUNMASK_BITS1_0 ((uint32_t)DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */
137 #define DAC_LFSRUNMASK_BITS2_0 ((uint32_t)DAC_CR_MAMP1_1) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */
138 #define DAC_LFSRUNMASK_BITS3_0 ((uint32_t)DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0)/*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */
139 #define DAC_LFSRUNMASK_BITS4_0 ((uint32_t)DAC_CR_MAMP1_2) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */
140 #define DAC_LFSRUNMASK_BITS5_0 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */
141 #define DAC_LFSRUNMASK_BITS6_0 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */
142 #define DAC_LFSRUNMASK_BITS7_0 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */
143 #define DAC_LFSRUNMASK_BITS8_0 ((uint32_t)DAC_CR_MAMP1_3) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */
144 #define DAC_LFSRUNMASK_BITS9_0 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */
145 #define DAC_LFSRUNMASK_BITS10_0 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */
146 #define DAC_LFSRUNMASK_BITS11_0 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */
147 #define DAC_TRIANGLEAMPLITUDE_1 (0x00000000U) /*!< Select max triangle amplitude of 1U */
148 #define DAC_TRIANGLEAMPLITUDE_3 ((uint32_t)DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 3U */
149 #define DAC_TRIANGLEAMPLITUDE_7 ((uint32_t)DAC_CR_MAMP1_1) /*!< Select max triangle amplitude of 7U */
150 #define DAC_TRIANGLEAMPLITUDE_15 ((uint32_t)DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 15U */
151 #define DAC_TRIANGLEAMPLITUDE_31 ((uint32_t)DAC_CR_MAMP1_2) /*!< Select max triangle amplitude of 31U */
152 #define DAC_TRIANGLEAMPLITUDE_63 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 63U */
153 #define DAC_TRIANGLEAMPLITUDE_127 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1) /*!< Select max triangle amplitude of 127U */
154 #define DAC_TRIANGLEAMPLITUDE_255 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 255U */
155 #define DAC_TRIANGLEAMPLITUDE_511 ((uint32_t)DAC_CR_MAMP1_3) /*!< Select max triangle amplitude of 511U */
156 #define DAC_TRIANGLEAMPLITUDE_1023 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 1023U */
157 #define DAC_TRIANGLEAMPLITUDE_2047 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1) /*!< Select max triangle amplitude of 2047U */
158 #define DAC_TRIANGLEAMPLITUDE_4095 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 4095U */
161 * @}
164 /** @defgroup DAC_output_buffer DAC output buffer
165 * @{
167 #define DAC_OUTPUTBUFFER_ENABLE (0x00000000U)
168 #define DAC_OUTPUTBUFFER_DISABLE ((uint32_t)DAC_CR_BOFF1)
171 * @}
174 #if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx)
175 /** @defgroup DAC_output_switch DAC output switch
176 * @{
178 #define DAC_OUTPUTSWITCH_DISABLE (0x00000000U)
179 #define DAC_OUTPUTSWITCH_ENABLE ((uint32_t)DAC_CR_OUTEN1)
182 * @}
185 #endif /* STM32F303x8 || STM32F334x8 || STM32F328xx || */
186 /** @defgroup DAC_data_alignement DAC data alignement
187 * @{
189 #define DAC_ALIGN_12B_R (0x00000000U)
190 #define DAC_ALIGN_12B_L (0x00000004U)
191 #define DAC_ALIGN_8B_R (0x00000008U)
194 * @}
197 /** @defgroup DAC_flags_definition DAC flags definition
198 * @{
200 #define DAC_FLAG_DMAUDR1 ((uint32_t)DAC_SR_DMAUDR1)
201 #define DAC_FLAG_DMAUDR2 ((uint32_t)DAC_SR_DMAUDR2)
203 * @}
206 /** @defgroup DAC_interrupts_definition DAC interrupts definition
207 * @{
209 #define DAC_IT_DMAUDR1 ((uint32_t)DAC_CR_DMAUDRIE1)
210 #define DAC_IT_DMAUDR2 ((uint32_t)DAC_CR_DMAUDRIE2)
213 * @}
217 * @}
220 /* Exported macro ------------------------------------------------------------*/
222 /** @defgroup DAC_Exported_Macros DAC Exported Macros
223 * @{
226 /** @brief Reset DAC handle state
227 * @param __HANDLE__ specifies the DAC handle.
228 * @retval None
230 #define __HAL_DAC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DAC_STATE_RESET)
232 /** @brief Enable the DAC channel
233 * @param __HANDLE__ specifies the DAC handle.
234 * @param __DAC_Channel__ specifies the DAC channel
235 * @retval None
237 #define __HAL_DAC_ENABLE(__HANDLE__, __DAC_Channel__) \
238 ((__HANDLE__)->Instance->CR |= (DAC_CR_EN1 << (__DAC_Channel__)))
240 /** @brief Disable the DAC channel
241 * @param __HANDLE__ specifies the DAC handle
242 * @param __DAC_Channel__ specifies the DAC channel.
243 * @retval None
245 #define __HAL_DAC_DISABLE(__HANDLE__, __DAC_Channel__) \
246 ((__HANDLE__)->Instance->CR &= ~(DAC_CR_EN1 << (__DAC_Channel__)))
248 /** @brief Set DHR12R1 alignment
249 * @param __ALIGNMENT__ specifies the DAC alignment
250 * @retval None
252 #define DAC_DHR12R1_ALIGNMENT(__ALIGNMENT__) ((0x00000008U) + (__ALIGNMENT__))
254 /** @brief Set DHR12R2 alignment
255 * @param __ALIGNMENT__ specifies the DAC alignment
256 * @retval None
258 #define DAC_DHR12R2_ALIGNMENT(__ALIGNMENT__) ((0x00000014U) + (__ALIGNMENT__))
260 /** @brief Set DHR12RD alignment
261 * @param __ALIGNMENT__ specifies the DAC alignment
262 * @retval None
264 #define DAC_DHR12RD_ALIGNMENT(__ALIGNMENT__) ((0x00000020U) + (__ALIGNMENT__))
266 /** @brief Enable the DAC interrupt
267 * @param __HANDLE__ specifies the DAC handle
268 * @param __INTERRUPT__ specifies the DAC interrupt.
269 * This parameter can be any combination of the following values:
270 * @arg DAC_IT_DMAUDR1: DAC channel 1 DMA underrun interrupt
271 * @arg DAC_IT_DMAUDR2: DAC channel 2 DMA underrun interrupt
272 * @retval None
274 #define __HAL_DAC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) |= (__INTERRUPT__))
276 /** @brief Disable the DAC interrupt
277 * @param __HANDLE__ specifies the DAC handle
278 * @param __INTERRUPT__ specifies the DAC interrupt.
279 * This parameter can be any combination of the following values:
280 * @arg DAC_IT_DMAUDR1: DAC channel 1 DMA underrun interrupt
281 * @arg DAC_IT_DMAUDR2: DAC channel 2 DMA underrun interrupt
282 * @retval None
284 #define __HAL_DAC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) &= ~(__INTERRUPT__))
286 /** @brief Check whether the specified DAC interrupt source is enabled or not
287 * @param __HANDLE__ DAC handle
288 * @param __INTERRUPT__ DAC interrupt source to check
289 * This parameter can be any combination of the following values:
290 * @arg DAC_IT_DMAUDR1: DAC channel 1 DMA underrun interrupt
291 * @arg DAC_IT_DMAUDR2: DAC channel 2 DMA underrun interrupt
292 * @retval State of interruption (SET or RESET)
294 #define __HAL_DAC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR & (__INTERRUPT__)) == (__INTERRUPT__))
296 /** @brief Get the selected DAC's flag status
297 * @param __HANDLE__ specifies the DAC handle.
298 * @param __FLAG__ specifies the DAC flag to get.
299 * This parameter can be any combination of the following values:
300 * @arg DAC_FLAG_DMAUDR1: DAC channel 1 DMA underrun flag
301 * @arg DAC_FLAG_DMAUDR2: DAC channel 2 DMA underrun flag
302 * @retval None
304 #define __HAL_DAC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__))
306 /** @brief Clear the DAC's flag
307 * @param __HANDLE__ specifies the DAC handle.
308 * @param __FLAG__ specifies the DAC flag to clear.
309 * This parameter can be any combination of the following values:
310 * @arg DAC_FLAG_DMAUDR1: DAC channel 1 DMA underrun flag
311 * @arg DAC_FLAG_DMAUDR2: DAC channel 2 DMA underrun flag
312 * @retval None
314 #define __HAL_DAC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = (__FLAG__))
317 * @}
320 /* Private macro -------------------------------------------------------------*/
322 /** @addtogroup DAC_Private_Macros
323 * @{
326 #define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUNMASK_BIT0) || \
327 ((VALUE) == DAC_LFSRUNMASK_BITS1_0) || \
328 ((VALUE) == DAC_LFSRUNMASK_BITS2_0) || \
329 ((VALUE) == DAC_LFSRUNMASK_BITS3_0) || \
330 ((VALUE) == DAC_LFSRUNMASK_BITS4_0) || \
331 ((VALUE) == DAC_LFSRUNMASK_BITS5_0) || \
332 ((VALUE) == DAC_LFSRUNMASK_BITS6_0) || \
333 ((VALUE) == DAC_LFSRUNMASK_BITS7_0) || \
334 ((VALUE) == DAC_LFSRUNMASK_BITS8_0) || \
335 ((VALUE) == DAC_LFSRUNMASK_BITS9_0) || \
336 ((VALUE) == DAC_LFSRUNMASK_BITS10_0) || \
337 ((VALUE) == DAC_LFSRUNMASK_BITS11_0) || \
338 ((VALUE) == DAC_TRIANGLEAMPLITUDE_1) || \
339 ((VALUE) == DAC_TRIANGLEAMPLITUDE_3) || \
340 ((VALUE) == DAC_TRIANGLEAMPLITUDE_7) || \
341 ((VALUE) == DAC_TRIANGLEAMPLITUDE_15) || \
342 ((VALUE) == DAC_TRIANGLEAMPLITUDE_31) || \
343 ((VALUE) == DAC_TRIANGLEAMPLITUDE_63) || \
344 ((VALUE) == DAC_TRIANGLEAMPLITUDE_127) || \
345 ((VALUE) == DAC_TRIANGLEAMPLITUDE_255) || \
346 ((VALUE) == DAC_TRIANGLEAMPLITUDE_511) || \
347 ((VALUE) == DAC_TRIANGLEAMPLITUDE_1023) || \
348 ((VALUE) == DAC_TRIANGLEAMPLITUDE_2047) || \
349 ((VALUE) == DAC_TRIANGLEAMPLITUDE_4095))
351 #define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OUTPUTBUFFER_ENABLE) || \
352 ((STATE) == DAC_OUTPUTBUFFER_DISABLE))
354 #if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx)
355 #define IS_DAC_OUTPUT_SWITCH_STATE(STATE) (((STATE) == DAC_OUTPUTSWITCH_DISABLE) || \
356 ((STATE) == DAC_OUTPUTSWITCH_ENABLE))
358 #endif /* STM32F303x8 || STM32F334x8 || STM32F328xx || */
359 #define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_ALIGN_12B_R) || \
360 ((ALIGN) == DAC_ALIGN_12B_L) || \
361 ((ALIGN) == DAC_ALIGN_8B_R))
363 #define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0U)
368 * @}
372 /* Include DAC HAL Extended module */
373 #include "stm32f3xx_hal_dac_ex.h"
375 /* Exported functions --------------------------------------------------------*/
377 /** @addtogroup DAC_Exported_Functions
378 * @{
381 /** @addtogroup DAC_Exported_Functions_Group1
382 * @{
384 /* Initialization and de-initialization functions *****************************/
385 HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef* hdac);
386 HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef* hdac);
387 void HAL_DAC_MspInit(DAC_HandleTypeDef* hdac);
388 void HAL_DAC_MspDeInit(DAC_HandleTypeDef* hdac);
391 * @}
394 /** @addtogroup DAC_Exported_Functions_Group2
395 * @{
397 /* IO operation functions *****************************************************/
398 HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef* hdac, uint32_t Channel);
399 HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef* hdac, uint32_t Channel);
400 HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef* hdac, uint32_t Channel, uint32_t* pData, uint32_t Length, uint32_t Alignment);
401 HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef* hdac, uint32_t Channel);
402 uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef* hdac, uint32_t Channel);
403 HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef* hdac, DAC_ChannelConfTypeDef* sConfig, uint32_t Channel);
405 void HAL_DAC_IRQHandler(DAC_HandleTypeDef* hdac);
406 void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef* hdac);
407 void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef* hdac);
408 void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac);
409 void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac);
412 * @}
415 /** @addtogroup DAC_Exported_Functions_Group3
416 * @{
418 /* Peripheral Control functions ***********************************************/
419 HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef* hdac, uint32_t Channel, uint32_t Alignment, uint32_t Data);
422 * @}
425 /** @addtogroup DAC_Exported_Functions_Group4
426 * @{
428 /* Peripheral State and Error functions ***************************************/
429 HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef* hdac);
430 uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac);
433 * @}
437 * @}
441 * @}
445 * @}
448 #ifdef __cplusplus
450 #endif
452 #endif /*__STM32F3xx_HAL_DAC_H */
454 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/