Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_tsc.c
blob62704a0e5013cf03d7df7d94ee09d049c7ffde60
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_tsc.c
4 * @author MCD Application Team
5 * @brief This file provides firmware functions to manage the following
6 * functionalities of the Touch Sensing Controller (TSC) peripheral:
7 * + Initialization and De-initialization
8 * + Channel IOs, Shield IOs and Sampling IOs configuration
9 * + Start and Stop an acquisition
10 * + Read acquisition result
11 * + Interrupts and flags management
13 @verbatim
14 ================================================================================
15 ##### TSC specific features #####
16 ================================================================================
17 [..]
18 (#) Proven and robust surface charge transfer acquisition principle
20 (#) Supports up to 3 capacitive sensing channels per group
22 (#) Capacitive sensing channels can be acquired in parallel offering a very good
23 response time
25 (#) Spread spectrum feature to improve system robustness in noisy environments
27 (#) Full hardware management of the charge transfer acquisition sequence
29 (#) Programmable charge transfer frequency
31 (#) Programmable sampling capacitor I/O pin
33 (#) Programmable channel I/O pin
35 (#) Programmable max count value to avoid long acquisition when a channel is faulty
37 (#) Dedicated end of acquisition and max count error flags with interrupt capability
39 (#) One sampling capacitor for up to 3 capacitive sensing channels to reduce the system
40 components
42 (#) Compatible with proximity, touchkey, linear and rotary touch sensor implementation
45 ##### How to use this driver #####
46 ================================================================================
47 [..]
48 (#) Enable the TSC interface clock using __HAL_RCC_TSC_CLK_ENABLE() macro.
50 (#) GPIO pins configuration
51 (++) Enable the clock for the TSC GPIOs using __HAL_RCC_GPIOx_CLK_ENABLE() macro.
52 (++) Configure the TSC pins used as sampling IOs in alternate function output Open-Drain mode,
53 and TSC pins used as channel/shield IOs in alternate function output Push-Pull mode
54 using HAL_GPIO_Init() function.
56 (#) Interrupts configuration
57 (++) Configure the NVIC (if the interrupt model is used) using HAL_NVIC_SetPriority()
58 and HAL_NVIC_EnableIRQ() and function.
60 (#) TSC configuration
61 (++) Configure all TSC parameters and used TSC IOs using HAL_TSC_Init() function.
64 *** Acquisition sequence ***
65 ===================================
66 [..]
67 (+) Discharge all IOs using HAL_TSC_IODischarge() function.
68 (+) Wait a certain time allowing a good discharge of all capacitors. This delay depends
69 of the sampling capacitor and electrodes design.
70 (+) Select the channel IOs to be acquired using HAL_TSC_IOConfig() function.
71 (+) Launch the acquisition using either HAL_TSC_Start() or HAL_TSC_Start_IT() function.
72 If the synchronized mode is selected, the acquisition will start as soon as the signal
73 is received on the synchro pin.
74 (+) Wait the end of acquisition using either HAL_TSC_PollForAcquisition() or
75 HAL_TSC_GetState() function or using WFI instruction for example.
76 (+) Check the group acquisition status using HAL_TSC_GroupGetStatus() function.
77 (+) Read the acquisition value using HAL_TSC_GroupGetValue() function.
79 @endverbatim
80 ******************************************************************************
81 * @attention
83 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
85 * Redistribution and use in source and binary forms, with or without modification,
86 * are permitted provided that the following conditions are met:
87 * 1. Redistributions of source code must retain the above copyright notice,
88 * this list of conditions and the following disclaimer.
89 * 2. Redistributions in binary form must reproduce the above copyright notice,
90 * this list of conditions and the following disclaimer in the documentation
91 * and/or other materials provided with the distribution.
92 * 3. Neither the name of STMicroelectronics nor the names of its contributors
93 * may be used to endorse or promote products derived from this software
94 * without specific prior written permission.
96 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
97 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
98 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
99 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
100 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
101 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
102 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
103 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
104 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
105 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
107 ******************************************************************************
111 Addition Table:
112 Table 1. IOs for the STM32F3xx devices
113 +--------------------------------+
114 | IOs | TSC functions |
115 |--------------|-----------------|
116 | PA0 (AF) | TSC_G1_IO1 |
117 | PA1 (AF) | TSC_G1_IO2 |
118 | PA2 (AF) | TSC_G1_IO3 |
119 | PA3 (AF) | TSC_G1_IO4 |
120 |--------------|-----------------|
121 | PA4 (AF) | TSC_G2_IO1 |
122 | PA5 (AF) | TSC_G2_IO2 |
123 | PA6 (AF) | TSC_G2_IO3 |
124 | PA7 (AF) | TSC_G2_IO4 |
125 |--------------|-----------------|
126 | PC5 (AF) | TSC_G3_IO1 |
127 | PB0 (AF) | TSC_G3_IO2 |
128 | PB1 (AF) | TSC_G3_IO3 |
129 | PB2 (AF) | TSC_G3_IO4 |
130 |--------------|-----------------|
131 | PA9 (AF) | TSC_G4_IO1 |
132 | PA10 (AF) | TSC_G4_IO2 |
133 | PA13 (AF) | TSC_G4_IO3 |
134 | PA14 (AF) | TSC_G4_IO4 |
135 |--------------|-----------------|
136 | PB3 (AF) | TSC_G5_IO1 |
137 | PB4 (AF) | TSC_G5_IO2 |
138 | PB6 (AF) | TSC_G5_IO3 |
139 | PB7 (AF) | TSC_G5_IO4 |
140 |--------------|-----------------|
141 | PB11 (AF) | TSC_G6_IO1 |
142 | PB12 (AF) | TSC_G6_IO2 |
143 | PB13 (AF) | TSC_G6_IO3 |
144 | PB14 (AF) | TSC_G6_IO4 |
145 |--------------|-----------------|
146 | PE2 (AF) | TSC_G7_IO1 |
147 | PE3 (AF) | TSC_G7_IO2 |
148 | PE4 (AF) | TSC_G7_IO3 |
149 | PE5 (AF) | TSC_G7_IO4 |
150 |--------------|-----------------|
151 | PD12 (AF) | TSC_G8_IO1 |
152 | PD13 (AF) | TSC_G8_IO2 |
153 | PD14 (AF) | TSC_G8_IO3 |
154 | PD15 (AF) | TSC_G8_IO4 |
155 |--------------|-----------------|
156 | PB8 (AF) | TSC_SYNC |
157 | PB10 (AF) | |
158 +--------------------------------+
159 TSC peripheral alternate functions are mapped on AF3.
164 /* Includes ------------------------------------------------------------------*/
165 #include "stm32f3xx_hal.h"
167 /** @addtogroup STM32F3xx_HAL_Driver
168 * @{
171 /** @defgroup TSC TSC
172 * @brief HAL TSC module driver
173 * @{
176 #ifdef HAL_TSC_MODULE_ENABLED
178 /* Private typedef -----------------------------------------------------------*/
179 /* Private define ------------------------------------------------------------*/
180 /* Private macro -------------------------------------------------------------*/
181 /* Private variables ---------------------------------------------------------*/
182 /* Private function prototypes -----------------------------------------------*/
183 static uint32_t TSC_extract_groups(uint32_t iomask);
185 /* Exported functions --------------------------------------------------------*/
187 /** @defgroup TSC_Exported_Functions Exported Functions
188 * @{
191 /** @defgroup TSC_Exported_Functions_Group1 Initialization and de-initialization functions
192 * @brief Initialization and Configuration functions
194 @verbatim
195 ===============================================================================
196 ##### Initialization and de-initialization functions #####
197 ===============================================================================
198 [..] This section provides functions allowing to:
199 (+) Initialize and configure the TSC.
200 (+) De-initialize the TSC.
201 @endverbatim
202 * @{
206 * @brief Initialize the TSC peripheral according to the specified parameters
207 * in the TSC_InitTypeDef structure and initialize the associated handle.
208 * @param htsc TSC handle
209 * @retval HAL status
211 HAL_StatusTypeDef HAL_TSC_Init(TSC_HandleTypeDef* htsc)
213 /* Check TSC handle allocation */
214 if (htsc == NULL)
216 return HAL_ERROR;
219 /* Check the parameters */
220 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
221 assert_param(IS_TSC_CTPH(htsc->Init.CTPulseHighLength));
222 assert_param(IS_TSC_CTPL(htsc->Init.CTPulseLowLength));
223 assert_param(IS_TSC_SS(htsc->Init.SpreadSpectrum));
224 assert_param(IS_TSC_SSD(htsc->Init.SpreadSpectrumDeviation));
225 assert_param(IS_TSC_SS_PRESC(htsc->Init.SpreadSpectrumPrescaler));
226 assert_param(IS_TSC_PG_PRESC(htsc->Init.PulseGeneratorPrescaler));
227 assert_param(IS_TSC_MCV(htsc->Init.MaxCountValue));
228 assert_param(IS_TSC_IODEF(htsc->Init.IODefaultMode));
229 assert_param(IS_TSC_SYNC_POL(htsc->Init.SynchroPinPolarity));
230 assert_param(IS_TSC_ACQ_MODE(htsc->Init.AcquisitionMode));
231 assert_param(IS_TSC_MCE_IT(htsc->Init.MaxCountInterrupt));
233 if(htsc->State == HAL_TSC_STATE_RESET)
235 /* Allocate lock resource and initialize it */
236 htsc->Lock = HAL_UNLOCKED;
239 /* Initialize the TSC state */
240 htsc->State = HAL_TSC_STATE_BUSY;
242 /* Init the low level hardware : GPIO, CLOCK, CORTEX */
243 HAL_TSC_MspInit(htsc);
245 /*--------------------------------------------------------------------------*/
246 /* Set TSC parameters */
248 /* Enable TSC */
249 htsc->Instance->CR = TSC_CR_TSCE;
251 /* Set all functions */
252 htsc->Instance->CR |= (htsc->Init.CTPulseHighLength |
253 htsc->Init.CTPulseLowLength |
254 (uint32_t)(htsc->Init.SpreadSpectrumDeviation << 17U) |
255 htsc->Init.SpreadSpectrumPrescaler |
256 htsc->Init.PulseGeneratorPrescaler |
257 htsc->Init.MaxCountValue |
258 htsc->Init.SynchroPinPolarity |
259 htsc->Init.AcquisitionMode);
261 /* Spread spectrum */
262 if (htsc->Init.SpreadSpectrum == ENABLE)
264 htsc->Instance->CR |= TSC_CR_SSE;
267 /* Disable Schmitt trigger hysteresis on all used TSC IOs */
268 htsc->Instance->IOHCR = (uint32_t)(~(htsc->Init.ChannelIOs | htsc->Init.ShieldIOs | htsc->Init.SamplingIOs));
270 /* Set channel and shield IOs */
271 htsc->Instance->IOCCR = (htsc->Init.ChannelIOs | htsc->Init.ShieldIOs);
273 /* Set sampling IOs */
274 htsc->Instance->IOSCR = htsc->Init.SamplingIOs;
276 /* Set the groups to be acquired */
277 htsc->Instance->IOGCSR = TSC_extract_groups(htsc->Init.ChannelIOs);
279 /* Disable interrupts */
280 htsc->Instance->IER &= (uint32_t)(~(TSC_IT_EOA | TSC_IT_MCE));
282 /* Clear flags */
283 htsc->Instance->ICR = (TSC_FLAG_EOA | TSC_FLAG_MCE);
285 /*--------------------------------------------------------------------------*/
287 /* Initialize the TSC state */
288 htsc->State = HAL_TSC_STATE_READY;
290 /* Return function status */
291 return HAL_OK;
295 * @brief Deinitialize the TSC peripheral registers to their default reset values.
296 * @param htsc TSC handle
297 * @retval HAL status
299 HAL_StatusTypeDef HAL_TSC_DeInit(TSC_HandleTypeDef* htsc)
301 /* Check TSC handle allocation */
302 if (htsc == NULL)
304 return HAL_ERROR;
307 /* Check the parameters */
308 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
310 /* Change TSC state */
311 htsc->State = HAL_TSC_STATE_BUSY;
313 /* DeInit the low level hardware */
314 HAL_TSC_MspDeInit(htsc);
316 /* Change TSC state */
317 htsc->State = HAL_TSC_STATE_RESET;
319 /* Process unlocked */
320 __HAL_UNLOCK(htsc);
322 /* Return function status */
323 return HAL_OK;
327 * @brief Initialize the TSC MSP.
328 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
329 * the configuration information for the specified TSC.
330 * @retval None
332 __weak void HAL_TSC_MspInit(TSC_HandleTypeDef* htsc)
334 /* Prevent unused argument(s) compilation warning */
335 UNUSED(htsc);
337 /* NOTE : This function should not be modified, when the callback is needed,
338 the HAL_TSC_MspInit could be implemented in the user file.
343 * @brief DeInitialize the TSC MSP.
344 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
345 * the configuration information for the specified TSC.
346 * @retval None
348 __weak void HAL_TSC_MspDeInit(TSC_HandleTypeDef* htsc)
350 /* Prevent unused argument(s) compilation warning */
351 UNUSED(htsc);
353 /* NOTE : This function should not be modified, when the callback is needed,
354 the HAL_TSC_MspDeInit could be implemented in the user file.
359 * @}
362 /** @defgroup TSC_Exported_Functions_Group2 Input and Output operation functions
363 * @brief Input and Output operation functions
365 @verbatim
366 ===============================================================================
367 ##### IO Operation functions #####
368 ===============================================================================
369 [..] This section provides functions allowing to:
370 (+) Start acquisition in polling mode.
371 (+) Start acquisition in interrupt mode.
372 (+) Stop conversion in polling mode.
373 (+) Stop conversion in interrupt mode.
374 (+) Poll for acquisition completed.
375 (+) Get group acquisition status.
376 (+) Get group acquisition value.
377 @endverbatim
378 * @{
382 * @brief Start the acquisition.
383 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
384 * the configuration information for the specified TSC.
385 * @retval HAL status
387 HAL_StatusTypeDef HAL_TSC_Start(TSC_HandleTypeDef* htsc)
389 /* Check the parameters */
390 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
392 /* Process locked */
393 __HAL_LOCK(htsc);
395 /* Change TSC state */
396 htsc->State = HAL_TSC_STATE_BUSY;
398 /* Clear interrupts */
399 __HAL_TSC_DISABLE_IT(htsc, (TSC_IT_EOA | TSC_IT_MCE));
401 /* Clear flags */
402 __HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
404 /* Set touch sensing IOs not acquired to the specified IODefaultMode */
405 if (htsc->Init.IODefaultMode == TSC_IODEF_OUT_PP_LOW)
407 __HAL_TSC_SET_IODEF_OUTPPLOW(htsc);
409 else
411 __HAL_TSC_SET_IODEF_INFLOAT(htsc);
414 /* Launch the acquisition */
415 __HAL_TSC_START_ACQ(htsc);
417 /* Process unlocked */
418 __HAL_UNLOCK(htsc);
420 /* Return function status */
421 return HAL_OK;
425 * @brief Start the acquisition in interrupt mode.
426 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
427 * the configuration information for the specified TSC.
428 * @retval HAL status.
430 HAL_StatusTypeDef HAL_TSC_Start_IT(TSC_HandleTypeDef* htsc)
432 /* Check the parameters */
433 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
434 assert_param(IS_TSC_MCE_IT(htsc->Init.MaxCountInterrupt));
436 /* Process locked */
437 __HAL_LOCK(htsc);
439 /* Change TSC state */
440 htsc->State = HAL_TSC_STATE_BUSY;
442 /* Enable end of acquisition interrupt */
443 __HAL_TSC_ENABLE_IT(htsc, TSC_IT_EOA);
445 /* Enable max count error interrupt (optional) */
446 if (htsc->Init.MaxCountInterrupt == ENABLE)
448 __HAL_TSC_ENABLE_IT(htsc, TSC_IT_MCE);
450 else
452 __HAL_TSC_DISABLE_IT(htsc, TSC_IT_MCE);
455 /* Clear flags */
456 __HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
458 /* Set touch sensing IOs not acquired to the specified IODefaultMode */
459 if (htsc->Init.IODefaultMode == TSC_IODEF_OUT_PP_LOW)
461 __HAL_TSC_SET_IODEF_OUTPPLOW(htsc);
463 else
465 __HAL_TSC_SET_IODEF_INFLOAT(htsc);
468 /* Launch the acquisition */
469 __HAL_TSC_START_ACQ(htsc);
471 /* Process unlocked */
472 __HAL_UNLOCK(htsc);
474 /* Return function status */
475 return HAL_OK;
479 * @brief Stop the acquisition previously launched in polling mode.
480 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
481 * the configuration information for the specified TSC.
482 * @retval HAL status
484 HAL_StatusTypeDef HAL_TSC_Stop(TSC_HandleTypeDef* htsc)
486 /* Check the parameters */
487 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
489 /* Process locked */
490 __HAL_LOCK(htsc);
492 /* Stop the acquisition */
493 __HAL_TSC_STOP_ACQ(htsc);
495 /* Set touch sensing IOs in low power mode (output push-pull) */
496 __HAL_TSC_SET_IODEF_OUTPPLOW(htsc);
498 /* Clear flags */
499 __HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
501 /* Change TSC state */
502 htsc->State = HAL_TSC_STATE_READY;
504 /* Process unlocked */
505 __HAL_UNLOCK(htsc);
507 /* Return function status */
508 return HAL_OK;
512 * @brief Stop the acquisition previously launched in interrupt mode.
513 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
514 * the configuration information for the specified TSC.
515 * @retval HAL status
517 HAL_StatusTypeDef HAL_TSC_Stop_IT(TSC_HandleTypeDef* htsc)
519 /* Check the parameters */
520 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
522 /* Process locked */
523 __HAL_LOCK(htsc);
525 /* Stop the acquisition */
526 __HAL_TSC_STOP_ACQ(htsc);
528 /* Set touch sensing IOs in low power mode (output push-pull) */
529 __HAL_TSC_SET_IODEF_OUTPPLOW(htsc);
531 /* Disable interrupts */
532 __HAL_TSC_DISABLE_IT(htsc, (TSC_IT_EOA | TSC_IT_MCE));
534 /* Clear flags */
535 __HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
537 /* Change TSC state */
538 htsc->State = HAL_TSC_STATE_READY;
540 /* Process unlocked */
541 __HAL_UNLOCK(htsc);
543 /* Return function status */
544 return HAL_OK;
548 * @brief Start acquisition and wait until completion.
549 * @note There is no need of a timeout parameter as the max count error is already
550 * managed by the TSC peripheral.
551 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
552 * the configuration information for the specified TSC.
553 * @retval HAL state
555 HAL_StatusTypeDef HAL_TSC_PollForAcquisition(TSC_HandleTypeDef* htsc)
557 /* Check the parameters */
558 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
560 /* Process locked */
561 __HAL_LOCK(htsc);
563 /* Check end of acquisition */
564 while (HAL_TSC_GetState(htsc) == HAL_TSC_STATE_BUSY)
566 /* The timeout (max count error) is managed by the TSC peripheral itself. */
569 /* Process unlocked */
570 __HAL_UNLOCK(htsc);
572 return HAL_OK;
576 * @brief Get the acquisition status for a group.
577 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
578 * the configuration information for the specified TSC.
579 * @param gx_index Index of the group
580 * @retval Group status
582 TSC_GroupStatusTypeDef HAL_TSC_GroupGetStatus(TSC_HandleTypeDef* htsc, uint32_t gx_index)
584 /* Check the parameters */
585 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
586 assert_param(IS_TSC_GROUP_INDEX(gx_index));
588 /* Return the group status */
589 return(__HAL_TSC_GET_GROUP_STATUS(htsc, gx_index));
593 * @brief Get the acquisition measure for a group.
594 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
595 * the configuration information for the specified TSC.
596 * @param gx_index Index of the group
597 * @retval Acquisition measure
599 uint32_t HAL_TSC_GroupGetValue(TSC_HandleTypeDef* htsc, uint32_t gx_index)
601 /* Check the parameters */
602 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
603 assert_param(IS_TSC_GROUP_INDEX(gx_index));
605 /* Return the group acquisition counter */
606 return htsc->Instance->IOGXCR[gx_index];
610 * @}
613 /** @defgroup TSC_Exported_Functions_Group3 Peripheral Control functions
614 * @brief Peripheral Control functions
616 @verbatim
617 ===============================================================================
618 ##### Peripheral Control functions #####
619 ===============================================================================
620 [..] This section provides functions allowing to:
621 (+) Configure TSC IOs
622 (+) Discharge TSC IOs
623 @endverbatim
624 * @{
628 * @brief Configure TSC IOs.
629 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
630 * the configuration information for the specified TSC.
631 * @param config pointer to the configuration structure.
632 * @retval HAL status
634 HAL_StatusTypeDef HAL_TSC_IOConfig(TSC_HandleTypeDef* htsc, TSC_IOConfigTypeDef* config)
636 /* Check the parameters */
637 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
639 /* Process locked */
640 __HAL_LOCK(htsc);
642 /* Stop acquisition */
643 __HAL_TSC_STOP_ACQ(htsc);
645 /* Disable Schmitt trigger hysteresis on all used TSC IOs */
646 htsc->Instance->IOHCR = (uint32_t)(~(config->ChannelIOs | config->ShieldIOs | config->SamplingIOs));
648 /* Set channel and shield IOs */
649 htsc->Instance->IOCCR = (config->ChannelIOs | config->ShieldIOs);
651 /* Set sampling IOs */
652 htsc->Instance->IOSCR = config->SamplingIOs;
654 /* Set groups to be acquired */
655 htsc->Instance->IOGCSR = TSC_extract_groups(config->ChannelIOs);
657 /* Process unlocked */
658 __HAL_UNLOCK(htsc);
660 /* Return function status */
661 return HAL_OK;
665 * @brief Discharge TSC IOs.
666 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
667 * the configuration information for the specified TSC.
668 * @param choice enable or disable
669 * @retval HAL status
671 HAL_StatusTypeDef HAL_TSC_IODischarge(TSC_HandleTypeDef* htsc, uint32_t choice)
673 /* Check the parameters */
674 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
676 /* Process locked */
677 __HAL_LOCK(htsc);
679 if (choice == ENABLE)
681 __HAL_TSC_SET_IODEF_OUTPPLOW(htsc);
683 else
685 __HAL_TSC_SET_IODEF_INFLOAT(htsc);
688 /* Process unlocked */
689 __HAL_UNLOCK(htsc);
691 /* Return the group acquisition counter */
692 return HAL_OK;
696 * @}
699 /** @defgroup TSC_Exported_Functions_Group4 Peripheral State and Errors functions
700 * @brief Peripheral State and Errors functions
702 @verbatim
703 ===============================================================================
704 ##### State and Errors functions #####
705 ===============================================================================
706 [..]
707 This subsection provides functions allowing to
708 (+) Get TSC state.
710 @endverbatim
711 * @{
715 * @brief Return the TSC handle state.
716 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
717 * the configuration information for the specified TSC.
718 * @retval HAL state
720 HAL_TSC_StateTypeDef HAL_TSC_GetState(TSC_HandleTypeDef* htsc)
722 /* Check the parameters */
723 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
725 if (htsc->State == HAL_TSC_STATE_BUSY)
727 /* Check end of acquisition flag */
728 if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_EOA) != RESET)
730 /* Check max count error flag */
731 if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_MCE) != RESET)
733 /* Change TSC state */
734 htsc->State = HAL_TSC_STATE_ERROR;
736 else
738 /* Change TSC state */
739 htsc->State = HAL_TSC_STATE_READY;
744 /* Return TSC state */
745 return htsc->State;
749 * @}
752 /** @defgroup TSC_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
753 * @{
757 * @brief Handle TSC interrupt request.
758 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
759 * the configuration information for the specified TSC.
760 * @retval None
762 void HAL_TSC_IRQHandler(TSC_HandleTypeDef* htsc)
764 /* Check the parameters */
765 assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
767 /* Check if the end of acquisition occurred */
768 if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_EOA) != RESET)
770 /* Clear EOA flag */
771 __HAL_TSC_CLEAR_FLAG(htsc, TSC_FLAG_EOA);
774 /* Check if max count error occurred */
775 if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_MCE) != RESET)
777 /* Clear MCE flag */
778 __HAL_TSC_CLEAR_FLAG(htsc, TSC_FLAG_MCE);
779 /* Change TSC state */
780 htsc->State = HAL_TSC_STATE_ERROR;
781 /* Conversion completed callback */
782 HAL_TSC_ErrorCallback(htsc);
784 else
786 /* Change TSC state */
787 htsc->State = HAL_TSC_STATE_READY;
788 /* Conversion completed callback */
789 HAL_TSC_ConvCpltCallback(htsc);
794 * @brief Acquisition completed callback in non-blocking mode.
795 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
796 * the configuration information for the specified TSC.
797 * @retval None
799 __weak void HAL_TSC_ConvCpltCallback(TSC_HandleTypeDef* htsc)
801 /* Prevent unused argument(s) compilation warning */
802 UNUSED(htsc);
804 /* NOTE : This function should not be modified, when the callback is needed,
805 the HAL_TSC_ConvCpltCallback could be implemented in the user file.
810 * @brief Error callback in non-blocking mode.
811 * @param htsc pointer to a TSC_HandleTypeDef structure that contains
812 * the configuration information for the specified TSC.
813 * @retval None
815 __weak void HAL_TSC_ErrorCallback(TSC_HandleTypeDef* htsc)
817 /* Prevent unused argument(s) compilation warning */
818 UNUSED(htsc);
820 /* NOTE : This function should not be modified, when the callback is needed,
821 the HAL_TSC_ErrorCallback could be implemented in the user file.
826 * @}
830 * @}
833 /* Private functions ---------------------------------------------------------*/
834 /** @defgroup TSC_Private_Functions Private Functions
835 * @{
839 * @brief Utility function used to set the acquired groups mask.
840 * @param iomask Channels IOs mask
841 * @retval Acquired groups mask
843 static uint32_t TSC_extract_groups(uint32_t iomask)
845 uint32_t groups = 0U;
846 uint32_t idx;
848 for (idx = 0U; idx < TSC_NB_OF_GROUPS; idx++)
850 if ((iomask & (0x0FU << (idx * 4U))) != RESET)
852 groups |= (1U << idx);
856 return groups;
860 * @}
863 #endif /* HAL_TSC_MODULE_ENABLED */
866 * @}
870 * @}
873 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/