Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_sdadc.c
blob0df99f1a8b76d1dbfd66939928be2650e3338ea9
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_sdadc.c
4 * @author MCD Application Team
5 * @brief This file provides firmware functions to manage the following
6 * functionalities of the Sigma-Delta Analog to Digital Converter
7 * (SDADC) peripherals:
8 * + Initialization and Configuration
9 * + Regular Channels Configuration
10 * + Injected channels Configuration
11 * + Power saving
12 * + Regular/Injected Channels DMA Configuration
13 * + Interrupts and flags management
14 @verbatim
15 ==============================================================================
16 ##### SDADC specific features #####
17 ==============================================================================
18 [..]
19 (#) 16-bit sigma delta architecture.
20 (#) Self calibration.
21 (#) Interrupt generation at the end of calibration, regular/injected conversion
22 and in case of overrun events.
23 (#) Single and continuous conversion modes.
24 (#) External trigger option with configurable polarity for injected conversion.
25 (#) Multi mode (synchronized another SDADC with SDADC1).
26 (#) DMA request generation during regular or injected channel conversion.
28 ##### How to use this driver #####
29 ==============================================================================
30 [..]
31 *** Initialization ***
32 ======================
33 [..]
34 (#) As prerequisite, fill in the HAL_SDADC_MspInit() :
35 (++) Enable SDADCx clock interface with __SDADCx_CLK_ENABLE().
36 (++) Configure SDADCx clock divider with HAL_RCCEx_PeriphCLKConfig.
37 (++) Enable power on SDADC with HAL_PWREx_EnableSDADC().
38 (++) Enable the clocks for the SDADC GPIOS with __HAL_RCC_GPIOx_CLK_ENABLE().
39 (++) Configure these SDADC pins in analog mode using HAL_GPIO_Init().
40 (++) If interrupt mode is used, enable and configure SDADC global
41 interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ().
42 (++) If DMA mode is used, configure DMA with HAL_DMA_Init and link it
43 with SDADC handle using __HAL_LINKDMA.
44 (#) Configure the SDADC low power mode, fast conversion mode, slow clock
45 mode and SDADC1 reference voltage using the HAL_ADC_Init() function.
46 Note: Common reference voltage. is common to all SDADC instances.
47 (#) Prepare channel configurations (input mode, common mode, gain and
48 offset) using HAL_SDADC_PrepareChannelConfig and associate channel
49 with one configuration using HAL_SDADC_AssociateChannelConfig.
51 *** Calibration ***
52 ============================================
53 [..]
54 (#) Start calibration using HAL_SDADC_StartCalibration or
55 HAL_SDADC_CalibrationStart_IT.
56 (#) In polling mode, use HAL_SDADC_PollForCalibEvent to detect the end of
57 calibration.
58 (#) In interrupt mode, HAL_SDADC_CalibrationCpltCallback will be called at
59 the end of calibration.
61 *** Regular channel conversion ***
62 ============================================
63 [..]
64 (#) Select trigger for regular conversion using
65 HAL_SDADC_SelectRegularTrigger.
66 (#) Select regular channel and enable/disable continuous mode using
67 HAL_SDADC_ConfigChannel.
68 (#) Start regular conversion using HAL_SDADC_Start, HAL_SDADC_Start_IT
69 or HAL_SDADC_Start_DMA.
70 (#) In polling mode, use HAL_SDADC_PollForConversion to detect the end of
71 regular conversion.
72 (#) In interrupt mode, HAL_SDADC_ConvCpltCallback will be called at the
73 end of regular conversion.
74 (#) Get value of regular conversion using HAL_SDADC_GetValue.
75 (#) In DMA mode, HAL_SDADC_ConvHalfCpltCallback and
76 HAL_SDADC_ConvCpltCallback will be called respectively at the half
77 transfer and at the transfer complete.
78 (#) Stop regular conversion using HAL_SDADC_Stop, HAL_SDADC_Stop_IT
79 or HAL_SDADC_Stop_DMA.
81 *** Injected channels conversion ***
82 ============================================
83 [..]
84 (#) Enable/disable delay on injected conversion using
85 HAL_SDADC_SelectInjectedDelay.
86 (#) If external trigger is used for injected conversion, configure this
87 trigger using HAL_SDADC_SelectInjectedExtTrigger.
88 (#) Select trigger for injected conversion using
89 HAL_SDADC_SelectInjectedTrigger.
90 (#) Select injected channels and enable/disable continuous mode using
91 HAL_SDADC_InjectedConfigChannel.
92 (#) Start injected conversion using HAL_SDADC_InjectedStart,
93 HAL_SDADC_InjectedStart_IT or HAL_SDADC_InjectedStart_DMA.
94 (#) In polling mode, use HAL_SDADC_PollForInjectedConversion to detect the
95 end of injected conversion.
96 (#) In interrupt mode, HAL_SDADC_InjectedConvCpltCallback will be called
97 at the end of injected conversion.
98 (#) Get value of injected conversion and corresponding channel using
99 HAL_SDADC_InjectedGetValue.
100 (#) In DMA mode, HAL_SDADC_InjectedConvHalfCpltCallback and
101 HAL_SDADC_InjectedConvCpltCallback will be called respectively at the
102 half transfer and at the transfer complete.
103 (#) Stop injected conversion using HAL_SDADC_InjectedStop,
104 HAL_SDADC_InjectedStop_IT or HAL_SDADC_InjectedStop_DMA.
106 *** Multi mode regular channels conversions ***
107 ======================================================
108 [..]
109 (#) Select type of multimode (SDADC1/SDADC2 or SDADC1/SDADC3) using
110 HAL_SDADC_MultiModeConfigChannel.
111 (#) Select software trigger for SDADC1 and synchronized trigger for
112 SDADC2 (or SDADC3) using HAL_SDADC_SelectRegularTrigger.
113 (#) Select regular channel for SDADC1 and SDADC2 (or SDADC3) using
114 HAL_SDADC_ConfigChannel.
115 (#) Start regular conversion for SDADC2 (or SDADC3) with HAL_SDADC_Start.
116 (#) Start regular conversion for SDADC1 using HAL_SDADC_Start,
117 HAL_SDADC_Start_IT or HAL_SDADC_MultiModeStart_DMA.
118 (#) In polling mode, use HAL_SDADC_PollForConversion to detect the end of
119 regular conversion for SDADC1.
120 (#) In interrupt mode, HAL_SDADC_ConvCpltCallback will be called at the
121 end of regular conversion for SDADC1.
122 (#) Get value of regular conversions using HAL_SDADC_MultiModeGetValue.
123 (#) In DMA mode, HAL_SDADC_ConvHalfCpltCallback and
124 HAL_SDADC_ConvCpltCallback will be called respectively at the half
125 transfer and at the transfer complete for SDADC1.
126 (#) Stop regular conversion using HAL_SDADC_Stop, HAL_SDADC_Stop_IT
127 or HAL_SDADC_MultiModeStop_DMA for SDADC1.
128 (#) Stop regular conversion using HAL_SDADC_Stop for SDADC2 (or SDADC3).
130 *** Multi mode injected channels conversions ***
131 ======================================================
132 [..]
133 (#) Select type of multimode (SDADC1/SDADC2 or SDADC1/SDADC3) using
134 HAL_SDADC_InjectedMultiModeConfigChannel.
135 (#) Select software or external trigger for SDADC1 and synchronized
136 trigger for SDADC2 (or SDADC3) using HAL_SDADC_SelectInjectedTrigger.
137 (#) Select injected channels for SDADC1 and SDADC2 (or SDADC3) using
138 HAL_SDADC_InjectedConfigChannel.
139 (#) Start injected conversion for SDADC2 (or SDADC3) with
140 HAL_SDADC_InjectedStart.
141 (#) Start injected conversion for SDADC1 using HAL_SDADC_InjectedStart,
142 HAL_SDADC_InjectedStart_IT or HAL_SDADC_InjectedMultiModeStart_DMA.
143 (#) In polling mode, use HAL_SDADC_InjectedPollForConversion to detect
144 the end of injected conversion for SDADC1.
145 (#) In interrupt mode, HAL_SDADC_InjectedConvCpltCallback will be called
146 at the end of injected conversion for SDADC1.
147 (#) Get value of injected conversions using
148 HAL_SDADC_InjectedMultiModeGetValue.
149 (#) In DMA mode, HAL_SDADC_InjectedConvHalfCpltCallback and
150 HAL_SDADC_InjectedConvCpltCallback will be called respectively at the
151 half transfer and at the transfer complete for SDADC1.
152 (#) Stop injected conversion using HAL_SDADC_InjectedStop,
153 HAL_SDADC_InjectedStop_IT or HAL_SDADC_InjecteddMultiModeStop_DMA
154 for SDADC1.
155 (#) Stop injected conversion using HAL_SDADC_InjectedStop for SDADC2
156 (or SDADC3).
158 @endverbatim
159 ******************************************************************************
160 * @attention
162 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
164 * Redistribution and use in source and binary forms, with or without modification,
165 * are permitted provided that the following conditions are met:
166 * 1. Redistributions of source code must retain the above copyright notice,
167 * this list of conditions and the following disclaimer.
168 * 2. Redistributions in binary form must reproduce the above copyright notice,
169 * this list of conditions and the following disclaimer in the documentation
170 * and/or other materials provided with the distribution.
171 * 3. Neither the name of STMicroelectronics nor the names of its contributors
172 * may be used to endorse or promote products derived from this software
173 * without specific prior written permission.
175 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
176 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
177 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
178 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
179 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
180 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
181 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
182 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
183 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
184 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
186 ******************************************************************************
189 /* Includes ------------------------------------------------------------------*/
190 #include "stm32f3xx_hal.h"
192 /** @addtogroup STM32F3xx_HAL_Driver
193 * @{
196 #ifdef HAL_SDADC_MODULE_ENABLED
197 #if defined(STM32F373xC) || defined(STM32F378xx)
198 /** @defgroup SDADC SDADC
199 * @brief SDADC HAL driver modules
200 * @{
203 /* Private typedef -----------------------------------------------------------*/
204 /* Private define ------------------------------------------------------------*/
205 /** @defgroup SDADC_Private_Define SDADC Private Define
206 * @{
208 #define SDADC_TIMEOUT 200
209 #define SDADC_CONFREG_OFFSET 0x00000020
210 #define SDADC_JDATAR_CH_OFFSET 24
211 #define SDADC_MSB_MASK 0xFFFF0000U
212 #define SDADC_LSB_MASK 0x0000FFFFU
214 * @}
217 /* Private macro -------------------------------------------------------------*/
218 /* Private variables ---------------------------------------------------------*/
219 /* Private function prototypes -----------------------------------------------*/
220 /** @defgroup SDADC_Private_Functions SDADC Private Functions
221 * @{
224 static HAL_StatusTypeDef SDADC_EnterInitMode(SDADC_HandleTypeDef* hsdadc);
225 static void SDADC_ExitInitMode(SDADC_HandleTypeDef* hsdadc);
226 static uint32_t SDADC_GetInjChannelsNbr(uint32_t Channels);
227 static HAL_StatusTypeDef SDADC_RegConvStart(SDADC_HandleTypeDef* hsdadc);
228 static HAL_StatusTypeDef SDADC_RegConvStop(SDADC_HandleTypeDef* hsdadc);
229 static HAL_StatusTypeDef SDADC_InjConvStart(SDADC_HandleTypeDef* hsdadc);
230 static HAL_StatusTypeDef SDADC_InjConvStop(SDADC_HandleTypeDef* hsdadc);
231 static void SDADC_DMARegularHalfConvCplt(DMA_HandleTypeDef *hdma);
232 static void SDADC_DMARegularConvCplt(DMA_HandleTypeDef *hdma);
233 static void SDADC_DMAInjectedHalfConvCplt(DMA_HandleTypeDef *hdma);
234 static void SDADC_DMAInjectedConvCplt(DMA_HandleTypeDef *hdma);
235 static void SDADC_DMAError(DMA_HandleTypeDef *hdma);
237 * @}
240 /* Exported functions ---------------------------------------------------------*/
242 /** @defgroup SDADC_Exported_Functions SDADC Exported Functions
243 * @{
246 /** @defgroup SDADC_Exported_Functions_Group1 Initialization and de-initialization functions
247 * @brief Initialization and de-initialization functions
249 @verbatim
250 ===============================================================================
251 ##### Initialization and de-initialization functions #####
252 ===============================================================================
253 [..] This section provides functions allowing to:
254 (+) Initialize the SDADC.
255 (+) De-initialize the SDADC.
257 @endverbatim
258 * @{
262 * @brief Initializes the SDADC according to the specified
263 * parameters in the SDADC_InitTypeDef structure.
264 * @note If multiple SDADC are used, please configure first SDADC1 to set
265 * the common reference voltage.
266 * @param hsdadc SDADC handle.
267 * @retval HAL status.
269 HAL_StatusTypeDef HAL_SDADC_Init(SDADC_HandleTypeDef* hsdadc)
271 /* Check SDADC handle */
272 if(hsdadc == NULL)
274 return HAL_ERROR;
277 /* Check parameters */
278 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
279 assert_param(IS_SDADC_LOWPOWER_MODE(hsdadc->Init.IdleLowPowerMode));
280 assert_param(IS_SDADC_FAST_CONV_MODE(hsdadc->Init.FastConversionMode));
281 assert_param(IS_SDADC_SLOW_CLOCK_MODE(hsdadc->Init.SlowClockMode));
282 assert_param(IS_SDADC_VREF(hsdadc->Init.ReferenceVoltage));
284 /* Initialize SDADC variables with default values */
285 hsdadc->RegularContMode = SDADC_CONTINUOUS_CONV_OFF;
286 hsdadc->InjectedContMode = SDADC_CONTINUOUS_CONV_OFF;
287 hsdadc->InjectedChannelsNbr = 1U;
288 hsdadc->InjConvRemaining = 1U;
289 hsdadc->RegularTrigger = SDADC_SOFTWARE_TRIGGER;
290 hsdadc->InjectedTrigger = SDADC_SOFTWARE_TRIGGER;
291 hsdadc->ExtTriggerEdge = SDADC_EXT_TRIG_RISING_EDGE;
292 hsdadc->RegularMultimode = SDADC_MULTIMODE_SDADC1_SDADC2;
293 hsdadc->InjectedMultimode = SDADC_MULTIMODE_SDADC1_SDADC2;
294 hsdadc->ErrorCode = SDADC_ERROR_NONE;
296 /* Call MSP init function */
297 HAL_SDADC_MspInit(hsdadc);
299 /* Set idle low power and slow clock modes */
300 hsdadc->Instance->CR1 &= ~(SDADC_CR1_SBI|SDADC_CR1_PDI|SDADC_CR1_SLOWCK);
301 hsdadc->Instance->CR1 |= (hsdadc->Init.IdleLowPowerMode | \
302 hsdadc->Init.SlowClockMode);
304 /* Set fast conversion mode */
305 hsdadc->Instance->CR2 &= ~(SDADC_CR2_FAST);
306 hsdadc->Instance->CR2 |= hsdadc->Init.FastConversionMode;
308 /* Set reference voltage common to all SDADC instances */
309 /* Update this parameter only if needed to avoid unnecessary settling time */
310 if((SDADC1->CR1 & SDADC_CR1_REFV) != hsdadc->Init.ReferenceVoltage)
312 /* Voltage reference bits are common to all SADC instances but are */
313 /* present in SDADC1 register. */
314 SDADC1->CR1 &= ~(SDADC_CR1_REFV);
315 SDADC1->CR1 |= hsdadc->Init.ReferenceVoltage;
317 /* Wait at least 2ms before setting ADON */
318 HAL_Delay(2U);
321 /* Enable SDADC */
322 hsdadc->Instance->CR2 |= SDADC_CR2_ADON;
324 /* Wait end of stabilization */
325 while((hsdadc->Instance->ISR & SDADC_ISR_STABIP) != 0U)
329 /* Set SDADC to ready state */
330 hsdadc->State = HAL_SDADC_STATE_READY;
332 /* Return HAL status */
333 return HAL_OK;
337 * @brief De-initializes the SDADC.
338 * @param hsdadc SDADC handle.
339 * @retval HAL status.
341 HAL_StatusTypeDef HAL_SDADC_DeInit(SDADC_HandleTypeDef* hsdadc)
343 /* Check SDADC handle */
344 if(hsdadc == NULL)
346 return HAL_ERROR;
349 /* Check parameters */
350 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
352 /* Disable the SDADC */
353 hsdadc->Instance->CR2 &= ~(SDADC_CR2_ADON);
355 /* Reset all registers */
356 hsdadc->Instance->CR1 = 0x00000000U;
357 hsdadc->Instance->CR2 = 0x00000000U;
358 hsdadc->Instance->JCHGR = 0x00000001U;
359 hsdadc->Instance->CONF0R = 0x00000000U;
360 hsdadc->Instance->CONF1R = 0x00000000U;
361 hsdadc->Instance->CONF2R = 0x00000000U;
362 hsdadc->Instance->CONFCHR1 = 0x00000000U;
363 hsdadc->Instance->CONFCHR2 = 0x00000000U;
365 /* Call MSP deinit function */
366 HAL_SDADC_MspDeInit(hsdadc);
368 /* Set SDADC in reset state */
369 hsdadc->State = HAL_SDADC_STATE_RESET;
371 /* Return function status */
372 return HAL_OK;
376 * @brief Initializes the SDADC MSP.
377 * @param hsdadc SDADC handle
378 * @retval None
380 __weak void HAL_SDADC_MspInit(SDADC_HandleTypeDef* hsdadc)
382 /* Prevent unused argument(s) compilation warning */
383 UNUSED(hsdadc);
385 /* NOTE : This function should not be modified, when the callback is needed,
386 the HAL_SDADC_MspInit could be implemented in the user file.
391 * @brief De-initializes the SDADC MSP.
392 * @param hsdadc SDADC handle
393 * @retval None
395 __weak void HAL_SDADC_MspDeInit(SDADC_HandleTypeDef* hsdadc)
397 /* Prevent unused argument(s) compilation warning */
398 UNUSED(hsdadc);
400 /* NOTE : This function should not be modified, when the callback is needed,
401 the HAL_SDADC_MspDeInit could be implemented in the user file.
406 * @}
409 /** @defgroup SDADC_Exported_Functions_Group2 peripheral control functions
410 * @brief Peripheral control functions
412 @verbatim
413 ===============================================================================
414 ##### Peripheral control functions #####
415 ===============================================================================
416 [..] This section provides functions allowing to:
417 (+) Program one of the three different configurations for channels.
418 (+) Associate channel to one of configurations.
419 (+) Select regular and injected channels.
420 (+) Enable/disable continuous mode for regular and injected conversions.
421 (+) Select regular and injected triggers.
422 (+) Select and configure injected external trigger.
423 (+) Enable/disable delay addition for injected conversions.
424 (+) Configure multimode.
426 @endverbatim
427 * @{
431 * @brief This function allows the user to set parameters for a configuration.
432 * Parameters are input mode, common mode, gain and offset.
433 * @note This function should be called only when SDADC instance is in idle state
434 * (neither calibration nor regular or injected conversion ongoing)
435 * @param hsdadc SDADC handle.
436 * @param ConfIndex Index of configuration to modify.
437 * This parameter can be a value of @ref SDADC_ConfIndex.
438 * @param ConfParamStruct Parameters to apply for this configuration.
439 * @retval HAL status
441 HAL_StatusTypeDef HAL_SDADC_PrepareChannelConfig(SDADC_HandleTypeDef *hsdadc,
442 uint32_t ConfIndex,
443 SDADC_ConfParamTypeDef* ConfParamStruct)
445 HAL_StatusTypeDef status = HAL_OK;
446 uint32_t tmp = 0U;
448 /* Check parameters */
449 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
450 assert_param(IS_SDADC_CONF_INDEX(ConfIndex));
451 assert_param(ConfParamStruct != NULL);
452 assert_param(IS_SDADC_INPUT_MODE(ConfParamStruct->InputMode));
453 assert_param(IS_SDADC_GAIN(ConfParamStruct->Gain));
454 assert_param(IS_SDADC_COMMON_MODE(ConfParamStruct->CommonMode));
455 assert_param(IS_SDADC_OFFSET_VALUE(ConfParamStruct->Offset));
457 /* Check SDADC state is ready */
458 if(hsdadc->State != HAL_SDADC_STATE_READY)
460 status = HAL_ERROR;
462 else
464 /* Enter init mode */
465 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
467 /* Set SDADC in error state */
468 hsdadc->State = HAL_SDADC_STATE_ERROR;
469 status = HAL_TIMEOUT;
471 else
473 /* Program configuration register with parameters */
474 tmp = (uint32_t)((uint32_t)(hsdadc->Instance) + \
475 SDADC_CONFREG_OFFSET + \
476 (uint32_t)(ConfIndex << 2U));
477 *(__IO uint32_t *) (tmp) = (uint32_t) (ConfParamStruct->InputMode | \
478 ConfParamStruct->Gain | \
479 ConfParamStruct->CommonMode | \
480 ConfParamStruct->Offset);
481 /* Exit init mode */
482 SDADC_ExitInitMode(hsdadc);
485 /* Return function status */
486 return status;
490 * @brief This function allows the user to associate a channel with one of the
491 * available configurations.
492 * @note This function should be called only when SDADC instance is in idle state
493 * (neither calibration nor regular or injected conversion ongoing)
494 * @param hsdadc SDADC handle.
495 * @param Channel Channel to associate with configuration.
496 * This parameter can be a value of @ref SDADC_Channel_Selection.
497 * @param ConfIndex Index of configuration to associate with channel.
498 * This parameter can be a value of @ref SDADC_ConfIndex.
499 * @retval HAL status
501 HAL_StatusTypeDef HAL_SDADC_AssociateChannelConfig(SDADC_HandleTypeDef *hsdadc,
502 uint32_t Channel,
503 uint32_t ConfIndex)
505 HAL_StatusTypeDef status = HAL_OK;
506 uint32_t channelnum = 0U;
508 /* Check parameters */
509 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
510 assert_param(IS_SDADC_REGULAR_CHANNEL(Channel));
511 assert_param(IS_SDADC_CONF_INDEX(ConfIndex));
513 /* Check SDADC state is ready */
514 if(hsdadc->State != HAL_SDADC_STATE_READY)
516 status = HAL_ERROR;
518 else
520 /* Enter init mode */
521 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
523 /* Set SDADC in error state */
524 hsdadc->State = HAL_SDADC_STATE_ERROR;
525 status = HAL_TIMEOUT;
527 else
529 /* Program channel configuration register according parameters */
530 if(Channel != SDADC_CHANNEL_8)
532 /* Get channel number */
533 channelnum = (uint32_t)(Channel>>16U);
535 /* Set the channel configuration */
536 hsdadc->Instance->CONFCHR1 &= (uint32_t) ~((uint32_t)SDADC_CONFCHR1_CONFCH0 << (channelnum << 2U));
537 hsdadc->Instance->CONFCHR1 |= (uint32_t) (ConfIndex << (channelnum << 2U));
539 else
541 hsdadc->Instance->CONFCHR2 = (uint32_t) (ConfIndex);
543 /* Exit init mode */
544 SDADC_ExitInitMode(hsdadc);
547 /* Return function status */
548 return status;
552 * @brief This function allows to select channel for regular conversion and
553 * to enable/disable continuous mode for regular conversion.
554 * @param hsdadc SDADC handle.
555 * @param Channel Channel for regular conversion.
556 * This parameter can be a value of @ref SDADC_Channel_Selection.
557 * @param ContinuousMode Enable/disable continuous mode for regular conversion.
558 * This parameter can be a value of @ref SDADC_ContinuousMode.
559 * @retval HAL status
561 HAL_StatusTypeDef HAL_SDADC_ConfigChannel(SDADC_HandleTypeDef *hsdadc,
562 uint32_t Channel,
563 uint32_t ContinuousMode)
565 HAL_StatusTypeDef status = HAL_OK;
567 /* Check parameters */
568 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
569 assert_param(IS_SDADC_REGULAR_CHANNEL(Channel));
570 assert_param(IS_SDADC_CONTINUOUS_MODE(ContinuousMode));
572 /* Check SDADC state */
573 if((hsdadc->State != HAL_SDADC_STATE_RESET) && (hsdadc->State != HAL_SDADC_STATE_ERROR))
575 /* Set RCH[3:0] and RCONT bits in SDADC_CR2 */
576 hsdadc->Instance->CR2 &= (uint32_t) ~(SDADC_CR2_RCH | SDADC_CR2_RCONT);
577 if(ContinuousMode == SDADC_CONTINUOUS_CONV_ON)
579 hsdadc->Instance->CR2 |= (uint32_t) ((Channel & SDADC_MSB_MASK) | SDADC_CR2_RCONT);
581 else
583 hsdadc->Instance->CR2 |= (uint32_t) ((Channel & SDADC_MSB_MASK));
585 /* Store continuous mode information */
586 hsdadc->RegularContMode = ContinuousMode;
588 else
590 status = HAL_ERROR;
592 /* Return function status */
593 return status;
597 * @brief This function allows to select channels for injected conversion and
598 * to enable/disable continuous mode for injected conversion.
599 * @param hsdadc SDADC handle.
600 * @param Channel Channels for injected conversion.
601 * This parameter can be a values combination of @ref SDADC_Channel_Selection.
602 * @param ContinuousMode Enable/disable continuous mode for injected conversion.
603 * This parameter can be a value of @ref SDADC_ContinuousMode.
604 * @retval HAL status
606 HAL_StatusTypeDef HAL_SDADC_InjectedConfigChannel(SDADC_HandleTypeDef *hsdadc,
607 uint32_t Channel,
608 uint32_t ContinuousMode)
610 HAL_StatusTypeDef status = HAL_OK;
612 /* Check parameters */
613 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
614 assert_param(IS_SDADC_INJECTED_CHANNEL(Channel));
615 assert_param(IS_SDADC_CONTINUOUS_MODE(ContinuousMode));
617 /* Check SDADC state */
618 if((hsdadc->State != HAL_SDADC_STATE_RESET) && (hsdadc->State != HAL_SDADC_STATE_ERROR))
620 /* Set JCHG[8:0] bits in SDADC_JCHG */
621 hsdadc->Instance->JCHGR = (uint32_t) (Channel & SDADC_LSB_MASK);
622 /* Set or clear JCONT bit in SDADC_CR2 */
623 if(ContinuousMode == SDADC_CONTINUOUS_CONV_ON)
625 hsdadc->Instance->CR2 |= SDADC_CR2_JCONT;
627 else
629 hsdadc->Instance->CR2 &= ~(SDADC_CR2_JCONT);
631 /* Store continuous mode information */
632 hsdadc->InjectedContMode = ContinuousMode;
633 /* Store number of injected channels */
634 hsdadc->InjectedChannelsNbr = SDADC_GetInjChannelsNbr(Channel);
636 else
638 status = HAL_ERROR;
640 /* Return function status */
641 return status;
645 * @brief This function allows to select trigger for regular conversions.
646 * @note This function should not be called if regular conversion is ongoing.
647 * @param hsdadc SDADC handle.
648 * @param Trigger Trigger for regular conversions.
649 * This parameter can be one of the following value :
650 * @arg SDADC_SOFTWARE_TRIGGER : Software trigger.
651 * @arg SDADC_SYNCHRONOUS_TRIGGER : Synchronous with SDADC1 (only for SDADC2 and SDADC3).
652 * @retval HAL status
654 HAL_StatusTypeDef HAL_SDADC_SelectRegularTrigger(SDADC_HandleTypeDef *hsdadc, uint32_t Trigger)
656 HAL_StatusTypeDef status = HAL_OK;
658 /* Check parameters */
659 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
660 assert_param(IS_SDADC_REGULAR_TRIGGER(Trigger));
662 /* Check parameters compatibility */
663 if((hsdadc->Instance == SDADC1) && (Trigger == SDADC_SYNCHRONOUS_TRIGGER))
665 status = HAL_ERROR;
667 /* Check SDADC state */
668 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
669 (hsdadc->State == HAL_SDADC_STATE_CALIB) || \
670 (hsdadc->State == HAL_SDADC_STATE_INJ))
672 /* Store regular trigger information */
673 hsdadc->RegularTrigger = Trigger;
675 else
677 status = HAL_ERROR;
679 /* Return function status */
680 return status;
684 * @brief This function allows to select trigger for injected conversions.
685 * @note This function should not be called if injected conversion is ongoing.
686 * @param hsdadc SDADC handle.
687 * @param Trigger Trigger for injected conversions.
688 * This parameter can be one of the following value :
689 * @arg SDADC_SOFTWARE_TRIGGER : Software trigger.
690 * @arg SDADC_SYNCHRONOUS_TRIGGER : Synchronous with SDADC1 (only for SDADC2 and SDADC3).
691 * @arg SDADC_EXTERNAL_TRIGGER : External trigger.
692 * @retval HAL status
694 HAL_StatusTypeDef HAL_SDADC_SelectInjectedTrigger(SDADC_HandleTypeDef *hsdadc, uint32_t Trigger)
696 HAL_StatusTypeDef status = HAL_OK;
698 /* Check parameters */
699 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
700 assert_param(IS_SDADC_INJECTED_TRIGGER(Trigger));
702 /* Check parameters compatibility */
703 if((hsdadc->Instance == SDADC1) && (Trigger == SDADC_SYNCHRONOUS_TRIGGER))
705 status = HAL_ERROR;
707 /* Check SDADC state */
708 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
709 (hsdadc->State == HAL_SDADC_STATE_CALIB) || \
710 (hsdadc->State == HAL_SDADC_STATE_REG))
712 /* Store regular trigger information */
713 hsdadc->InjectedTrigger = Trigger;
715 else
717 status = HAL_ERROR;
719 /* Return function status */
720 return status;
724 * @brief This function allows to select and configure injected external trigger.
725 * @note This function should be called only when SDADC instance is in idle state
726 * (neither calibration nor regular or injected conversion ongoing)
727 * @param hsdadc SDADC handle.
728 * @param InjectedExtTrigger External trigger for injected conversions.
729 * This parameter can be a value of @ref SDADC_InjectedExtTrigger.
730 * @param ExtTriggerEdge Edge of external injected trigger.
731 * This parameter can be a value of @ref SDADC_ExtTriggerEdge.
732 * @retval HAL status
734 HAL_StatusTypeDef HAL_SDADC_SelectInjectedExtTrigger(SDADC_HandleTypeDef *hsdadc,
735 uint32_t InjectedExtTrigger,
736 uint32_t ExtTriggerEdge)
738 HAL_StatusTypeDef status = HAL_OK;
740 /* Check parameters */
741 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
742 assert_param(IS_SDADC_EXT_INJEC_TRIG(InjectedExtTrigger));
743 assert_param(IS_SDADC_EXT_TRIG_EDGE(ExtTriggerEdge));
745 /* Check SDADC state */
746 if(hsdadc->State == HAL_SDADC_STATE_READY)
748 /* Enter init mode */
749 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
751 /* Set SDADC in error state */
752 hsdadc->State = HAL_SDADC_STATE_ERROR;
753 status = HAL_TIMEOUT;
755 else
757 /* Set JEXTSEL[2:0] bits in SDADC_CR2 register */
758 hsdadc->Instance->CR2 &= ~(SDADC_CR2_JEXTSEL);
759 hsdadc->Instance->CR2 |= InjectedExtTrigger;
761 /* Store external trigger edge information */
762 hsdadc->ExtTriggerEdge = ExtTriggerEdge;
764 /* Exit init mode */
765 SDADC_ExitInitMode(hsdadc);
768 else
770 status = HAL_ERROR;
772 /* Return function status */
773 return status;
777 * @brief This function allows to enable/disable delay addition for injected conversions.
778 * @note This function should be called only when SDADC instance is in idle state
779 * (neither calibration nor regular or injected conversion ongoing)
780 * @param hsdadc SDADC handle.
781 * @param InjectedDelay Enable/disable delay for injected conversions.
782 * This parameter can be a value of @ref SDADC_InjectedDelay.
783 * @retval HAL status
785 HAL_StatusTypeDef HAL_SDADC_SelectInjectedDelay(SDADC_HandleTypeDef *hsdadc,
786 uint32_t InjectedDelay)
788 HAL_StatusTypeDef status = HAL_OK;
790 /* Check parameters */
791 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
792 assert_param(IS_SDADC_INJECTED_DELAY(InjectedDelay));
794 /* Check SDADC state */
795 if(hsdadc->State == HAL_SDADC_STATE_READY)
797 /* Enter init mode */
798 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
800 /* Set SDADC in error state */
801 hsdadc->State = HAL_SDADC_STATE_ERROR;
802 status = HAL_TIMEOUT;
804 else
806 /* Set JDS bit in SDADC_CR2 register */
807 hsdadc->Instance->CR2 &= ~(SDADC_CR2_JDS);
808 hsdadc->Instance->CR2 |= InjectedDelay;
810 /* Exit init mode */
811 SDADC_ExitInitMode(hsdadc);
814 else
816 status = HAL_ERROR;
818 /* Return function status */
819 return status;
823 * @brief This function allows to configure multimode for regular conversions.
824 * @note This function should not be called if regular conversion is ongoing
825 * and should be could only for SDADC1.
826 * @param hsdadc SDADC handle.
827 * @param MultimodeType Type of multimode for regular conversions.
828 * This parameter can be a value of @ref SDADC_MultimodeType.
829 * @retval HAL status
831 HAL_StatusTypeDef HAL_SDADC_MultiModeConfigChannel(SDADC_HandleTypeDef* hsdadc,
832 uint32_t MultimodeType)
834 HAL_StatusTypeDef status = HAL_OK;
836 /* Check parameters */
837 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
838 assert_param(IS_SDADC_MULTIMODE_TYPE(MultimodeType));
840 /* Check instance is SDADC1 */
841 if(hsdadc->Instance != SDADC1)
843 status = HAL_ERROR;
845 /* Check SDADC state */
846 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
847 (hsdadc->State == HAL_SDADC_STATE_CALIB) || \
848 (hsdadc->State == HAL_SDADC_STATE_INJ))
850 /* Store regular trigger information */
851 hsdadc->RegularMultimode = MultimodeType;
853 else
855 status = HAL_ERROR;
857 /* Return function status */
858 return status;
862 * @brief This function allows to configure multimode for injected conversions.
863 * @note This function should not be called if injected conversion is ongoing
864 * and should be could only for SDADC1.
865 * @param hsdadc SDADC handle.
866 * @param MultimodeType Type of multimode for injected conversions.
867 * This parameter can be a value of @ref SDADC_MultimodeType.
868 * @retval HAL status
870 HAL_StatusTypeDef HAL_SDADC_InjectedMultiModeConfigChannel(SDADC_HandleTypeDef* hsdadc,
871 uint32_t MultimodeType)
873 HAL_StatusTypeDef status = HAL_OK;
875 /* Check parameters */
876 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
877 assert_param(IS_SDADC_MULTIMODE_TYPE(MultimodeType));
879 /* Check instance is SDADC1 */
880 if(hsdadc->Instance != SDADC1)
882 status = HAL_ERROR;
884 /* Check SDADC state */
885 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
886 (hsdadc->State == HAL_SDADC_STATE_CALIB) || \
887 (hsdadc->State == HAL_SDADC_STATE_REG))
889 /* Store regular trigger information */
890 hsdadc->InjectedMultimode = MultimodeType;
892 else
894 status = HAL_ERROR;
896 /* Return function status */
897 return status;
901 * @}
904 /** @defgroup SDADC_Exported_Functions_Group3 Input and Output operation functions
905 * @brief IO operation Control functions
907 @verbatim
908 ===============================================================================
909 ##### IO operation functions #####
910 ===============================================================================
911 [..] This section provides functions allowing to:
912 (+) Start calibration.
913 (+) Poll for the end of calibration.
914 (+) Start calibration and enable interrupt.
915 (+) Start conversion of regular/injected channel.
916 (+) Poll for the end of regular/injected conversion.
917 (+) Stop conversion of regular/injected channel.
918 (+) Start conversion of regular/injected channel and enable interrupt.
919 (+) Stop conversion of regular/injected channel and disable interrupt.
920 (+) Start conversion of regular/injected channel and enable DMA transfer.
921 (+) Stop conversion of regular/injected channel and disable DMA transfer.
922 (+) Start multimode and enable DMA transfer for regular/injected conversion.
923 (+) Stop multimode and disable DMA transfer for regular/injected conversion..
924 (+) Get result of regular channel conversion.
925 (+) Get result of injected channel conversion.
926 (+) Get result of multimode conversion.
927 (+) Handle SDADC interrupt request.
928 (+) Callbacks for calibration and regular/injected conversions.
930 @endverbatim
931 * @{
935 * @brief This function allows to start calibration in polling mode.
936 * @note This function should be called only when SDADC instance is in idle state
937 * (neither calibration nor regular or injected conversion ongoing).
938 * @param hsdadc SDADC handle.
939 * @param CalibrationSequence Calibration sequence.
940 * This parameter can be a value of @ref SDADC_CalibrationSequence.
941 * @retval HAL status
943 HAL_StatusTypeDef HAL_SDADC_CalibrationStart(SDADC_HandleTypeDef *hsdadc,
944 uint32_t CalibrationSequence)
946 HAL_StatusTypeDef status = HAL_OK;
948 /* Check parameters */
949 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
950 assert_param(IS_SDADC_CALIB_SEQUENCE(CalibrationSequence));
952 /* Check SDADC state */
953 if(hsdadc->State == HAL_SDADC_STATE_READY)
955 /* Enter init mode */
956 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
958 /* Set SDADC in error state */
959 hsdadc->State = HAL_SDADC_STATE_ERROR;
960 status = HAL_TIMEOUT;
962 else
964 /* Set CALIBCNT[1:0] bits in SDADC_CR2 register */
965 hsdadc->Instance->CR2 &= ~(SDADC_CR2_CALIBCNT);
966 hsdadc->Instance->CR2 |= CalibrationSequence;
968 /* Exit init mode */
969 SDADC_ExitInitMode(hsdadc);
971 /* Set STARTCALIB in SDADC_CR2 */
972 hsdadc->Instance->CR2 |= SDADC_CR2_STARTCALIB;
974 /* Set SDADC in calibration state */
975 hsdadc->State = HAL_SDADC_STATE_CALIB;
978 else
980 status = HAL_ERROR;
982 /* Return function status */
983 return status;
987 * @brief This function allows to poll for the end of calibration.
988 * @note This function should be called only if calibration is ongoing.
989 * @param hsdadc SDADC handle.
990 * @param Timeout Timeout value in milliseconds.
991 * @retval HAL status
993 HAL_StatusTypeDef HAL_SDADC_PollForCalibEvent(SDADC_HandleTypeDef* hsdadc, uint32_t Timeout)
995 uint32_t tickstart;
997 /* Check parameters */
998 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1000 /* Check SDADC state */
1001 if(hsdadc->State != HAL_SDADC_STATE_CALIB)
1003 /* Return error status */
1004 return HAL_ERROR;
1006 else
1008 /* Get timeout */
1009 tickstart = HAL_GetTick();
1011 /* Wait EOCALF bit in SDADC_ISR register */
1012 while((hsdadc->Instance->ISR & SDADC_ISR_EOCALF) != SDADC_ISR_EOCALF)
1014 /* Check the Timeout */
1015 if(Timeout != HAL_MAX_DELAY)
1017 if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout))
1019 /* Return timeout status */
1020 return HAL_TIMEOUT;
1024 /* Set CLREOCALF bit in SDADC_CLRISR register */
1025 hsdadc->Instance->CLRISR |= SDADC_ISR_CLREOCALF;
1027 /* Set SDADC in ready state */
1028 hsdadc->State = HAL_SDADC_STATE_READY;
1030 /* Return function status */
1031 return HAL_OK;
1036 * @brief This function allows to start calibration in interrupt mode.
1037 * @note This function should be called only when SDADC instance is in idle state
1038 * (neither calibration nor regular or injected conversion ongoing).
1039 * @param hsdadc SDADC handle.
1040 * @param CalibrationSequence Calibration sequence.
1041 * This parameter can be a value of @ref SDADC_CalibrationSequence.
1042 * @retval HAL status
1044 HAL_StatusTypeDef HAL_SDADC_CalibrationStart_IT(SDADC_HandleTypeDef *hsdadc,
1045 uint32_t CalibrationSequence)
1047 HAL_StatusTypeDef status = HAL_OK;
1049 /* Check parameters */
1050 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1051 assert_param(IS_SDADC_CALIB_SEQUENCE(CalibrationSequence));
1053 /* Check SDADC state */
1054 if(hsdadc->State == HAL_SDADC_STATE_READY)
1056 /* Enter init mode */
1057 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
1059 /* Set SDADC in error state */
1060 hsdadc->State = HAL_SDADC_STATE_ERROR;
1061 status = HAL_TIMEOUT;
1063 else
1065 /* Set CALIBCNT[1:0] bits in SDADC_CR2 register */
1066 hsdadc->Instance->CR2 &= ~(SDADC_CR2_CALIBCNT);
1067 hsdadc->Instance->CR2 |= CalibrationSequence;
1069 /* Exit init mode */
1070 SDADC_ExitInitMode(hsdadc);
1072 /* Set EOCALIE bit in SDADC_CR1 register */
1073 hsdadc->Instance->CR1 |= SDADC_CR1_EOCALIE;
1075 /* Set STARTCALIB in SDADC_CR2 */
1076 hsdadc->Instance->CR2 |= SDADC_CR2_STARTCALIB;
1078 /* Set SDADC in calibration state */
1079 hsdadc->State = HAL_SDADC_STATE_CALIB;
1082 else
1084 status = HAL_ERROR;
1086 /* Return function status */
1087 return status;
1091 * @brief This function allows to start regular conversion in polling mode.
1092 * @note This function should be called only when SDADC instance is in idle state
1093 * or if injected conversion is ongoing.
1094 * @param hsdadc SDADC handle.
1095 * @retval HAL status
1097 HAL_StatusTypeDef HAL_SDADC_Start(SDADC_HandleTypeDef *hsdadc)
1099 HAL_StatusTypeDef status = HAL_OK;
1101 /* Check parameters */
1102 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1104 /* Check SDADC state */
1105 if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1106 (hsdadc->State == HAL_SDADC_STATE_INJ))
1108 /* Start regular conversion */
1109 status = SDADC_RegConvStart(hsdadc);
1111 else
1113 status = HAL_ERROR;
1115 /* Return function status */
1116 return status;
1120 * @brief This function allows to poll for the end of regular conversion.
1121 * @note This function should be called only if regular conversion is ongoing.
1122 * @param hsdadc SDADC handle.
1123 * @param Timeout Timeout value in milliseconds.
1124 * @retval HAL status
1126 HAL_StatusTypeDef HAL_SDADC_PollForConversion(SDADC_HandleTypeDef* hsdadc, uint32_t Timeout)
1128 uint32_t tickstart;
1130 /* Check parameters */
1131 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1133 /* Check SDADC state */
1134 if((hsdadc->State != HAL_SDADC_STATE_REG) && \
1135 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1137 /* Return error status */
1138 return HAL_ERROR;
1140 else
1142 /* Get timeout */
1143 tickstart = HAL_GetTick();
1145 /* Wait REOCF bit in SDADC_ISR register */
1146 while((hsdadc->Instance->ISR & SDADC_ISR_REOCF) != SDADC_ISR_REOCF)
1148 /* Check the Timeout */
1149 if(Timeout != HAL_MAX_DELAY)
1151 if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout))
1153 /* Return timeout status */
1154 return HAL_TIMEOUT;
1158 /* Check if overrun occurs */
1159 if((hsdadc->Instance->ISR & SDADC_ISR_ROVRF) == SDADC_ISR_ROVRF)
1161 /* Update error code and call error callback */
1162 hsdadc->ErrorCode = SDADC_ERROR_REGULAR_OVERRUN;
1163 HAL_SDADC_ErrorCallback(hsdadc);
1165 /* Set CLRROVRF bit in SDADC_CLRISR register */
1166 hsdadc->Instance->CLRISR |= SDADC_ISR_CLRROVRF;
1168 /* Update SDADC state only if not continuous conversion and SW trigger */
1169 if((hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1170 (hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER))
1172 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_REG) ? \
1173 HAL_SDADC_STATE_READY : HAL_SDADC_STATE_INJ;
1175 /* Return function status */
1176 return HAL_OK;
1181 * @brief This function allows to stop regular conversion in polling mode.
1182 * @note This function should be called only if regular conversion is ongoing.
1183 * @param hsdadc SDADC handle.
1184 * @retval HAL status
1186 HAL_StatusTypeDef HAL_SDADC_Stop(SDADC_HandleTypeDef *hsdadc)
1188 HAL_StatusTypeDef status = HAL_OK;
1190 /* Check parameters */
1191 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1193 /* Check SDADC state */
1194 if((hsdadc->State != HAL_SDADC_STATE_REG) && \
1195 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1197 /* Return error status */
1198 status = HAL_ERROR;
1200 else
1202 /* Stop regular conversion */
1203 status = SDADC_RegConvStop(hsdadc);
1205 /* Return function status */
1206 return status;
1210 * @brief This function allows to start regular conversion in interrupt mode.
1211 * @note This function should be called only when SDADC instance is in idle state
1212 * or if injected conversion is ongoing.
1213 * @param hsdadc SDADC handle.
1214 * @retval HAL status
1216 HAL_StatusTypeDef HAL_SDADC_Start_IT(SDADC_HandleTypeDef *hsdadc)
1218 HAL_StatusTypeDef status = HAL_OK;
1220 /* Check parameters */
1221 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1223 /* Check SDADC state */
1224 if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1225 (hsdadc->State == HAL_SDADC_STATE_INJ))
1227 /* Set REOCIE and ROVRIE bits in SDADC_CR1 register */
1228 hsdadc->Instance->CR1 |= (uint32_t) (SDADC_CR1_REOCIE | SDADC_CR1_ROVRIE);
1230 /* Start regular conversion */
1231 status = SDADC_RegConvStart(hsdadc);
1233 else
1235 status = HAL_ERROR;
1237 /* Return function status */
1238 return status;
1242 * @brief This function allows to stop regular conversion in interrupt mode.
1243 * @note This function should be called only if regular conversion is ongoing.
1244 * @param hsdadc SDADC handle.
1245 * @retval HAL status
1247 HAL_StatusTypeDef HAL_SDADC_Stop_IT(SDADC_HandleTypeDef *hsdadc)
1249 HAL_StatusTypeDef status = HAL_OK;
1251 /* Check parameters */
1252 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1254 /* Check SDADC state */
1255 if((hsdadc->State != HAL_SDADC_STATE_REG) && \
1256 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1258 /* Return error status */
1259 status = HAL_ERROR;
1261 else
1263 /* Clear REOCIE and ROVRIE bits in SDADC_CR1 register */
1264 hsdadc->Instance->CR1 &= (uint32_t) ~(SDADC_CR1_REOCIE | SDADC_CR1_ROVRIE);
1266 /* Stop regular conversion */
1267 status = SDADC_RegConvStop(hsdadc);
1269 /* Return function status */
1270 return status;
1274 * @brief This function allows to start regular conversion in DMA mode.
1275 * @note This function should be called only when SDADC instance is in idle state
1276 * or if injected conversion is ongoing.
1277 * @param hsdadc SDADC handle.
1278 * @param pData The destination buffer address.
1279 * @param Length The length of data to be transferred from SDADC peripheral to memory.
1280 * @retval HAL status
1282 HAL_StatusTypeDef HAL_SDADC_Start_DMA(SDADC_HandleTypeDef *hsdadc, uint32_t *pData,
1283 uint32_t Length)
1285 HAL_StatusTypeDef status = HAL_OK;
1287 /* Check parameters */
1288 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1289 assert_param(pData != NULL);
1290 assert_param(Length != 0U);
1292 /* Check that DMA is not enabled for injected conversion */
1293 if((hsdadc->Instance->CR1 & SDADC_CR1_JDMAEN) == SDADC_CR1_JDMAEN)
1295 status = HAL_ERROR;
1297 /* Check parameters compatibility */
1298 else if((hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER) && \
1299 (hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1300 (hsdadc->hdma->Init.Mode == DMA_NORMAL) && \
1301 (Length != 1U))
1303 status = HAL_ERROR;
1305 else if((hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER) && \
1306 (hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1307 (hsdadc->hdma->Init.Mode == DMA_CIRCULAR))
1309 status = HAL_ERROR;
1311 /* Check SDADC state */
1312 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1313 (hsdadc->State == HAL_SDADC_STATE_INJ))
1315 /* Set callbacks on DMA handler */
1316 hsdadc->hdma->XferCpltCallback = SDADC_DMARegularConvCplt;
1317 hsdadc->hdma->XferErrorCallback = SDADC_DMAError;
1318 if(hsdadc->hdma->Init.Mode == DMA_CIRCULAR)
1320 hsdadc->hdma->XferHalfCpltCallback = SDADC_DMARegularHalfConvCplt;
1323 /* Set RDMAEN bit in SDADC_CR1 register */
1324 hsdadc->Instance->CR1 |= SDADC_CR1_RDMAEN;
1326 /* Start DMA in interrupt mode */
1327 if(HAL_DMA_Start_IT(hsdadc->hdma, (uint32_t)&hsdadc->Instance->RDATAR, \
1328 (uint32_t) pData, Length) != HAL_OK)
1330 /* Set SDADC in error state */
1331 hsdadc->State = HAL_SDADC_STATE_ERROR;
1332 status = HAL_ERROR;
1334 else
1336 /* Start regular conversion */
1337 status = SDADC_RegConvStart(hsdadc);
1340 else
1342 status = HAL_ERROR;
1344 /* Return function status */
1345 return status;
1349 * @brief This function allows to stop regular conversion in DMA mode.
1350 * @note This function should be called only if regular conversion is ongoing.
1351 * @param hsdadc SDADC handle.
1352 * @retval HAL status
1354 HAL_StatusTypeDef HAL_SDADC_Stop_DMA(SDADC_HandleTypeDef *hsdadc)
1356 HAL_StatusTypeDef status = HAL_OK;
1358 /* Check parameters */
1359 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1361 /* Check SDADC state */
1362 if((hsdadc->State != HAL_SDADC_STATE_REG) && \
1363 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1365 /* Return error status */
1366 status = HAL_ERROR;
1368 else
1370 /* Clear RDMAEN bit in SDADC_CR1 register */
1371 hsdadc->Instance->CR1 &= ~(SDADC_CR1_RDMAEN);
1373 /* Stop current DMA transfer */
1374 if(HAL_DMA_Abort(hsdadc->hdma) != HAL_OK)
1376 /* Set SDADC in error state */
1377 hsdadc->State = HAL_SDADC_STATE_ERROR;
1378 status = HAL_ERROR;
1380 else
1382 /* Stop regular conversion */
1383 status = SDADC_RegConvStop(hsdadc);
1386 /* Return function status */
1387 return status;
1391 * @brief This function allows to get regular conversion value.
1392 * @param hsdadc SDADC handle.
1393 * @retval Regular conversion value
1395 uint32_t HAL_SDADC_GetValue(SDADC_HandleTypeDef *hsdadc)
1397 /* Check parameters */
1398 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1400 /* Return regular conversion value */
1401 return hsdadc->Instance->RDATAR;
1405 * @brief This function allows to start injected conversion in polling mode.
1406 * @note This function should be called only when SDADC instance is in idle state
1407 * or if regular conversion is ongoing.
1408 * @param hsdadc SDADC handle.
1409 * @retval HAL status
1411 HAL_StatusTypeDef HAL_SDADC_InjectedStart(SDADC_HandleTypeDef *hsdadc)
1413 HAL_StatusTypeDef status = HAL_OK;
1415 /* Check parameters */
1416 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1418 /* Check SDADC state */
1419 if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1420 (hsdadc->State == HAL_SDADC_STATE_REG))
1422 /* Start injected conversion */
1423 status = SDADC_InjConvStart(hsdadc);
1425 else
1427 status = HAL_ERROR;
1429 /* Return function status */
1430 return status;
1434 * @brief This function allows to poll for the end of injected conversion.
1435 * @note This function should be called only if injected conversion is ongoing.
1436 * @param hsdadc SDADC handle.
1437 * @param Timeout Timeout value in milliseconds.
1438 * @retval HAL status
1440 HAL_StatusTypeDef HAL_SDADC_PollForInjectedConversion(SDADC_HandleTypeDef* hsdadc,
1441 uint32_t Timeout)
1443 uint32_t tickstart;
1445 /* Check parameters */
1446 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1448 /* Check SDADC state */
1449 if((hsdadc->State != HAL_SDADC_STATE_INJ) && \
1450 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1452 /* Return error status */
1453 return HAL_ERROR;
1455 else
1457 /* Get timeout */
1458 tickstart = HAL_GetTick();
1460 /* Wait JEOCF bit in SDADC_ISR register */
1461 while((hsdadc->Instance->ISR & SDADC_ISR_JEOCF) != SDADC_ISR_JEOCF)
1463 /* Check the Timeout */
1464 if(Timeout != HAL_MAX_DELAY)
1466 if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout))
1468 /* Return timeout status */
1469 return HAL_TIMEOUT;
1473 /* Check if overrun occurs */
1474 if((hsdadc->Instance->ISR & SDADC_ISR_JOVRF) == SDADC_ISR_JOVRF)
1476 /* Update error code and call error callback */
1477 hsdadc->ErrorCode = SDADC_ERROR_INJECTED_OVERRUN;
1478 HAL_SDADC_ErrorCallback(hsdadc);
1480 /* Set CLRJOVRF bit in SDADC_CLRISR register */
1481 hsdadc->Instance->CLRISR |= SDADC_ISR_CLRJOVRF;
1483 /* Update remaining injected conversions */
1484 hsdadc->InjConvRemaining--;
1485 if(hsdadc->InjConvRemaining == 0U)
1487 /* end of injected sequence, reset the value */
1488 hsdadc->InjConvRemaining = hsdadc->InjectedChannelsNbr;
1491 /* Update SDADC state only if not continuous conversion, SW trigger */
1492 /* and end of injected sequence */
1493 if((hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1494 (hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER) && \
1495 (hsdadc->InjConvRemaining == hsdadc->InjectedChannelsNbr))
1497 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_INJ) ? \
1498 HAL_SDADC_STATE_READY : HAL_SDADC_STATE_REG;
1500 /* Return function status */
1501 return HAL_OK;
1506 * @brief This function allows to stop injected conversion in polling mode.
1507 * @note This function should be called only if injected conversion is ongoing.
1508 * @param hsdadc SDADC handle.
1509 * @retval HAL status
1511 HAL_StatusTypeDef HAL_SDADC_InjectedStop(SDADC_HandleTypeDef *hsdadc)
1513 HAL_StatusTypeDef status = HAL_OK;
1515 /* Check parameters */
1516 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1518 /* Check SDADC state */
1519 if((hsdadc->State != HAL_SDADC_STATE_INJ) && \
1520 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1522 /* Return error status */
1523 status = HAL_ERROR;
1525 else
1527 /* Stop injected conversion */
1528 status = SDADC_InjConvStop(hsdadc);
1530 /* Return function status */
1531 return status;
1535 * @brief This function allows to start injected conversion in interrupt mode.
1536 * @note This function should be called only when SDADC instance is in idle state
1537 * or if regular conversion is ongoing.
1538 * @param hsdadc SDADC handle.
1539 * @retval HAL status
1541 HAL_StatusTypeDef HAL_SDADC_InjectedStart_IT(SDADC_HandleTypeDef *hsdadc)
1543 HAL_StatusTypeDef status = HAL_OK;
1545 /* Check parameters */
1546 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1548 /* Check SDADC state */
1549 if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1550 (hsdadc->State == HAL_SDADC_STATE_REG))
1552 /* Set JEOCIE and JOVRIE bits in SDADC_CR1 register */
1553 hsdadc->Instance->CR1 |= (uint32_t) (SDADC_CR1_JEOCIE | SDADC_CR1_JOVRIE);
1555 /* Start injected conversion */
1556 status = SDADC_InjConvStart(hsdadc);
1558 else
1560 status = HAL_ERROR;
1562 /* Return function status */
1563 return status;
1567 * @brief This function allows to stop injected conversion in interrupt mode.
1568 * @note This function should be called only if injected conversion is ongoing.
1569 * @param hsdadc SDADC handle.
1570 * @retval HAL status
1572 HAL_StatusTypeDef HAL_SDADC_InjectedStop_IT(SDADC_HandleTypeDef *hsdadc)
1574 HAL_StatusTypeDef status = HAL_OK;
1576 /* Check parameters */
1577 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1579 /* Check SDADC state */
1580 if((hsdadc->State != HAL_SDADC_STATE_INJ) && \
1581 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1583 /* Return error status */
1584 status = HAL_ERROR;
1586 else
1588 /* Clear JEOCIE and JOVRIE bits in SDADC_CR1 register */
1589 hsdadc->Instance->CR1 &= (uint32_t) ~(SDADC_CR1_JEOCIE | SDADC_CR1_JOVRIE);
1591 /* Stop injected conversion */
1592 status = SDADC_InjConvStop(hsdadc);
1594 /* Return function status */
1595 return status;
1599 * @brief This function allows to start injected conversion in DMA mode.
1600 * @note This function should be called only when SDADC instance is in idle state
1601 * or if regular conversion is ongoing.
1602 * @param hsdadc SDADC handle.
1603 * @param pData The destination buffer address.
1604 * @param Length The length of data to be transferred from SDADC peripheral to memory.
1605 * @retval HAL status
1607 HAL_StatusTypeDef HAL_SDADC_InjectedStart_DMA(SDADC_HandleTypeDef *hsdadc, uint32_t *pData,
1608 uint32_t Length)
1610 HAL_StatusTypeDef status = HAL_OK;
1612 /* Check parameters */
1613 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1614 assert_param(pData != NULL);
1615 assert_param(Length != 0U);
1617 /* Check that DMA is not enabled for regular conversion */
1618 if((hsdadc->Instance->CR1 & SDADC_CR1_RDMAEN) == SDADC_CR1_RDMAEN)
1620 status = HAL_ERROR;
1622 /* Check parameters compatibility */
1623 else if((hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER) && \
1624 (hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1625 (hsdadc->hdma->Init.Mode == DMA_NORMAL) && \
1626 (Length > hsdadc->InjectedChannelsNbr))
1628 status = HAL_ERROR;
1630 else if((hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER) && \
1631 (hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1632 (hsdadc->hdma->Init.Mode == DMA_CIRCULAR))
1634 status = HAL_ERROR;
1636 /* Check SDADC state */
1637 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1638 (hsdadc->State == HAL_SDADC_STATE_REG))
1640 /* Set callbacks on DMA handler */
1641 hsdadc->hdma->XferCpltCallback = SDADC_DMAInjectedConvCplt;
1642 hsdadc->hdma->XferErrorCallback = SDADC_DMAError;
1643 if(hsdadc->hdma->Init.Mode == DMA_CIRCULAR)
1645 hsdadc->hdma->XferHalfCpltCallback = SDADC_DMAInjectedHalfConvCplt;
1648 /* Set JDMAEN bit in SDADC_CR1 register */
1649 hsdadc->Instance->CR1 |= SDADC_CR1_JDMAEN;
1651 /* Start DMA in interrupt mode */
1652 if(HAL_DMA_Start_IT(hsdadc->hdma, (uint32_t)&hsdadc->Instance->JDATAR, \
1653 (uint32_t) pData, Length) != HAL_OK)
1655 /* Set SDADC in error state */
1656 hsdadc->State = HAL_SDADC_STATE_ERROR;
1657 status = HAL_ERROR;
1659 else
1661 /* Start injected conversion */
1662 status = SDADC_InjConvStart(hsdadc);
1665 else
1667 status = HAL_ERROR;
1669 /* Return function status */
1670 return status;
1674 * @brief This function allows to stop injected conversion in DMA mode.
1675 * @note This function should be called only if injected conversion is ongoing.
1676 * @param hsdadc SDADC handle.
1677 * @retval HAL status
1679 HAL_StatusTypeDef HAL_SDADC_InjectedStop_DMA(SDADC_HandleTypeDef *hsdadc)
1681 HAL_StatusTypeDef status = HAL_OK;
1683 /* Check parameters */
1684 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1686 /* Check SDADC state */
1687 if((hsdadc->State != HAL_SDADC_STATE_INJ) && \
1688 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1690 /* Return error status */
1691 status = HAL_ERROR;
1693 else
1695 /* Clear JDMAEN bit in SDADC_CR1 register */
1696 hsdadc->Instance->CR1 &= ~(SDADC_CR1_JDMAEN);
1698 /* Stop current DMA transfer */
1699 if(HAL_DMA_Abort(hsdadc->hdma) != HAL_OK)
1701 /* Set SDADC in error state */
1702 hsdadc->State = HAL_SDADC_STATE_ERROR;
1703 status = HAL_ERROR;
1705 else
1707 /* Stop injected conversion */
1708 status = SDADC_InjConvStop(hsdadc);
1711 /* Return function status */
1712 return status;
1716 * @brief This function allows to get injected conversion value.
1717 * @param hsdadc SDADC handle.
1718 * @param Channel Corresponding channel of injected conversion.
1719 * @retval Injected conversion value
1721 uint32_t HAL_SDADC_InjectedGetValue(SDADC_HandleTypeDef *hsdadc, uint32_t* Channel)
1723 uint32_t value = 0U;
1725 /* Check parameters */
1726 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1727 assert_param(Channel != NULL);
1729 /* Read SDADC_JDATAR register and extract channel and conversion value */
1730 value = hsdadc->Instance->JDATAR;
1731 *Channel = ((value & SDADC_JDATAR_JDATACH) >> SDADC_JDATAR_CH_OFFSET);
1732 value &= SDADC_JDATAR_JDATA;
1734 /* Return injected conversion value */
1735 return value;
1739 * @brief This function allows to start multimode regular conversions in DMA mode.
1740 * @note This function should be called only when SDADC instance is in idle state
1741 * or if injected conversion is ongoing.
1742 * @param hsdadc SDADC handle.
1743 * @param pData The destination buffer address.
1744 * @param Length The length of data to be transferred from SDADC peripheral to memory.
1745 * @retval HAL status
1747 HAL_StatusTypeDef HAL_SDADC_MultiModeStart_DMA(SDADC_HandleTypeDef* hsdadc, uint32_t* pData,
1748 uint32_t Length)
1750 HAL_StatusTypeDef status = HAL_OK;
1752 /* Check parameters */
1753 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1754 assert_param(pData != NULL);
1755 assert_param(Length != 0U);
1757 /* Check instance is SDADC1 */
1758 if(hsdadc->Instance != SDADC1)
1760 status = HAL_ERROR;
1762 /* Check that DMA is not enabled for injected conversion */
1763 else if((hsdadc->Instance->CR1 & SDADC_CR1_JDMAEN) == SDADC_CR1_JDMAEN)
1765 status = HAL_ERROR;
1767 /* Check parameters compatibility */
1768 else if((hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER) && \
1769 (hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1770 (hsdadc->hdma->Init.Mode == DMA_NORMAL) && \
1771 (Length != 1U))
1773 status = HAL_ERROR;
1775 else if((hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER) && \
1776 (hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1777 (hsdadc->hdma->Init.Mode == DMA_CIRCULAR))
1779 status = HAL_ERROR;
1781 /* Check SDADC state */
1782 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1783 (hsdadc->State == HAL_SDADC_STATE_INJ))
1785 /* Set callbacks on DMA handler */
1786 hsdadc->hdma->XferCpltCallback = SDADC_DMARegularConvCplt;
1787 hsdadc->hdma->XferErrorCallback = SDADC_DMAError;
1788 if(hsdadc->hdma->Init.Mode == DMA_CIRCULAR)
1790 hsdadc->hdma->XferHalfCpltCallback = SDADC_DMARegularHalfConvCplt;
1792 /* Set RDMAEN bit in SDADC_CR1 register */
1793 hsdadc->Instance->CR1 |= SDADC_CR1_RDMAEN;
1795 /* Start DMA in interrupt mode */
1796 if(hsdadc->RegularMultimode == SDADC_MULTIMODE_SDADC1_SDADC2)
1798 status = HAL_DMA_Start_IT(hsdadc->hdma, (uint32_t)&hsdadc->Instance->RDATA12R, \
1799 (uint32_t) pData, Length);
1801 else
1803 status = HAL_DMA_Start_IT(hsdadc->hdma, (uint32_t)&hsdadc->Instance->RDATA13R, \
1804 (uint32_t) pData, Length);
1806 if(status != HAL_OK)
1808 /* Set SDADC in error state */
1809 hsdadc->State = HAL_SDADC_STATE_ERROR;
1810 status = HAL_ERROR;
1812 else
1814 /* Start regular conversion */
1815 status = SDADC_RegConvStart(hsdadc);
1818 else
1820 status = HAL_ERROR;
1822 /* Return function status */
1823 return status;
1827 * @brief This function allows to stop multimode regular conversions in DMA mode.
1828 * @note This function should be called only if regular conversion is ongoing.
1829 * @param hsdadc SDADC handle.
1830 * @retval HAL status
1832 HAL_StatusTypeDef HAL_SDADC_MultiModeStop_DMA(SDADC_HandleTypeDef* hsdadc)
1834 HAL_StatusTypeDef status = HAL_OK;
1836 /* Check parameters */
1837 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1839 /* Check instance is SDADC1 */
1840 if(hsdadc->Instance != SDADC1)
1842 status = HAL_ERROR;
1844 /* Check SDADC state */
1845 else if((hsdadc->State != HAL_SDADC_STATE_REG) && \
1846 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
1848 /* Return error status */
1849 status = HAL_ERROR;
1851 else
1853 /* Clear RDMAEN bit in SDADC_CR1 register */
1854 hsdadc->Instance->CR1 &= ~(SDADC_CR1_RDMAEN);
1856 /* Stop current DMA transfer */
1857 if(HAL_DMA_Abort(hsdadc->hdma) != HAL_OK)
1859 /* Set SDADC in error state */
1860 hsdadc->State = HAL_SDADC_STATE_ERROR;
1861 status = HAL_ERROR;
1863 else
1865 /* Stop regular conversion */
1866 status = SDADC_RegConvStop(hsdadc);
1869 /* Return function status */
1870 return status;
1874 * @brief This function allows to get multimode regular conversion value.
1875 * @param hsdadc SDADC handle.
1876 * @retval Multimode regular conversion value
1878 uint32_t HAL_SDADC_MultiModeGetValue(SDADC_HandleTypeDef* hsdadc)
1880 uint32_t value = 0U;
1882 /* Check parameters and check instance is SDADC1 */
1883 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1884 assert_param(hsdadc->Instance == SDADC1);
1886 /* read multimode regular value */
1887 value = (hsdadc->RegularMultimode == SDADC_MULTIMODE_SDADC1_SDADC2) ? \
1888 hsdadc->Instance->RDATA12R : hsdadc->Instance->RDATA13R;
1890 /* Return multimode regular conversions value */
1891 return value;
1895 * @brief This function allows to start multimode injected conversions in DMA mode.
1896 * @note This function should be called only when SDADC instance is in idle state
1897 * or if regular conversion is ongoing.
1898 * @param hsdadc SDADC handle.
1899 * @param pData The destination buffer address.
1900 * @param Length The length of data to be transferred from SDADC peripheral to memory.
1901 * @retval HAL status
1903 HAL_StatusTypeDef HAL_SDADC_InjectedMultiModeStart_DMA(SDADC_HandleTypeDef* hsdadc,
1904 uint32_t* pData, uint32_t Length)
1906 HAL_StatusTypeDef status = HAL_OK;
1908 /* Check parameters */
1909 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1910 assert_param(pData != NULL);
1911 assert_param(Length != 0U);
1913 /* Check instance is SDADC1 */
1914 if(hsdadc->Instance != SDADC1)
1916 status = HAL_ERROR;
1918 /* Check that DMA is not enabled for regular conversion */
1919 else if((hsdadc->Instance->CR1 & SDADC_CR1_RDMAEN) == SDADC_CR1_RDMAEN)
1921 status = HAL_ERROR;
1923 /* Check parameters compatibility */
1924 else if((hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER) && \
1925 (hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1926 (hsdadc->hdma->Init.Mode == DMA_NORMAL) && \
1927 (Length > (hsdadc->InjectedChannelsNbr << 1U)))
1929 status = HAL_ERROR;
1931 else if((hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER) && \
1932 (hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_OFF) && \
1933 (hsdadc->hdma->Init.Mode == DMA_CIRCULAR))
1935 status = HAL_ERROR;
1937 /* Check SDADC state */
1938 else if((hsdadc->State == HAL_SDADC_STATE_READY) || \
1939 (hsdadc->State == HAL_SDADC_STATE_REG))
1941 /* Set callbacks on DMA handler */
1942 hsdadc->hdma->XferCpltCallback = SDADC_DMAInjectedConvCplt;
1943 hsdadc->hdma->XferErrorCallback = SDADC_DMAError;
1944 if(hsdadc->hdma->Init.Mode == DMA_CIRCULAR)
1946 hsdadc->hdma->XferHalfCpltCallback = SDADC_DMAInjectedHalfConvCplt;
1948 /* Set JDMAEN bit in SDADC_CR1 register */
1949 hsdadc->Instance->CR1 |= SDADC_CR1_JDMAEN;
1951 /* Start DMA in interrupt mode */
1952 if(hsdadc->InjectedMultimode == SDADC_MULTIMODE_SDADC1_SDADC2)
1954 status = HAL_DMA_Start_IT(hsdadc->hdma, (uint32_t)&hsdadc->Instance->JDATA12R, \
1955 (uint32_t) pData, Length);
1957 else
1959 status = HAL_DMA_Start_IT(hsdadc->hdma, (uint32_t)&hsdadc->Instance->JDATA13R, \
1960 (uint32_t) pData, Length);
1962 if(status != HAL_OK)
1964 /* Set SDADC in error state */
1965 hsdadc->State = HAL_SDADC_STATE_ERROR;
1966 status = HAL_ERROR;
1968 else
1970 /* Start injected conversion */
1971 status = SDADC_InjConvStart(hsdadc);
1974 else
1976 status = HAL_ERROR;
1978 /* Return function status */
1979 return status;
1983 * @brief This function allows to stop multimode injected conversions in DMA mode.
1984 * @note This function should be called only if injected conversion is ongoing.
1985 * @param hsdadc SDADC handle.
1986 * @retval HAL status
1988 HAL_StatusTypeDef HAL_SDADC_InjectedMultiModeStop_DMA(SDADC_HandleTypeDef* hsdadc)
1990 HAL_StatusTypeDef status = HAL_OK;
1992 /* Check parameters */
1993 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
1995 /* Check instance is SDADC1 */
1996 if(hsdadc->Instance != SDADC1)
1998 status = HAL_ERROR;
2000 /* Check SDADC state */
2001 else if((hsdadc->State != HAL_SDADC_STATE_INJ) && \
2002 (hsdadc->State != HAL_SDADC_STATE_REG_INJ))
2004 /* Return error status */
2005 status = HAL_ERROR;
2007 else
2009 /* Clear JDMAEN bit in SDADC_CR1 register */
2010 hsdadc->Instance->CR1 &= ~(SDADC_CR1_JDMAEN);
2012 /* Stop current DMA transfer */
2013 if(HAL_DMA_Abort(hsdadc->hdma) != HAL_OK)
2015 /* Set SDADC in error state */
2016 hsdadc->State = HAL_SDADC_STATE_ERROR;
2017 status = HAL_ERROR;
2019 else
2021 /* Stop injected conversion */
2022 status = SDADC_InjConvStop(hsdadc);
2025 /* Return function status */
2026 return status;
2030 * @brief This function allows to get multimode injected conversion value.
2031 * @param hsdadc SDADC handle.
2032 * @retval Multimode injected conversion value
2034 uint32_t HAL_SDADC_InjectedMultiModeGetValue(SDADC_HandleTypeDef* hsdadc)
2036 uint32_t value = 0U;
2038 /* Check parameters and check instance is SDADC1 */
2039 assert_param(IS_SDADC_ALL_INSTANCE(hsdadc->Instance));
2040 assert_param(hsdadc->Instance == SDADC1);
2042 /* read multimode injected value */
2043 value = (hsdadc->InjectedMultimode == SDADC_MULTIMODE_SDADC1_SDADC2) ? \
2044 hsdadc->Instance->JDATA12R : hsdadc->Instance->JDATA13R;
2046 /* Return multimode injected conversions value */
2047 return value;
2051 * @brief This function handles the SDADC interrupts.
2052 * @param hsdadc SDADC handle.
2053 * @retval None
2055 void HAL_SDADC_IRQHandler(SDADC_HandleTypeDef* hsdadc)
2057 /* Check if end of regular conversion */
2058 if(((hsdadc->Instance->ISR & SDADC_ISR_REOCF) == SDADC_ISR_REOCF) && \
2059 ((hsdadc->Instance->CR1 & SDADC_CR1_REOCIE) == SDADC_CR1_REOCIE))
2061 /* Call regular conversion complete callback */
2062 HAL_SDADC_ConvCpltCallback(hsdadc);
2064 /* End of conversion if mode is not continuous and software trigger */
2065 if((hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_OFF) && \
2066 (hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER))
2068 /* Clear REOCIE and ROVRIE bits in SDADC_CR1 register */
2069 hsdadc->Instance->CR1 &= ~(SDADC_CR1_REOCIE | SDADC_CR1_ROVRIE);
2071 /* Update SDADC state */
2072 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_REG) ? \
2073 HAL_SDADC_STATE_READY : HAL_SDADC_STATE_INJ;
2076 /* Check if end of injected conversion */
2077 else if(((hsdadc->Instance->ISR & SDADC_ISR_JEOCF) == SDADC_ISR_JEOCF) && \
2078 ((hsdadc->Instance->CR1 & SDADC_CR1_JEOCIE) == SDADC_CR1_JEOCIE))
2080 /* Call injected conversion complete callback */
2081 HAL_SDADC_InjectedConvCpltCallback(hsdadc);
2083 /* Update remaining injected conversions */
2084 hsdadc->InjConvRemaining--;
2085 if(hsdadc->InjConvRemaining ==0U)
2087 /* end of injected sequence, reset the value */
2088 hsdadc->InjConvRemaining = hsdadc->InjectedChannelsNbr;
2090 /* End of conversion if mode is not continuous, software trigger */
2091 /* and end of injected sequence */
2092 if((hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_OFF) && \
2093 (hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER) && \
2094 (hsdadc->InjConvRemaining == hsdadc->InjectedChannelsNbr))
2096 /* Clear JEOCIE and JOVRIE bits in SDADC_CR1 register */
2097 hsdadc->Instance->CR1 &= ~(SDADC_CR1_JEOCIE | SDADC_CR1_JOVRIE);
2099 /* Update SDADC state */
2100 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_INJ) ? \
2101 HAL_SDADC_STATE_READY : HAL_SDADC_STATE_REG;
2104 /* Check if end of calibration */
2105 else if(((hsdadc->Instance->ISR & SDADC_ISR_EOCALF) == SDADC_ISR_EOCALF) && \
2106 ((hsdadc->Instance->CR1 & SDADC_CR1_EOCALIE) == SDADC_CR1_EOCALIE))
2108 /* Clear EOCALIE bit in SDADC_CR1 register */
2109 hsdadc->Instance->CR1 &= ~(SDADC_CR1_EOCALIE);
2111 /* Set CLREOCALF bit in SDADC_CLRISR register */
2112 hsdadc->Instance->CLRISR |= SDADC_ISR_CLREOCALF;
2114 /* Call calibration callback */
2115 HAL_SDADC_CalibrationCpltCallback(hsdadc);
2117 /* Update SDADC state */
2118 hsdadc->State = HAL_SDADC_STATE_READY;
2120 /* Check if overrun occurs during regular conversion */
2121 else if(((hsdadc->Instance->ISR & SDADC_ISR_ROVRF) == SDADC_ISR_ROVRF) && \
2122 ((hsdadc->Instance->CR1 & SDADC_CR1_ROVRIE) == SDADC_CR1_ROVRIE))
2124 /* Set CLRROVRF bit in SDADC_CLRISR register */
2125 hsdadc->Instance->CLRISR |= SDADC_ISR_CLRROVRF;
2127 /* Update error code */
2128 hsdadc->ErrorCode = SDADC_ERROR_REGULAR_OVERRUN;
2130 /* Call error callback */
2131 HAL_SDADC_ErrorCallback(hsdadc);
2133 /* Check if overrun occurs during injected conversion */
2134 else if(((hsdadc->Instance->ISR & SDADC_ISR_JOVRF) == SDADC_ISR_JOVRF) && \
2135 ((hsdadc->Instance->CR1 & SDADC_CR1_JOVRIE) == SDADC_CR1_JOVRIE))
2137 /* Set CLRJOVRF bit in SDADC_CLRISR register */
2138 hsdadc->Instance->CLRISR |= SDADC_ISR_CLRJOVRF;
2140 /* Update error code */
2141 hsdadc->ErrorCode = SDADC_ERROR_INJECTED_OVERRUN;
2143 /* Call error callback */
2144 HAL_SDADC_ErrorCallback(hsdadc);
2146 else
2148 /* No additional IRQ source */
2151 return;
2155 * @brief Calibration complete callback.
2156 * @param hsdadc SDADC handle.
2157 * @retval None
2159 __weak void HAL_SDADC_CalibrationCpltCallback(SDADC_HandleTypeDef* hsdadc)
2161 /* Prevent unused argument(s) compilation warning */
2162 UNUSED(hsdadc);
2164 /* NOTE : This function should not be modified, when the callback is needed,
2165 the HAL_SDADC_CalibrationCpltCallback could be implemented in the user file
2170 * @brief Half regular conversion complete callback.
2171 * @param hsdadc SDADC handle.
2172 * @retval None
2174 __weak void HAL_SDADC_ConvHalfCpltCallback(SDADC_HandleTypeDef* hsdadc)
2176 /* Prevent unused argument(s) compilation warning */
2177 UNUSED(hsdadc);
2179 /* NOTE : This function should not be modified, when the callback is needed,
2180 the HAL_SDADC_ConvHalfCpltCallback could be implemented in the user file
2185 * @brief Regular conversion complete callback.
2186 * @note In interrupt mode, user has to read conversion value in this function
2187 using HAL_SDADC_GetValue or HAL_SDADC_MultiModeGetValue.
2188 * @param hsdadc SDADC handle.
2189 * @retval None
2191 __weak void HAL_SDADC_ConvCpltCallback(SDADC_HandleTypeDef* hsdadc)
2193 /* Prevent unused argument(s) compilation warning */
2194 UNUSED(hsdadc);
2196 /* NOTE : This function should not be modified, when the callback is needed,
2197 the HAL_SDADC_ConvCpltCallback could be implemented in the user file.
2202 * @brief Half injected conversion complete callback.
2203 * @param hsdadc SDADC handle.
2204 * @retval None
2206 __weak void HAL_SDADC_InjectedConvHalfCpltCallback(SDADC_HandleTypeDef* hsdadc)
2208 /* Prevent unused argument(s) compilation warning */
2209 UNUSED(hsdadc);
2211 /* NOTE : This function should not be modified, when the callback is needed,
2212 the HAL_SDADC_InjectedConvHalfCpltCallback could be implemented in the user file.
2217 * @brief Injected conversion complete callback.
2218 * @note In interrupt mode, user has to read conversion value in this function
2219 using HAL_SDADC_InjectedGetValue or HAL_SDADC_InjectedMultiModeGetValue.
2220 * @param hsdadc SDADC handle.
2221 * @retval None
2223 __weak void HAL_SDADC_InjectedConvCpltCallback(SDADC_HandleTypeDef* hsdadc)
2225 /* Prevent unused argument(s) compilation warning */
2226 UNUSED(hsdadc);
2228 /* NOTE : This function should not be modified, when the callback is needed,
2229 the HAL_SDADC_InjectedConvCpltCallback could be implemented in the user file.
2234 * @brief Error callback.
2235 * @param hsdadc SDADC handle.
2236 * @retval None
2238 __weak void HAL_SDADC_ErrorCallback(SDADC_HandleTypeDef* hsdadc)
2240 /* Prevent unused argument(s) compilation warning */
2241 UNUSED(hsdadc);
2243 /* NOTE : This function should not be modified, when the callback is needed,
2244 the HAL_SDADC_ErrorCallback could be implemented in the user file.
2249 * @brief DMA half transfer complete callback for regular conversion.
2250 * @param hdma DMA handle.
2251 * @retval None
2253 static void SDADC_DMARegularHalfConvCplt(DMA_HandleTypeDef *hdma)
2255 /* Get SDADC handle */
2256 SDADC_HandleTypeDef* hsdadc = (SDADC_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent;
2258 /* Call regular half conversion complete callback */
2259 HAL_SDADC_ConvHalfCpltCallback(hsdadc);
2263 * @brief DMA transfer complete callback for regular conversion.
2264 * @param hdma DMA handle.
2265 * @retval None
2267 static void SDADC_DMARegularConvCplt(DMA_HandleTypeDef *hdma)
2269 /* Get SDADC handle */
2270 SDADC_HandleTypeDef* hsdadc = (SDADC_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent;
2272 /* Call regular conversion complete callback */
2273 HAL_SDADC_ConvCpltCallback(hsdadc);
2277 * @brief DMA half transfer complete callback for injected conversion.
2278 * @param hdma DMA handle.
2279 * @retval None
2281 static void SDADC_DMAInjectedHalfConvCplt(DMA_HandleTypeDef *hdma)
2283 /* Get SDADC handle */
2284 SDADC_HandleTypeDef* hsdadc = (SDADC_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent;
2286 /* Call injected half conversion complete callback */
2287 HAL_SDADC_InjectedConvHalfCpltCallback(hsdadc);
2291 * @brief DMA transfer complete callback for injected conversion.
2292 * @param hdma DMA handle.
2293 * @retval None
2295 static void SDADC_DMAInjectedConvCplt(DMA_HandleTypeDef *hdma)
2297 /* Get SDADC handle */
2298 SDADC_HandleTypeDef* hsdadc = (SDADC_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent;
2300 /* Call injected conversion complete callback */
2301 HAL_SDADC_InjectedConvCpltCallback(hsdadc);
2305 * @brief DMA error callback.
2306 * @param hdma DMA handle.
2307 * @retval None
2309 static void SDADC_DMAError(DMA_HandleTypeDef *hdma)
2311 /* Get SDADC handle */
2312 SDADC_HandleTypeDef* hsdadc = (SDADC_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent;
2314 /* Update error code */
2315 hsdadc->ErrorCode = SDADC_ERROR_DMA;
2317 /* Call error callback */
2318 HAL_SDADC_ErrorCallback(hsdadc);
2322 * @}
2325 /** @defgroup SDADC_Exported_Functions_Group4 Peripheral State functions
2326 * @brief SDADC Peripheral State functions
2328 @verbatim
2329 ===============================================================================
2330 ##### ADC Peripheral State functions #####
2331 ===============================================================================
2332 [..] This subsection provides functions allowing to
2333 (+) Get the SDADC state
2334 (+) Get the SDADC Error
2336 @endverbatim
2337 * @{
2341 * @brief This function allows to get the current SDADC state.
2342 * @param hsdadc SDADC handle.
2343 * @retval SDADC state.
2345 HAL_SDADC_StateTypeDef HAL_SDADC_GetState(SDADC_HandleTypeDef* hsdadc)
2347 return hsdadc->State;
2351 * @brief This function allows to get the current SDADC error code.
2352 * @param hsdadc SDADC handle.
2353 * @retval SDADC error code.
2355 uint32_t HAL_SDADC_GetError(SDADC_HandleTypeDef* hsdadc)
2357 return hsdadc->ErrorCode;
2361 * @}
2364 /** @addtogroup SDADC_Private_Functions SDADC Private Functions
2365 * @{
2369 * @brief This function allows to enter in init mode for SDADC instance.
2370 * @param hsdadc SDADC handle.
2371 * @retval HAL status.
2373 static HAL_StatusTypeDef SDADC_EnterInitMode(SDADC_HandleTypeDef* hsdadc)
2375 uint32_t tickstart = 0U;
2377 /* Set INIT bit on SDADC_CR1 register */
2378 hsdadc->Instance->CR1 |= SDADC_CR1_INIT;
2380 /* Wait INITRDY bit on SDADC_ISR */
2381 tickstart = HAL_GetTick();
2382 while((hsdadc->Instance->ISR & SDADC_ISR_INITRDY) == (uint32_t)RESET)
2384 if((HAL_GetTick()-tickstart) > SDADC_TIMEOUT)
2386 return HAL_TIMEOUT;
2390 /* Return HAL status */
2391 return HAL_OK;
2395 * @brief This function allows to exit from init mode for SDADC instance.
2396 * @param hsdadc SDADC handle.
2397 * @retval None.
2399 static void SDADC_ExitInitMode(SDADC_HandleTypeDef* hsdadc)
2401 /* Reset INIT bit in SDADC_CR1 register */
2402 hsdadc->Instance->CR1 &= ~(SDADC_CR1_INIT);
2406 * @brief This function allows to get the number of injected channels.
2407 * @param Channels bitfield of injected channels.
2408 * @retval Number of injected channels.
2410 static uint32_t SDADC_GetInjChannelsNbr(uint32_t Channels)
2412 uint32_t nbChannels = 0U;
2413 uint32_t tmp,i;
2415 /* Get the number of channels from bitfield */
2416 tmp = (uint32_t) (Channels & SDADC_LSB_MASK);
2417 for(i = 0U ; i < 9U ; i++)
2419 if((tmp & 0x00000001U) != 0U)
2421 nbChannels++;
2423 tmp = (uint32_t) (tmp >> 1U);
2425 return nbChannels;
2429 * @brief This function allows to really start regular conversion.
2430 * @param hsdadc SDADC handle.
2431 * @retval HAL status.
2433 static HAL_StatusTypeDef SDADC_RegConvStart(SDADC_HandleTypeDef* hsdadc)
2435 HAL_StatusTypeDef status = HAL_OK;
2437 /* Check regular trigger */
2438 if(hsdadc->RegularTrigger == SDADC_SOFTWARE_TRIGGER)
2440 /* Set RSWSTART bit in SDADC_CR2 register */
2441 hsdadc->Instance->CR2 |= SDADC_CR2_RSWSTART;
2443 else /* synchronuous trigger */
2445 /* Enter init mode */
2446 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
2448 /* Set SDADC in error state */
2449 hsdadc->State = HAL_SDADC_STATE_ERROR;
2450 status = HAL_TIMEOUT;
2452 else
2454 /* Set RSYNC bit in SDADC_CR1 register */
2455 hsdadc->Instance->CR1 |= SDADC_CR1_RSYNC;
2457 /* Exit init mode */
2458 SDADC_ExitInitMode(hsdadc);
2461 /* Update SDADC state only if status is OK */
2462 if(status == HAL_OK)
2464 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_READY) ? \
2465 HAL_SDADC_STATE_REG : HAL_SDADC_STATE_REG_INJ;
2467 /* Return function status */
2468 return status;
2472 * @brief This function allows to really stop regular conversion.
2473 * @param hsdadc SDADC handle.
2474 * @retval HAL status.
2476 static HAL_StatusTypeDef SDADC_RegConvStop(SDADC_HandleTypeDef* hsdadc)
2478 uint32_t tickstart;
2479 __IO uint32_t dummy_read_for_register_reset;
2481 /* Check continuous mode */
2482 if(hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_ON)
2484 /* Clear REOCF by reading SDADC_RDATAR register */
2485 dummy_read_for_register_reset = hsdadc->Instance->RDATAR;
2486 UNUSED(dummy_read_for_register_reset);
2488 /* Clear RCONT bit in SDADC_CR2 register */
2489 hsdadc->Instance->CR2 &= ~(SDADC_CR2_RCONT);
2491 /* Wait for the end of regular conversion */
2492 tickstart = HAL_GetTick();
2493 while((hsdadc->Instance->ISR & SDADC_ISR_RCIP) != 0U)
2495 if((HAL_GetTick()-tickstart) > SDADC_TIMEOUT)
2497 /* Set SDADC in error state and return timeout status */
2498 hsdadc->State = HAL_SDADC_STATE_ERROR;
2499 return HAL_TIMEOUT;
2502 /* Check if trigger is synchronuous */
2503 if(hsdadc->RegularTrigger == SDADC_SYNCHRONOUS_TRIGGER)
2505 /* Enter init mode */
2506 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
2508 /* Set SDADC in error state and return timeout status */
2509 hsdadc->State = HAL_SDADC_STATE_ERROR;
2510 return HAL_TIMEOUT;
2512 else
2514 /* Clear RSYNC bit in SDADC_CR1 register */
2515 hsdadc->Instance->CR1 &= ~(SDADC_CR1_RSYNC);
2517 /* Exit init mode */
2518 SDADC_ExitInitMode(hsdadc);
2521 /* Check if continuous mode */
2522 if(hsdadc->RegularContMode == SDADC_CONTINUOUS_CONV_ON)
2524 /* Restore RCONT bit in SDADC_CR2 register */
2525 hsdadc->Instance->CR2 |= SDADC_CR2_RCONT;
2527 /* Clear REOCF by reading SDADC_RDATAR register */
2528 dummy_read_for_register_reset = hsdadc->Instance->RDATAR;
2529 UNUSED(dummy_read_for_register_reset);
2531 /* Set CLRROVRF bit in SDADC_CLRISR register */
2532 hsdadc->Instance->CLRISR |= SDADC_ISR_CLRROVRF;
2534 /* Update SDADC state */
2535 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_REG) ? \
2536 HAL_SDADC_STATE_READY : HAL_SDADC_STATE_INJ;
2538 /* Return function status */
2539 return HAL_OK;
2543 * @brief This function allows to really start injected conversion.
2544 * @param hsdadc SDADC handle.
2545 * @retval HAL status.
2547 static HAL_StatusTypeDef SDADC_InjConvStart(SDADC_HandleTypeDef* hsdadc)
2549 HAL_StatusTypeDef status = HAL_OK;
2551 /* Initialize number of injected conversions remaining */
2552 hsdadc->InjConvRemaining = hsdadc->InjectedChannelsNbr;
2554 /* Check injected trigger */
2555 if(hsdadc->InjectedTrigger == SDADC_SOFTWARE_TRIGGER)
2557 /* Set JSWSTART bit in SDADC_CR2 register */
2558 hsdadc->Instance->CR2 |= SDADC_CR2_JSWSTART;
2560 else /* external or synchronuous trigger */
2562 /* Enter init mode */
2563 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
2565 /* Set SDADC in error state */
2566 hsdadc->State = HAL_SDADC_STATE_ERROR;
2567 status = HAL_TIMEOUT;
2569 else
2571 if(hsdadc->InjectedTrigger == SDADC_SYNCHRONOUS_TRIGGER)
2573 /* Set JSYNC bit in SDADC_CR1 register */
2574 hsdadc->Instance->CR1 |= SDADC_CR1_JSYNC;
2576 else /* external trigger */
2578 /* Set JEXTEN[1:0] bits in SDADC_CR2 register */
2579 hsdadc->Instance->CR2 |= hsdadc->ExtTriggerEdge;
2581 /* Exit init mode */
2582 SDADC_ExitInitMode(hsdadc);
2585 /* Update SDADC state only if status is OK */
2586 if(status == HAL_OK)
2588 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_READY) ? \
2589 HAL_SDADC_STATE_INJ : HAL_SDADC_STATE_REG_INJ;
2591 /* Return function status */
2592 return status;
2596 * @brief This function allows to really stop injected conversion.
2597 * @param hsdadc SDADC handle.
2598 * @retval HAL status.
2600 static HAL_StatusTypeDef SDADC_InjConvStop(SDADC_HandleTypeDef* hsdadc)
2602 uint32_t tickstart;
2603 __IO uint32_t dummy_read_for_register_reset;
2605 /* Check continuous mode */
2606 if(hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_ON)
2608 /* Clear JEOCF by reading SDADC_JDATAR register */
2609 dummy_read_for_register_reset = hsdadc->Instance->JDATAR;
2610 UNUSED(dummy_read_for_register_reset);
2612 /* Clear JCONT bit in SDADC_CR2 register */
2613 hsdadc->Instance->CR2 &= ~(SDADC_CR2_JCONT);
2615 /* Wait for the end of injected conversion */
2616 tickstart = HAL_GetTick();
2617 while((hsdadc->Instance->ISR & SDADC_ISR_JCIP) != 0U)
2619 if((HAL_GetTick()-tickstart) > SDADC_TIMEOUT)
2621 /* Set SDADC in error state and return timeout status */
2622 hsdadc->State = HAL_SDADC_STATE_ERROR;
2623 return HAL_TIMEOUT;
2626 /* Check if trigger is not software */
2627 if(hsdadc->InjectedTrigger != SDADC_SOFTWARE_TRIGGER)
2629 /* Enter init mode */
2630 if(SDADC_EnterInitMode(hsdadc) != HAL_OK)
2632 /* Set SDADC in error state and return timeout status */
2633 hsdadc->State = HAL_SDADC_STATE_ERROR;
2634 return HAL_TIMEOUT;
2636 else
2638 /* Check if trigger is synchronuous */
2639 if(hsdadc->InjectedTrigger == SDADC_SYNCHRONOUS_TRIGGER)
2641 /* Clear JSYNC bit in SDADC_CR1 register */
2642 hsdadc->Instance->CR1 &= ~(SDADC_CR1_JSYNC);
2644 else /* external trigger */
2646 /* Clear JEXTEN[1:0] bits in SDADC_CR2 register */
2647 hsdadc->Instance->CR2 &= ~(SDADC_CR2_JEXTEN);
2649 /* Exit init mode */
2650 SDADC_ExitInitMode(hsdadc);
2653 /* Check if continuous mode */
2654 if(hsdadc->InjectedContMode == SDADC_CONTINUOUS_CONV_ON)
2656 /* Restore JCONT bit in SDADC_CR2 register */
2657 hsdadc->Instance->CR2 |= SDADC_CR2_JCONT;
2659 /* Clear JEOCF by reading SDADC_JDATAR register */
2660 dummy_read_for_register_reset = hsdadc->Instance->JDATAR;
2661 UNUSED(dummy_read_for_register_reset);
2663 /* Set CLRJOVRF bit in SDADC_CLRISR register */
2664 hsdadc->Instance->CLRISR |= SDADC_ISR_CLRJOVRF;
2666 /* Update SDADC state */
2667 hsdadc->State = (hsdadc->State == HAL_SDADC_STATE_INJ) ? \
2668 HAL_SDADC_STATE_READY : HAL_SDADC_STATE_REG;
2670 /* Return function status */
2671 return HAL_OK;
2675 * @}
2679 * @}
2683 * @}
2686 #endif /* defined(STM32F373xC) || defined(STM32F378xx) */
2687 #endif /* HAL_SDADC_MODULE_ENABLED */
2689 * @}
2692 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/