Merge pull request #10558 from iNavFlight/MrD_Correct-comments-on-OSD-symbols
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_dsi.c
blob9a68b75c3dab7f45afb90ecf0b23bd3da9ff0785
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_dsi.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief DSI HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the DSI peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State and Errors functions
14 ******************************************************************************
15 * @attention
17 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
19 * Redistribution and use in source and binary forms, with or without modification,
20 * are permitted provided that the following conditions are met:
21 * 1. Redistributions of source code must retain the above copyright notice,
22 * this list of conditions and the following disclaimer.
23 * 2. Redistributions in binary form must reproduce the above copyright notice,
24 * this list of conditions and the following disclaimer in the documentation
25 * and/or other materials provided with the distribution.
26 * 3. Neither the name of STMicroelectronics nor the names of its contributors
27 * may be used to endorse or promote products derived from this software
28 * without specific prior written permission.
30 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
31 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
32 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
33 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
34 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
35 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
36 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
37 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
38 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
39 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
41 ******************************************************************************
42 */
44 /* Includes ------------------------------------------------------------------*/
45 #include "stm32f7xx_hal.h"
47 /** @addtogroup STM32F7xx_HAL_Driver
48 * @{
50 /** @addtogroup DSI
51 * @{
54 #ifdef HAL_DSI_MODULE_ENABLED
56 #if defined (STM32F769xx) || defined (STM32F779xx)
58 /* Private types -------------------------------------------------------------*/
59 /* Private defines -----------------------------------------------------------*/
60 /** @addtogroup DSI_Private_Constants
61 * @{
63 #define DSI_TIMEOUT_VALUE ((uint32_t)1000) /* 1s */
65 #define DSI_ERROR_ACK_MASK (DSI_ISR0_AE0 | DSI_ISR0_AE1 | DSI_ISR0_AE2 | DSI_ISR0_AE3 | \
66 DSI_ISR0_AE4 | DSI_ISR0_AE5 | DSI_ISR0_AE6 | DSI_ISR0_AE7 | \
67 DSI_ISR0_AE8 | DSI_ISR0_AE9 | DSI_ISR0_AE10 | DSI_ISR0_AE11 | \
68 DSI_ISR0_AE12 | DSI_ISR0_AE13 | DSI_ISR0_AE14 | DSI_ISR0_AE15)
69 #define DSI_ERROR_PHY_MASK (DSI_ISR0_PE0 | DSI_ISR0_PE1 | DSI_ISR0_PE2 | DSI_ISR0_PE3 | DSI_ISR0_PE4)
70 #define DSI_ERROR_TX_MASK DSI_ISR1_TOHSTX
71 #define DSI_ERROR_RX_MASK DSI_ISR1_TOLPRX
72 #define DSI_ERROR_ECC_MASK (DSI_ISR1_ECCSE | DSI_ISR1_ECCME)
73 #define DSI_ERROR_CRC_MASK DSI_ISR1_CRCE
74 #define DSI_ERROR_PSE_MASK DSI_ISR1_PSE
75 #define DSI_ERROR_EOT_MASK DSI_ISR1_EOTPE
76 #define DSI_ERROR_OVF_MASK DSI_ISR1_LPWRE
77 #define DSI_ERROR_GEN_MASK (DSI_ISR1_GCWRE | DSI_ISR1_GPWRE | DSI_ISR1_GPTXE | DSI_ISR1_GPRDE | DSI_ISR1_GPRXE)
78 /**
79 * @}
82 /* Private variables ---------------------------------------------------------*/
83 /* Private constants ---------------------------------------------------------*/
84 /* Private macros ------------------------------------------------------------*/
85 /* Private function prototypes -----------------------------------------------*/
86 static void DSI_ConfigPacketHeader(DSI_TypeDef *DSIx, uint32_t ChannelID, uint32_t DataType, uint32_t Data0, uint32_t Data1);
88 /* Private functions ---------------------------------------------------------*/
89 /**
90 * @brief Generic DSI packet header configuration
91 * @param DSIx: Pointer to DSI register base
92 * @param ChannelID: Virtual channel ID of the header packet
93 * @param DataType: Packet data type of the header packet
94 * This parameter can be any value of :
95 * @ref DSI_SHORT_WRITE_PKT_Data_Type
96 * or @ref DSI_LONG_WRITE_PKT_Data_Type
97 * or @ref DSI_SHORT_READ_PKT_Data_Type
98 * or DSI_MAX_RETURN_PKT_SIZE
99 * @param Data0: Word count LSB
100 * @param Data1: Word count MSB
101 * @retval None
103 static void DSI_ConfigPacketHeader(DSI_TypeDef *DSIx,
104 uint32_t ChannelID,
105 uint32_t DataType,
106 uint32_t Data0,
107 uint32_t Data1)
109 /* Update the DSI packet header with new information */
110 DSIx->GHCR = (DataType | (ChannelID<<6) | (Data0<<8) | (Data1<<16));
113 /* Exported functions --------------------------------------------------------*/
114 /** @addtogroup DSI_Exported_Functions
115 * @{
118 /** @defgroup DSI_Group1 Initialization and Configuration functions
119 * @brief Initialization and Configuration functions
121 @verbatim
122 ===============================================================================
123 ##### Initialization and Configuration functions #####
124 ===============================================================================
125 [..] This section provides functions allowing to:
126 (+) Initialize and configure the DSI
127 (+) De-initialize the DSI
129 @endverbatim
130 * @{
134 * @brief Initializes the DSI according to the specified
135 * parameters in the DSI_InitTypeDef and create the associated handle.
136 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
137 * the configuration information for the DSI.
138 * @param PLLInit: pointer to a DSI_PLLInitTypeDef structure that contains
139 * the PLL Clock structure definition for the DSI.
140 * @retval HAL status
142 HAL_StatusTypeDef HAL_DSI_Init(DSI_HandleTypeDef *hdsi, DSI_PLLInitTypeDef *PLLInit)
144 uint32_t tickstart = 0;
145 uint32_t unitIntervalx4 = 0;
146 uint32_t tempIDF = 0;
148 /* Check the DSI handle allocation */
149 if(hdsi == NULL)
151 return HAL_ERROR;
154 /* Check function parameters */
155 assert_param(IS_DSI_PLL_NDIV(PLLInit->PLLNDIV));
156 assert_param(IS_DSI_PLL_IDF(PLLInit->PLLIDF));
157 assert_param(IS_DSI_PLL_ODF(PLLInit->PLLODF));
158 assert_param(IS_DSI_AUTO_CLKLANE_CONTROL(hdsi->Init.AutomaticClockLaneControl));
159 assert_param(IS_DSI_NUMBER_OF_LANES(hdsi->Init.NumberOfLanes));
161 if(hdsi->State == HAL_DSI_STATE_RESET)
163 /* Initialize the low level hardware */
164 HAL_DSI_MspInit(hdsi);
167 /* Change DSI peripheral state */
168 hdsi->State = HAL_DSI_STATE_BUSY;
170 /**************** Turn on the regulator and enable the DSI PLL ****************/
172 /* Enable the regulator */
173 __HAL_DSI_REG_ENABLE(hdsi);
175 /* Get tick */
176 tickstart = HAL_GetTick();
178 /* Wait until the regulator is ready */
179 while(__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_RRS) == RESET)
181 /* Check for the Timeout */
182 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
184 return HAL_TIMEOUT;
188 /* Set the PLL division factors */
189 hdsi->Instance->WRPCR &= ~(DSI_WRPCR_PLL_NDIV | DSI_WRPCR_PLL_IDF | DSI_WRPCR_PLL_ODF);
190 hdsi->Instance->WRPCR |= (((PLLInit->PLLNDIV)<<2) | ((PLLInit->PLLIDF)<<11) | ((PLLInit->PLLODF)<<16));
192 /* Enable the DSI PLL */
193 __HAL_DSI_PLL_ENABLE(hdsi);
195 /* Get tick */
196 tickstart = HAL_GetTick();
198 /* Wait for the lock of the PLL */
199 while(__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_PLLLS) == RESET)
201 /* Check for the Timeout */
202 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
204 return HAL_TIMEOUT;
208 /*************************** Set the PHY parameters ***************************/
210 /* D-PHY clock and digital enable*/
211 hdsi->Instance->PCTLR |= (DSI_PCTLR_CKE | DSI_PCTLR_DEN);
213 /* Clock lane configuration */
214 hdsi->Instance->CLCR &= ~(DSI_CLCR_DPCC | DSI_CLCR_ACR);
215 hdsi->Instance->CLCR |= (DSI_CLCR_DPCC | hdsi->Init.AutomaticClockLaneControl);
217 /* Configure the number of active data lanes */
218 hdsi->Instance->PCONFR &= ~DSI_PCONFR_NL;
219 hdsi->Instance->PCONFR |= hdsi->Init.NumberOfLanes;
221 /************************ Set the DSI clock parameters ************************/
223 /* Set the TX escape clock division factor */
224 hdsi->Instance->CCR &= ~DSI_CCR_TXECKDIV;
225 hdsi->Instance->CCR |= hdsi->Init.TXEscapeCkdiv;
227 /* Calculate the bit period in high-speed mode in unit of 0.25 ns (UIX4) */
228 /* The equation is : UIX4 = IntegerPart( (1000/F_PHY_Mhz) * 4 ) */
229 /* Where : F_PHY_Mhz = (NDIV * HSE_Mhz) / (IDF * ODF) */
230 tempIDF = (PLLInit->PLLIDF > 0) ? PLLInit->PLLIDF : 1;
231 unitIntervalx4 = (4000000 * tempIDF * (1 << PLLInit->PLLODF)) / ((HSE_VALUE/1000) * PLLInit->PLLNDIV);
233 /* Set the bit period in high-speed mode */
234 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_UIX4;
235 hdsi->Instance->WPCR[0] |= unitIntervalx4;
237 /****************************** Error management *****************************/
239 /* Disable all error interrupts and reset the Error Mask */
240 hdsi->Instance->IER[0] = 0;
241 hdsi->Instance->IER[1] = 0;
242 hdsi->ErrorMsk = 0;
244 /* Initialise the error code */
245 hdsi->ErrorCode = HAL_DSI_ERROR_NONE;
247 /* Initialize the DSI state*/
248 hdsi->State = HAL_DSI_STATE_READY;
250 return HAL_OK;
254 * @brief De-initializes the DSI peripheral registers to their default reset
255 * values.
256 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
257 * the configuration information for the DSI.
258 * @retval HAL status
260 HAL_StatusTypeDef HAL_DSI_DeInit(DSI_HandleTypeDef *hdsi)
262 /* Check the DSI handle allocation */
263 if(hdsi == NULL)
265 return HAL_ERROR;
268 /* Change DSI peripheral state */
269 hdsi->State = HAL_DSI_STATE_BUSY;
271 /* Disable the DSI wrapper */
272 __HAL_DSI_WRAPPER_DISABLE(hdsi);
274 /* Disable the DSI host */
275 __HAL_DSI_DISABLE(hdsi);
277 /* D-PHY clock and digital disable */
278 hdsi->Instance->PCTLR &= ~(DSI_PCTLR_CKE | DSI_PCTLR_DEN);
280 /* Turn off the DSI PLL */
281 __HAL_DSI_PLL_DISABLE(hdsi);
283 /* Disable the regulator */
284 __HAL_DSI_REG_DISABLE(hdsi);
286 /* DeInit the low level hardware */
287 HAL_DSI_MspDeInit(hdsi);
289 /* Initialise the error code */
290 hdsi->ErrorCode = HAL_DSI_ERROR_NONE;
292 /* Initialize the DSI state*/
293 hdsi->State = HAL_DSI_STATE_RESET;
295 /* Release Lock */
296 __HAL_UNLOCK(hdsi);
298 return HAL_OK;
302 * @brief Return the DSI error code
303 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
304 * the configuration information for the DSI.
305 * @retval DSI Error Code
307 uint32_t HAL_DSI_GetError(DSI_HandleTypeDef *hdsi)
309 /* Get the error code */
310 return hdsi->ErrorCode;
314 * @brief Enable the error monitor flags
315 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
316 * the configuration information for the DSI.
317 * @param ActiveErrors: indicates which error interrupts will be enabled.
318 * This parameter can be any combination of @ref DSI_Error_Data_Type.
319 * @retval HAL status
321 HAL_StatusTypeDef HAL_DSI_ConfigErrorMonitor(DSI_HandleTypeDef *hdsi, uint32_t ActiveErrors)
323 /* Process locked */
324 __HAL_LOCK(hdsi);
326 hdsi->Instance->IER[0] = 0;
327 hdsi->Instance->IER[1] = 0;
329 /* Store active errors to the handle */
330 hdsi->ErrorMsk = ActiveErrors;
332 if((ActiveErrors & HAL_DSI_ERROR_ACK) != RESET)
334 /* Enable the interrupt generation on selected errors */
335 hdsi->Instance->IER[0] |= DSI_ERROR_ACK_MASK;
338 if((ActiveErrors & HAL_DSI_ERROR_PHY ) != RESET)
340 /* Enable the interrupt generation on selected errors */
341 hdsi->Instance->IER[0] |= DSI_ERROR_PHY_MASK;
344 if((ActiveErrors & HAL_DSI_ERROR_TX) != RESET)
346 /* Enable the interrupt generation on selected errors */
347 hdsi->Instance->IER[1] |= DSI_ERROR_TX_MASK;
350 if((ActiveErrors & HAL_DSI_ERROR_RX) != RESET)
352 /* Enable the interrupt generation on selected errors */
353 hdsi->Instance->IER[1] |= DSI_ERROR_RX_MASK;
356 if((ActiveErrors & HAL_DSI_ERROR_ECC) != RESET)
358 /* Enable the interrupt generation on selected errors */
359 hdsi->Instance->IER[1] |= DSI_ERROR_ECC_MASK;
362 if((ActiveErrors & HAL_DSI_ERROR_CRC) != RESET)
364 /* Enable the interrupt generation on selected errors */
365 hdsi->Instance->IER[1] |= DSI_ERROR_CRC_MASK;
368 if((ActiveErrors & HAL_DSI_ERROR_PSE) != RESET)
370 /* Enable the interrupt generation on selected errors */
371 hdsi->Instance->IER[1] |= DSI_ERROR_PSE_MASK;
374 if((ActiveErrors & HAL_DSI_ERROR_EOT) != RESET)
376 /* Enable the interrupt generation on selected errors */
377 hdsi->Instance->IER[1] |= DSI_ERROR_EOT_MASK;
380 if((ActiveErrors & HAL_DSI_ERROR_OVF) != RESET)
382 /* Enable the interrupt generation on selected errors */
383 hdsi->Instance->IER[1] |= DSI_ERROR_OVF_MASK;
386 if((ActiveErrors & HAL_DSI_ERROR_GEN) != RESET)
388 /* Enable the interrupt generation on selected errors */
389 hdsi->Instance->IER[1] |= DSI_ERROR_GEN_MASK;
392 /* Process Unlocked */
393 __HAL_UNLOCK(hdsi);
395 return HAL_OK;
399 * @brief Initializes the DSI MSP.
400 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
401 * the configuration information for the DSI.
402 * @retval None
404 __weak void HAL_DSI_MspInit(DSI_HandleTypeDef* hdsi)
406 /* Prevent unused argument(s) compilation warning */
407 UNUSED(hdsi);
409 /* NOTE : This function Should not be modified, when the callback is needed,
410 the HAL_DSI_MspInit could be implemented in the user file
415 * @brief De-initializes the DSI MSP.
416 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
417 * the configuration information for the DSI.
418 * @retval None
420 __weak void HAL_DSI_MspDeInit(DSI_HandleTypeDef* hdsi)
422 /* Prevent unused argument(s) compilation warning */
423 UNUSED(hdsi);
425 /* NOTE : This function Should not be modified, when the callback is needed,
426 the HAL_DSI_MspDeInit could be implemented in the user file
431 * @}
434 /** @defgroup DSI_Group2 IO operation functions
435 * @brief IO operation functions
437 @verbatim
438 ===============================================================================
439 ##### IO operation functions #####
440 ===============================================================================
441 [..] This section provides function allowing to:
442 (+) Handle DSI interrupt request
444 @endverbatim
445 * @{
448 * @brief Handles DSI interrupt request.
449 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
450 * the configuration information for the DSI.
451 * @retval HAL status
453 void HAL_DSI_IRQHandler(DSI_HandleTypeDef *hdsi)
455 uint32_t ErrorStatus0, ErrorStatus1;
457 /* Tearing Effect Interrupt management ***************************************/
458 if(__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_TE) != RESET)
460 if(__HAL_DSI_GET_IT_SOURCE(hdsi, DSI_IT_TE) != RESET)
462 /* Clear the Tearing Effect Interrupt Flag */
463 __HAL_DSI_CLEAR_FLAG(hdsi, DSI_FLAG_TE);
465 /* Tearing Effect Callback */
466 HAL_DSI_TearingEffectCallback(hdsi);
470 /* End of Refresh Interrupt management ***************************************/
471 if(__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_ER) != RESET)
473 if(__HAL_DSI_GET_IT_SOURCE(hdsi, DSI_IT_ER) != RESET)
475 /* Clear the End of Refresh Interrupt Flag */
476 __HAL_DSI_CLEAR_FLAG(hdsi, DSI_FLAG_ER);
478 /* End of Refresh Callback */
479 HAL_DSI_EndOfRefreshCallback(hdsi);
483 /* Error Interrupts management ***********************************************/
484 if(hdsi->ErrorMsk != 0)
486 ErrorStatus0 = hdsi->Instance->ISR[0];
487 ErrorStatus0 &= hdsi->Instance->IER[0];
488 ErrorStatus1 = hdsi->Instance->ISR[1];
489 ErrorStatus1 &= hdsi->Instance->IER[1];
491 if((ErrorStatus0 & DSI_ERROR_ACK_MASK) != RESET)
493 hdsi->ErrorCode |= HAL_DSI_ERROR_ACK;
496 if((ErrorStatus0 & DSI_ERROR_PHY_MASK) != RESET)
498 hdsi->ErrorCode |= HAL_DSI_ERROR_PHY;
501 if((ErrorStatus1 & DSI_ERROR_TX_MASK) != RESET)
503 hdsi->ErrorCode |= HAL_DSI_ERROR_TX;
506 if((ErrorStatus1 & DSI_ERROR_RX_MASK) != RESET)
508 hdsi->ErrorCode |= HAL_DSI_ERROR_RX;
511 if((ErrorStatus1 & DSI_ERROR_ECC_MASK) != RESET)
513 hdsi->ErrorCode |= HAL_DSI_ERROR_ECC;
516 if((ErrorStatus1 & DSI_ERROR_CRC_MASK) != RESET)
518 hdsi->ErrorCode |= HAL_DSI_ERROR_CRC;
521 if((ErrorStatus1 & DSI_ERROR_PSE_MASK) != RESET)
523 hdsi->ErrorCode |= HAL_DSI_ERROR_PSE;
526 if((ErrorStatus1 & DSI_ERROR_EOT_MASK) != RESET)
528 hdsi->ErrorCode |= HAL_DSI_ERROR_EOT;
531 if((ErrorStatus1 & DSI_ERROR_OVF_MASK) != RESET)
533 hdsi->ErrorCode |= HAL_DSI_ERROR_OVF;
536 if((ErrorStatus1 & DSI_ERROR_GEN_MASK) != RESET)
538 hdsi->ErrorCode |= HAL_DSI_ERROR_GEN;
541 /* Check only selected errors */
542 if(hdsi->ErrorCode != HAL_DSI_ERROR_NONE)
544 /* DSI error interrupt user callback */
545 HAL_DSI_ErrorCallback(hdsi);
551 * @brief Tearing Effect DSI callback.
552 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
553 * the configuration information for the DSI.
554 * @retval None
556 __weak void HAL_DSI_TearingEffectCallback(DSI_HandleTypeDef *hdsi)
558 /* Prevent unused argument(s) compilation warning */
559 UNUSED(hdsi);
561 /* NOTE : This function Should not be modified, when the callback is needed,
562 the HAL_DSI_TearingEffectCallback could be implemented in the user file
567 * @brief End of Refresh DSI callback.
568 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
569 * the configuration information for the DSI.
570 * @retval None
572 __weak void HAL_DSI_EndOfRefreshCallback(DSI_HandleTypeDef *hdsi)
574 /* Prevent unused argument(s) compilation warning */
575 UNUSED(hdsi);
577 /* NOTE : This function Should not be modified, when the callback is needed,
578 the HAL_DSI_EndOfRefreshCallback could be implemented in the user file
583 * @brief Operation Error DSI callback.
584 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
585 * the configuration information for the DSI.
586 * @retval None
588 __weak void HAL_DSI_ErrorCallback(DSI_HandleTypeDef *hdsi)
590 /* Prevent unused argument(s) compilation warning */
591 UNUSED(hdsi);
593 /* NOTE : This function Should not be modified, when the callback is needed,
594 the HAL_DSI_ErrorCallback could be implemented in the user file
599 * @}
602 /** @defgroup DSI_Group3 Peripheral Control functions
603 * @brief Peripheral Control functions
605 @verbatim
606 ===============================================================================
607 ##### Peripheral Control functions #####
608 ===============================================================================
610 @endverbatim
611 * @{
615 * @brief Configure the Generic interface read-back Virtual Channel ID.
616 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
617 * the configuration information for the DSI.
618 * @param VirtualChannelID: Virtual channel ID
619 * @retval HAL status
621 HAL_StatusTypeDef HAL_DSI_SetGenericVCID(DSI_HandleTypeDef *hdsi, uint32_t VirtualChannelID)
623 /* Process locked */
624 __HAL_LOCK(hdsi);
626 /* Update the GVCID register */
627 hdsi->Instance->GVCIDR &= ~DSI_GVCIDR_VCID;
628 hdsi->Instance->GVCIDR |= VirtualChannelID;
630 /* Process unlocked */
631 __HAL_UNLOCK(hdsi);
633 return HAL_OK;
637 * @brief Select video mode and configure the corresponding parameters
638 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
639 * the configuration information for the DSI.
640 * @param VidCfg: pointer to a DSI_VidCfgTypeDef structure that contains
641 * the DSI video mode configuration parameters
642 * @retval HAL status
644 HAL_StatusTypeDef HAL_DSI_ConfigVideoMode(DSI_HandleTypeDef *hdsi, DSI_VidCfgTypeDef *VidCfg)
646 /* Process locked */
647 __HAL_LOCK(hdsi);
649 /* Check the parameters */
650 assert_param(IS_DSI_COLOR_CODING(VidCfg->ColorCoding));
651 assert_param(IS_DSI_VIDEO_MODE_TYPE(VidCfg->Mode));
652 assert_param(IS_DSI_LP_COMMAND(VidCfg->LPCommandEnable));
653 assert_param(IS_DSI_LP_HFP(VidCfg->LPHorizontalFrontPorchEnable));
654 assert_param(IS_DSI_LP_HBP(VidCfg->LPHorizontalBackPorchEnable));
655 assert_param(IS_DSI_LP_VACTIVE(VidCfg->LPVerticalActiveEnable));
656 assert_param(IS_DSI_LP_VFP(VidCfg->LPVerticalFrontPorchEnable));
657 assert_param(IS_DSI_LP_VBP(VidCfg->LPVerticalBackPorchEnable));
658 assert_param(IS_DSI_LP_VSYNC(VidCfg->LPVerticalSyncActiveEnable));
659 assert_param(IS_DSI_FBTAA(VidCfg->FrameBTAAcknowledgeEnable));
660 assert_param(IS_DSI_DE_POLARITY(VidCfg->DEPolarity));
661 assert_param(IS_DSI_VSYNC_POLARITY(VidCfg->VSPolarity));
662 assert_param(IS_DSI_HSYNC_POLARITY(VidCfg->HSPolarity));
663 /* Check the LooselyPacked variant only in 18-bit mode */
664 if(VidCfg->ColorCoding == DSI_RGB666)
666 assert_param(IS_DSI_LOOSELY_PACKED(VidCfg->LooselyPacked));
669 /* Select video mode by resetting CMDM and DSIM bits */
670 hdsi->Instance->MCR &= ~DSI_MCR_CMDM;
671 hdsi->Instance->WCFGR &= ~DSI_WCFGR_DSIM;
673 /* Configure the video mode transmission type */
674 hdsi->Instance->VMCR &= ~DSI_VMCR_VMT;
675 hdsi->Instance->VMCR |= VidCfg->Mode;
677 /* Configure the video packet size */
678 hdsi->Instance->VPCR &= ~DSI_VPCR_VPSIZE;
679 hdsi->Instance->VPCR |= VidCfg->PacketSize;
681 /* Set the chunks number to be transmitted through the DSI link */
682 hdsi->Instance->VCCR &= ~DSI_VCCR_NUMC;
683 hdsi->Instance->VCCR |= VidCfg->NumberOfChunks;
685 /* Set the size of the null packet */
686 hdsi->Instance->VNPCR &= ~DSI_VNPCR_NPSIZE;
687 hdsi->Instance->VNPCR |= VidCfg->NullPacketSize;
689 /* Select the virtual channel for the LTDC interface traffic */
690 hdsi->Instance->LVCIDR &= ~DSI_LVCIDR_VCID;
691 hdsi->Instance->LVCIDR |= VidCfg->VirtualChannelID;
693 /* Configure the polarity of control signals */
694 hdsi->Instance->LPCR &= ~(DSI_LPCR_DEP | DSI_LPCR_VSP | DSI_LPCR_HSP);
695 hdsi->Instance->LPCR |= (VidCfg->DEPolarity | VidCfg->VSPolarity | VidCfg->HSPolarity);
697 /* Select the color coding for the host */
698 hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_COLC;
699 hdsi->Instance->LCOLCR |= VidCfg->ColorCoding;
701 /* Select the color coding for the wrapper */
702 hdsi->Instance->WCFGR &= ~DSI_WCFGR_COLMUX;
703 hdsi->Instance->WCFGR |= ((VidCfg->ColorCoding)<<1);
705 /* Enable/disable the loosely packed variant to 18-bit configuration */
706 if(VidCfg->ColorCoding == DSI_RGB666)
708 hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_LPE;
709 hdsi->Instance->LCOLCR |= VidCfg->LooselyPacked;
712 /* Set the Horizontal Synchronization Active (HSA) in lane byte clock cycles */
713 hdsi->Instance->VHSACR &= ~DSI_VHSACR_HSA;
714 hdsi->Instance->VHSACR |= VidCfg->HorizontalSyncActive;
716 /* Set the Horizontal Back Porch (HBP) in lane byte clock cycles */
717 hdsi->Instance->VHBPCR &= ~DSI_VHBPCR_HBP;
718 hdsi->Instance->VHBPCR |= VidCfg->HorizontalBackPorch;
720 /* Set the total line time (HLINE=HSA+HBP+HACT+HFP) in lane byte clock cycles */
721 hdsi->Instance->VLCR &= ~DSI_VLCR_HLINE;
722 hdsi->Instance->VLCR |= VidCfg->HorizontalLine;
724 /* Set the Vertical Synchronization Active (VSA) */
725 hdsi->Instance->VVSACR &= ~DSI_VVSACR_VSA;
726 hdsi->Instance->VVSACR |= VidCfg->VerticalSyncActive;
728 /* Set the Vertical Back Porch (VBP)*/
729 hdsi->Instance->VVBPCR &= ~DSI_VVBPCR_VBP;
730 hdsi->Instance->VVBPCR |= VidCfg->VerticalBackPorch;
732 /* Set the Vertical Front Porch (VFP)*/
733 hdsi->Instance->VVFPCR &= ~DSI_VVFPCR_VFP;
734 hdsi->Instance->VVFPCR |= VidCfg->VerticalFrontPorch;
736 /* Set the Vertical Active period*/
737 hdsi->Instance->VVACR &= ~DSI_VVACR_VA;
738 hdsi->Instance->VVACR |= VidCfg->VerticalActive;
740 /* Configure the command transmission mode */
741 hdsi->Instance->VMCR &= ~DSI_VMCR_LPCE;
742 hdsi->Instance->VMCR |= VidCfg->LPCommandEnable;
744 /* Low power largest packet size */
745 hdsi->Instance->LPMCR &= ~DSI_LPMCR_LPSIZE;
746 hdsi->Instance->LPMCR |= ((VidCfg->LPLargestPacketSize)<<16);
748 /* Low power VACT largest packet size */
749 hdsi->Instance->LPMCR &= ~DSI_LPMCR_VLPSIZE;
750 hdsi->Instance->LPMCR |= VidCfg->LPVACTLargestPacketSize;
752 /* Enable LP transition in HFP period */
753 hdsi->Instance->VMCR &= ~DSI_VMCR_LPHFPE;
754 hdsi->Instance->VMCR |= VidCfg->LPHorizontalFrontPorchEnable;
756 /* Enable LP transition in HBP period */
757 hdsi->Instance->VMCR &= ~DSI_VMCR_LPHBPE;
758 hdsi->Instance->VMCR |= VidCfg->LPHorizontalBackPorchEnable;
760 /* Enable LP transition in VACT period */
761 hdsi->Instance->VMCR &= ~DSI_VMCR_LPVAE;
762 hdsi->Instance->VMCR |= VidCfg->LPVerticalActiveEnable;
764 /* Enable LP transition in VFP period */
765 hdsi->Instance->VMCR &= ~DSI_VMCR_LPVFPE;
766 hdsi->Instance->VMCR |= VidCfg->LPVerticalFrontPorchEnable;
768 /* Enable LP transition in VBP period */
769 hdsi->Instance->VMCR &= ~DSI_VMCR_LPVBPE;
770 hdsi->Instance->VMCR |= VidCfg->LPVerticalBackPorchEnable;
772 /* Enable LP transition in vertical sync period */
773 hdsi->Instance->VMCR &= ~DSI_VMCR_LPVSAE;
774 hdsi->Instance->VMCR |= VidCfg->LPVerticalSyncActiveEnable;
776 /* Enable the request for an acknowledge response at the end of a frame */
777 hdsi->Instance->VMCR &= ~DSI_VMCR_FBTAAE;
778 hdsi->Instance->VMCR |= VidCfg->FrameBTAAcknowledgeEnable;
780 /* Process unlocked */
781 __HAL_UNLOCK(hdsi);
783 return HAL_OK;
787 * @brief Select adapted command mode and configure the corresponding parameters
788 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
789 * the configuration information for the DSI.
790 * @param CmdCfg: pointer to a DSI_CmdCfgTypeDef structure that contains
791 * the DSI command mode configuration parameters
792 * @retval HAL status
794 HAL_StatusTypeDef HAL_DSI_ConfigAdaptedCommandMode(DSI_HandleTypeDef *hdsi, DSI_CmdCfgTypeDef *CmdCfg)
796 /* Process locked */
797 __HAL_LOCK(hdsi);
799 /* Check the parameters */
800 assert_param(IS_DSI_COLOR_CODING(CmdCfg->ColorCoding));
801 assert_param(IS_DSI_TE_SOURCE(CmdCfg->TearingEffectSource));
802 assert_param(IS_DSI_TE_POLARITY(CmdCfg->TearingEffectPolarity));
803 assert_param(IS_DSI_AUTOMATIC_REFRESH(CmdCfg->AutomaticRefresh));
804 assert_param(IS_DSI_VS_POLARITY(CmdCfg->VSyncPol));
805 assert_param(IS_DSI_TE_ACK_REQUEST(CmdCfg->TEAcknowledgeRequest));
806 assert_param(IS_DSI_DE_POLARITY(CmdCfg->DEPolarity));
807 assert_param(IS_DSI_VSYNC_POLARITY(CmdCfg->VSPolarity));
808 assert_param(IS_DSI_HSYNC_POLARITY(CmdCfg->HSPolarity));
810 /* Select command mode by setting CMDM and DSIM bits */
811 hdsi->Instance->MCR |= DSI_MCR_CMDM;
812 hdsi->Instance->WCFGR &= ~DSI_WCFGR_DSIM;
813 hdsi->Instance->WCFGR |= DSI_WCFGR_DSIM;
815 /* Select the virtual channel for the LTDC interface traffic */
816 hdsi->Instance->LVCIDR &= ~DSI_LVCIDR_VCID;
817 hdsi->Instance->LVCIDR |= CmdCfg->VirtualChannelID;
819 /* Configure the polarity of control signals */
820 hdsi->Instance->LPCR &= ~(DSI_LPCR_DEP | DSI_LPCR_VSP | DSI_LPCR_HSP);
821 hdsi->Instance->LPCR |= (CmdCfg->DEPolarity | CmdCfg->VSPolarity | CmdCfg->HSPolarity);
823 /* Select the color coding for the host */
824 hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_COLC;
825 hdsi->Instance->LCOLCR |= CmdCfg->ColorCoding;
827 /* Select the color coding for the wrapper */
828 hdsi->Instance->WCFGR &= ~DSI_WCFGR_COLMUX;
829 hdsi->Instance->WCFGR |= ((CmdCfg->ColorCoding)<<1);
831 /* Configure the maximum allowed size for write memory command */
832 hdsi->Instance->LCCR &= ~DSI_LCCR_CMDSIZE;
833 hdsi->Instance->LCCR |= CmdCfg->CommandSize;
835 /* Configure the tearing effect source and polarity and select the refresh mode */
836 hdsi->Instance->WCFGR &= ~(DSI_WCFGR_TESRC | DSI_WCFGR_TEPOL | DSI_WCFGR_AR | DSI_WCFGR_VSPOL);
837 hdsi->Instance->WCFGR |= (CmdCfg->TearingEffectSource | CmdCfg->TearingEffectPolarity | CmdCfg->AutomaticRefresh | CmdCfg->VSyncPol);
839 /* Configure the tearing effect acknowledge request */
840 hdsi->Instance->CMCR &= ~DSI_CMCR_TEARE;
841 hdsi->Instance->CMCR |= CmdCfg->TEAcknowledgeRequest;
843 /* Enable the Tearing Effect interrupt */
844 __HAL_DSI_ENABLE_IT(hdsi, DSI_IT_TE);
846 /* Enable the End of Refresh interrupt */
847 __HAL_DSI_ENABLE_IT(hdsi, DSI_IT_ER);
849 /* Process unlocked */
850 __HAL_UNLOCK(hdsi);
852 return HAL_OK;
856 * @brief Configure command transmission mode: High-speed or Low-power
857 * and enable/disable acknowledge request after packet transmission
858 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
859 * the configuration information for the DSI.
860 * @param LPCmd: pointer to a DSI_LPCmdTypeDef structure that contains
861 * the DSI command transmission mode configuration parameters
862 * @retval HAL status
864 HAL_StatusTypeDef HAL_DSI_ConfigCommand(DSI_HandleTypeDef *hdsi, DSI_LPCmdTypeDef *LPCmd)
866 /* Process locked */
867 __HAL_LOCK(hdsi);
869 assert_param(IS_DSI_LP_GSW0P(LPCmd->LPGenShortWriteNoP));
870 assert_param(IS_DSI_LP_GSW1P(LPCmd->LPGenShortWriteOneP));
871 assert_param(IS_DSI_LP_GSW2P(LPCmd->LPGenShortWriteTwoP));
872 assert_param(IS_DSI_LP_GSR0P(LPCmd->LPGenShortReadNoP));
873 assert_param(IS_DSI_LP_GSR1P(LPCmd->LPGenShortReadOneP));
874 assert_param(IS_DSI_LP_GSR2P(LPCmd->LPGenShortReadTwoP));
875 assert_param(IS_DSI_LP_GLW(LPCmd->LPGenLongWrite));
876 assert_param(IS_DSI_LP_DSW0P(LPCmd->LPDcsShortWriteNoP));
877 assert_param(IS_DSI_LP_DSW1P(LPCmd->LPDcsShortWriteOneP));
878 assert_param(IS_DSI_LP_DSR0P(LPCmd->LPDcsShortReadNoP));
879 assert_param(IS_DSI_LP_DLW(LPCmd->LPDcsLongWrite));
880 assert_param(IS_DSI_LP_MRDP(LPCmd->LPMaxReadPacket));
881 assert_param(IS_DSI_ACK_REQUEST(LPCmd->AcknowledgeRequest));
883 /* Select High-speed or Low-power for command transmission */
884 hdsi->Instance->CMCR &= ~(DSI_CMCR_GSW0TX |\
885 DSI_CMCR_GSW1TX |\
886 DSI_CMCR_GSW2TX |\
887 DSI_CMCR_GSR0TX |\
888 DSI_CMCR_GSR1TX |\
889 DSI_CMCR_GSR2TX |\
890 DSI_CMCR_GLWTX |\
891 DSI_CMCR_DSW0TX |\
892 DSI_CMCR_DSW1TX |\
893 DSI_CMCR_DSR0TX |\
894 DSI_CMCR_DLWTX |\
895 DSI_CMCR_MRDPS);
896 hdsi->Instance->CMCR |= (LPCmd->LPGenShortWriteNoP |\
897 LPCmd->LPGenShortWriteOneP |\
898 LPCmd->LPGenShortWriteTwoP |\
899 LPCmd->LPGenShortReadNoP |\
900 LPCmd->LPGenShortReadOneP |\
901 LPCmd->LPGenShortReadTwoP |\
902 LPCmd->LPGenLongWrite |\
903 LPCmd->LPDcsShortWriteNoP |\
904 LPCmd->LPDcsShortWriteOneP |\
905 LPCmd->LPDcsShortReadNoP |\
906 LPCmd->LPDcsLongWrite |\
907 LPCmd->LPMaxReadPacket);
909 /* Configure the acknowledge request after each packet transmission */
910 hdsi->Instance->CMCR &= ~DSI_CMCR_ARE;
911 hdsi->Instance->CMCR |= LPCmd->AcknowledgeRequest;
913 /* Process unlocked */
914 __HAL_UNLOCK(hdsi);
916 return HAL_OK;
920 * @brief Configure the flow control parameters
921 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
922 * the configuration information for the DSI.
923 * @param FlowControl: flow control feature(s) to be enabled.
924 * This parameter can be any combination of @ref DSI_FlowControl.
925 * @retval HAL status
927 HAL_StatusTypeDef HAL_DSI_ConfigFlowControl(DSI_HandleTypeDef *hdsi, uint32_t FlowControl)
929 /* Process locked */
930 __HAL_LOCK(hdsi);
932 /* Check the parameters */
933 assert_param(IS_DSI_FLOW_CONTROL(FlowControl));
935 /* Set the DSI Host Protocol Configuration Register */
936 hdsi->Instance->PCR &= ~DSI_FLOW_CONTROL_ALL;
937 hdsi->Instance->PCR |= FlowControl;
939 /* Process unlocked */
940 __HAL_UNLOCK(hdsi);
942 return HAL_OK;
946 * @brief Configure the DSI PHY timer parameters
947 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
948 * the configuration information for the DSI.
949 * @param PhyTimers: DSI_PHY_TimerTypeDef structure that contains
950 * the DSI PHY timing parameters
951 * @retval HAL status
953 HAL_StatusTypeDef HAL_DSI_ConfigPhyTimer(DSI_HandleTypeDef *hdsi, DSI_PHY_TimerTypeDef *PhyTimers)
955 uint32_t maxTime;
956 /* Process locked */
957 __HAL_LOCK(hdsi);
959 maxTime = (PhyTimers->ClockLaneLP2HSTime > PhyTimers->ClockLaneHS2LPTime)? PhyTimers->ClockLaneLP2HSTime: PhyTimers->ClockLaneHS2LPTime;
961 /* Clock lane timer configuration */
963 /* In Automatic Clock Lane control mode, the DSI Host can turn off the clock lane between two
964 High-Speed transmission.
965 To do so, the DSI Host calculates the time required for the clock lane to change from HighSpeed
966 to Low-Power and from Low-Power to High-Speed.
967 This timings are configured by the HS2LP_TIME and LP2HS_TIME in the DSI Host Clock Lane Timer Configuration Register (DSI_CLTCR).
968 But the DSI Host is not calculating LP2HS_TIME + HS2LP_TIME but 2 x HS2LP_TIME.
970 Workaround : Configure HS2LP_TIME and LP2HS_TIME with the same value being the max of HS2LP_TIME or LP2HS_TIME.
972 hdsi->Instance->CLTCR &= ~(DSI_CLTCR_LP2HS_TIME | DSI_CLTCR_HS2LP_TIME);
973 hdsi->Instance->CLTCR |= (maxTime | ((maxTime)<<16));
975 /* Data lane timer configuration */
976 hdsi->Instance->DLTCR &= ~(DSI_DLTCR_MRD_TIME | DSI_DLTCR_LP2HS_TIME | DSI_DLTCR_HS2LP_TIME);
977 hdsi->Instance->DLTCR |= (PhyTimers->DataLaneMaxReadTime | ((PhyTimers->DataLaneLP2HSTime)<<16) | ((PhyTimers->DataLaneHS2LPTime)<<24));
979 /* Configure the wait period to request HS transmission after a stop state */
980 hdsi->Instance->PCONFR &= ~DSI_PCONFR_SW_TIME;
981 hdsi->Instance->PCONFR |= ((PhyTimers->StopWaitTime)<<8);
983 /* Process unlocked */
984 __HAL_UNLOCK(hdsi);
986 return HAL_OK;
990 * @brief Configure the DSI HOST timeout parameters
991 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
992 * the configuration information for the DSI.
993 * @param HostTimeouts: DSI_HOST_TimeoutTypeDef structure that contains
994 * the DSI host timeout parameters
995 * @retval HAL status
997 HAL_StatusTypeDef HAL_DSI_ConfigHostTimeouts(DSI_HandleTypeDef *hdsi, DSI_HOST_TimeoutTypeDef *HostTimeouts)
999 /* Process locked */
1000 __HAL_LOCK(hdsi);
1002 /* Set the timeout clock division factor */
1003 hdsi->Instance->CCR &= ~DSI_CCR_TOCKDIV;
1004 hdsi->Instance->CCR |= ((HostTimeouts->TimeoutCkdiv)<<8);
1006 /* High-speed transmission timeout */
1007 hdsi->Instance->TCCR[0] &= ~DSI_TCCR0_HSTX_TOCNT;
1008 hdsi->Instance->TCCR[0] |= ((HostTimeouts->HighSpeedTransmissionTimeout)<<16);
1010 /* Low-power reception timeout */
1011 hdsi->Instance->TCCR[0] &= ~DSI_TCCR0_LPRX_TOCNT;
1012 hdsi->Instance->TCCR[0] |= HostTimeouts->LowPowerReceptionTimeout;
1014 /* High-speed read timeout */
1015 hdsi->Instance->TCCR[1] &= ~DSI_TCCR1_HSRD_TOCNT;
1016 hdsi->Instance->TCCR[1] |= HostTimeouts->HighSpeedReadTimeout;
1018 /* Low-power read timeout */
1019 hdsi->Instance->TCCR[2] &= ~DSI_TCCR2_LPRD_TOCNT;
1020 hdsi->Instance->TCCR[2] |= HostTimeouts->LowPowerReadTimeout;
1022 /* High-speed write timeout */
1023 hdsi->Instance->TCCR[3] &= ~DSI_TCCR3_HSWR_TOCNT;
1024 hdsi->Instance->TCCR[3] |= HostTimeouts->HighSpeedWriteTimeout;
1026 /* High-speed write presp mode */
1027 hdsi->Instance->TCCR[3] &= ~DSI_TCCR3_PM;
1028 hdsi->Instance->TCCR[3] |= HostTimeouts->HighSpeedWritePrespMode;
1030 /* Low-speed write timeout */
1031 hdsi->Instance->TCCR[4] &= ~DSI_TCCR4_LPWR_TOCNT;
1032 hdsi->Instance->TCCR[4] |= HostTimeouts->LowPowerWriteTimeout;
1034 /* BTA timeout */
1035 hdsi->Instance->TCCR[5] &= ~DSI_TCCR5_BTA_TOCNT;
1036 hdsi->Instance->TCCR[5] |= HostTimeouts->BTATimeout;
1038 /* Process unlocked */
1039 __HAL_UNLOCK(hdsi);
1041 return HAL_OK;
1045 * @brief Start the DSI module
1046 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1047 * the configuration information for the DSI.
1048 * @retval HAL status
1050 HAL_StatusTypeDef HAL_DSI_Start(DSI_HandleTypeDef *hdsi)
1052 /* Process locked */
1053 __HAL_LOCK(hdsi);
1055 /* Enable the DSI host */
1056 __HAL_DSI_ENABLE(hdsi);
1058 /* Enable the DSI wrapper */
1059 __HAL_DSI_WRAPPER_ENABLE(hdsi);
1061 /* Process unlocked */
1062 __HAL_UNLOCK(hdsi);
1064 return HAL_OK;
1068 * @brief Stop the DSI module
1069 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1070 * the configuration information for the DSI.
1071 * @retval HAL status
1073 HAL_StatusTypeDef HAL_DSI_Stop(DSI_HandleTypeDef *hdsi)
1075 /* Process locked */
1076 __HAL_LOCK(hdsi);
1078 /* Disable the DSI host */
1079 __HAL_DSI_DISABLE(hdsi);
1081 /* Disable the DSI wrapper */
1082 __HAL_DSI_WRAPPER_DISABLE(hdsi);
1084 /* Process unlocked */
1085 __HAL_UNLOCK(hdsi);
1087 return HAL_OK;
1091 * @brief Refresh the display in command mode
1092 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1093 * the configuration information for the DSI.
1094 * @retval HAL status
1096 HAL_StatusTypeDef HAL_DSI_Refresh(DSI_HandleTypeDef *hdsi)
1098 /* Process locked */
1099 __HAL_LOCK(hdsi);
1101 /* Update the display */
1102 hdsi->Instance->WCR |= DSI_WCR_LTDCEN;
1104 /* Process unlocked */
1105 __HAL_UNLOCK(hdsi);
1107 return HAL_OK;
1111 * @brief Controls the display color mode in Video mode
1112 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1113 * the configuration information for the DSI.
1114 * @param ColorMode: Color mode (full or 8-colors).
1115 * This parameter can be any value of @ref DSI_Color_Mode
1116 * @retval HAL status
1118 HAL_StatusTypeDef HAL_DSI_ColorMode(DSI_HandleTypeDef *hdsi, uint32_t ColorMode)
1120 /* Process locked */
1121 __HAL_LOCK(hdsi);
1123 /* Check the parameters */
1124 assert_param(IS_DSI_COLOR_MODE(ColorMode));
1126 /* Update the display color mode */
1127 hdsi->Instance->WCR &= ~DSI_WCR_COLM;
1128 hdsi->Instance->WCR |= ColorMode;
1130 /* Process unlocked */
1131 __HAL_UNLOCK(hdsi);
1133 return HAL_OK;
1137 * @brief Control the display shutdown in Video mode
1138 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1139 * the configuration information for the DSI.
1140 * @param Shutdown: Shut-down (Display-ON or Display-OFF).
1141 * This parameter can be any value of @ref DSI_ShutDown
1142 * @retval HAL status
1144 HAL_StatusTypeDef HAL_DSI_Shutdown(DSI_HandleTypeDef *hdsi, uint32_t Shutdown)
1146 /* Process locked */
1147 __HAL_LOCK(hdsi);
1149 /* Check the parameters */
1150 assert_param(IS_DSI_SHUT_DOWN(Shutdown));
1152 /* Update the display Shutdown */
1153 hdsi->Instance->WCR &= ~DSI_WCR_SHTDN;
1154 hdsi->Instance->WCR |= Shutdown;
1156 /* Process unlocked */
1157 __HAL_UNLOCK(hdsi);
1159 return HAL_OK;
1163 * @brief DCS or Generic short write command
1164 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1165 * the configuration information for the DSI.
1166 * @param ChannelID: Virtual channel ID.
1167 * @param Mode: DSI short packet data type.
1168 * This parameter can be any value of @ref DSI_SHORT_WRITE_PKT_Data_Type.
1169 * @param Param1: DSC command or first generic parameter.
1170 * This parameter can be any value of @ref DSI_DCS_Command or a
1171 * generic command code.
1172 * @param Param2: DSC parameter or second generic parameter.
1173 * @retval HAL status
1175 HAL_StatusTypeDef HAL_DSI_ShortWrite(DSI_HandleTypeDef *hdsi,
1176 uint32_t ChannelID,
1177 uint32_t Mode,
1178 uint32_t Param1,
1179 uint32_t Param2)
1181 uint32_t tickstart = 0;
1183 /* Process locked */
1184 __HAL_LOCK(hdsi);
1186 /* Check the parameters */
1187 assert_param(IS_DSI_SHORT_WRITE_PACKET_TYPE(Mode));
1189 /* Get tick */
1190 tickstart = HAL_GetTick();
1192 /* Wait for Command FIFO Empty */
1193 while((hdsi->Instance->GPSR & DSI_GPSR_CMDFE) == 0)
1195 /* Check for the Timeout */
1196 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1198 /* Process Unlocked */
1199 __HAL_UNLOCK(hdsi);
1201 return HAL_TIMEOUT;
1205 /* Configure the packet to send a short DCS command with 0 or 1 parameter */
1206 DSI_ConfigPacketHeader(hdsi->Instance,
1207 ChannelID,
1208 Mode,
1209 Param1,
1210 Param2);
1212 /* Process unlocked */
1213 __HAL_UNLOCK(hdsi);
1215 return HAL_OK;
1219 * @brief DCS or Generic long write command
1220 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1221 * the configuration information for the DSI.
1222 * @param ChannelID: Virtual channel ID.
1223 * @param Mode: DSI long packet data type.
1224 * This parameter can be any value of @ref DSI_LONG_WRITE_PKT_Data_Type.
1225 * @param NbParams: Number of parameters.
1226 * @param Param1: DSC command or first generic parameter.
1227 * This parameter can be any value of @ref DSI_DCS_Command or a
1228 * generic command code
1229 * @param ParametersTable: Pointer to parameter values table.
1230 * @retval HAL status
1232 HAL_StatusTypeDef HAL_DSI_LongWrite(DSI_HandleTypeDef *hdsi,
1233 uint32_t ChannelID,
1234 uint32_t Mode,
1235 uint32_t NbParams,
1236 uint32_t Param1,
1237 uint8_t* ParametersTable)
1239 uint32_t uicounter = 0;
1240 uint32_t tickstart = 0;
1242 /* Process locked */
1243 __HAL_LOCK(hdsi);
1245 /* Check the parameters */
1246 assert_param(IS_DSI_LONG_WRITE_PACKET_TYPE(Mode));
1248 /* Get tick */
1249 tickstart = HAL_GetTick();
1251 /* Wait for Command FIFO Empty */
1252 while((hdsi->Instance->GPSR & DSI_GPSR_CMDFE) == RESET)
1254 /* Check for the Timeout */
1255 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1257 /* Process Unlocked */
1258 __HAL_UNLOCK(hdsi);
1260 return HAL_TIMEOUT;
1264 /* Set the DCS code hexadecimal on payload byte 1, and the other parameters on the write FIFO command*/
1265 while(uicounter < NbParams)
1267 if(uicounter == 0x00)
1269 hdsi->Instance->GPDR=(Param1 | \
1270 ((uint32_t)(*(ParametersTable + uicounter)) << 8) | \
1271 ((uint32_t)(*(ParametersTable + uicounter+1))<<16) | \
1272 ((uint32_t)(*(ParametersTable + uicounter+2))<<24));
1273 uicounter += 3;
1275 else
1277 hdsi->Instance->GPDR=((uint32_t)(*(ParametersTable + uicounter)) | \
1278 ((uint32_t)(*(ParametersTable + uicounter+1)) << 8) | \
1279 ((uint32_t)(*(ParametersTable + uicounter+2)) << 16) | \
1280 ((uint32_t)(*(ParametersTable + uicounter+3)) << 24));
1281 uicounter+=4;
1285 /* Configure the packet to send a long DCS command */
1286 DSI_ConfigPacketHeader(hdsi->Instance,
1287 ChannelID,
1288 Mode,
1289 ((NbParams+1)&0x00FF),
1290 (((NbParams+1)&0xFF00)>>8));
1292 /* Process unlocked */
1293 __HAL_UNLOCK(hdsi);
1295 return HAL_OK;
1299 * @brief Read command (DCS or generic)
1300 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1301 * the configuration information for the DSI.
1302 * @param ChannelNbr: Virtual channel ID
1303 * @param Array: pointer to a buffer to store the payload of a read back operation.
1304 * @param Size: Data size to be read (in byte).
1305 * @param Mode: DSI read packet data type.
1306 * This parameter can be any value of @ref DSI_SHORT_READ_PKT_Data_Type.
1307 * @param DCSCmd: DCS get/read command.
1308 * @param ParametersTable: Pointer to parameter values table.
1309 * @retval HAL status
1311 HAL_StatusTypeDef HAL_DSI_Read(DSI_HandleTypeDef *hdsi,
1312 uint32_t ChannelNbr,
1313 uint8_t* Array,
1314 uint32_t Size,
1315 uint32_t Mode,
1316 uint32_t DCSCmd,
1317 uint8_t* ParametersTable)
1319 uint32_t tickstart = 0;
1321 /* Process locked */
1322 __HAL_LOCK(hdsi);
1324 /* Check the parameters */
1325 assert_param(IS_DSI_READ_PACKET_TYPE(Mode));
1327 if(Size > 2)
1329 /* set max return packet size */
1330 HAL_DSI_ShortWrite(hdsi, ChannelNbr, DSI_MAX_RETURN_PKT_SIZE, ((Size)&0xFF), (((Size)>>8)&0xFF));
1333 /* Configure the packet to read command */
1334 if (Mode == DSI_DCS_SHORT_PKT_READ)
1336 DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, DCSCmd, 0);
1338 else if (Mode == DSI_GEN_SHORT_PKT_READ_P0)
1340 DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, 0, 0);
1342 else if (Mode == DSI_GEN_SHORT_PKT_READ_P1)
1344 DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, ParametersTable[0], 0);
1346 else if (Mode == DSI_GEN_SHORT_PKT_READ_P2)
1348 DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, ParametersTable[0], ParametersTable[1]);
1350 else
1352 /* Process Unlocked */
1353 __HAL_UNLOCK(hdsi);
1355 return HAL_ERROR;
1358 /* Get tick */
1359 tickstart = HAL_GetTick();
1361 /* Check that the payload read FIFO is not empty */
1362 while((hdsi->Instance->GPSR & DSI_GPSR_PRDFE) == DSI_GPSR_PRDFE)
1364 /* Check for the Timeout */
1365 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1367 /* Process Unlocked */
1368 __HAL_UNLOCK(hdsi);
1370 return HAL_TIMEOUT;
1374 /* Get the first byte */
1375 *((uint32_t *)Array) = (hdsi->Instance->GPDR);
1376 if (Size > 4)
1378 Size -= 4;
1379 Array += 4;
1381 else
1383 /* Process unlocked */
1384 __HAL_UNLOCK(hdsi);
1386 return HAL_OK;
1389 /* Get tick */
1390 tickstart = HAL_GetTick();
1392 /* Get the remaining bytes if any */
1393 while(((int)(Size)) > 0)
1395 if((hdsi->Instance->GPSR & DSI_GPSR_PRDFE) == 0)
1397 *((uint32_t *)Array) = (hdsi->Instance->GPDR);
1398 Size -= 4;
1399 Array += 4;
1402 /* Check for the Timeout */
1403 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1405 /* Process Unlocked */
1406 __HAL_UNLOCK(hdsi);
1408 return HAL_TIMEOUT;
1412 /* Process unlocked */
1413 __HAL_UNLOCK(hdsi);
1415 return HAL_OK;
1419 * @brief Enter the ULPM (Ultra Low Power Mode) with the D-PHY PLL running
1420 * (only data lanes are in ULPM)
1421 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1422 * the configuration information for the DSI.
1423 * @retval HAL status
1425 HAL_StatusTypeDef HAL_DSI_EnterULPMData(DSI_HandleTypeDef *hdsi)
1427 uint32_t tickstart = 0;
1429 /* Process locked */
1430 __HAL_LOCK(hdsi);
1432 /* ULPS Request on Data Lanes */
1433 hdsi->Instance->PUCR |= DSI_PUCR_URDL;
1435 /* Get tick */
1436 tickstart = HAL_GetTick();
1438 /* Wait until the D-PHY active lanes enter into ULPM */
1439 if((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE)
1441 while((hdsi->Instance->PSR & DSI_PSR_UAN0) != RESET)
1443 /* Check for the Timeout */
1444 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1446 /* Process Unlocked */
1447 __HAL_UNLOCK(hdsi);
1449 return HAL_TIMEOUT;
1453 else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES)
1455 while((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1)) != RESET)
1457 /* Check for the Timeout */
1458 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1460 /* Process Unlocked */
1461 __HAL_UNLOCK(hdsi);
1463 return HAL_TIMEOUT;
1468 /* Process unlocked */
1469 __HAL_UNLOCK(hdsi);
1471 return HAL_OK;
1475 * @brief Exit the ULPM (Ultra Low Power Mode) with the D-PHY PLL running
1476 * (only data lanes are in ULPM)
1477 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1478 * the configuration information for the DSI.
1479 * @retval HAL status
1481 HAL_StatusTypeDef HAL_DSI_ExitULPMData(DSI_HandleTypeDef *hdsi)
1483 uint32_t tickstart = 0;
1485 /* Process locked */
1486 __HAL_LOCK(hdsi);
1488 /* Exit ULPS on Data Lanes */
1489 hdsi->Instance->PUCR |= DSI_PUCR_UEDL;
1491 /* Get tick */
1492 tickstart = HAL_GetTick();
1494 /* Wait until all active lanes exit ULPM */
1495 if((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE)
1497 while((hdsi->Instance->PSR & DSI_PSR_UAN0) != DSI_PSR_UAN0)
1499 /* Check for the Timeout */
1500 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1502 /* Process Unlocked */
1503 __HAL_UNLOCK(hdsi);
1505 return HAL_TIMEOUT;
1509 else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES)
1511 while((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1)) != (DSI_PSR_UAN0 | DSI_PSR_UAN1))
1513 /* Check for the Timeout */
1514 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1516 /* Process Unlocked */
1517 __HAL_UNLOCK(hdsi);
1519 return HAL_TIMEOUT;
1524 /* De-assert the ULPM requests and the ULPM exit bits */
1525 hdsi->Instance->PUCR = 0;
1527 /* Process unlocked */
1528 __HAL_UNLOCK(hdsi);
1530 return HAL_OK;
1534 * @brief Enter the ULPM (Ultra Low Power Mode) with the D-PHY PLL turned off
1535 * (both data and clock lanes are in ULPM)
1536 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1537 * the configuration information for the DSI.
1538 * @retval HAL status
1540 HAL_StatusTypeDef HAL_DSI_EnterULPM(DSI_HandleTypeDef *hdsi)
1542 uint32_t tickstart = 0;
1544 /* Process locked */
1545 __HAL_LOCK(hdsi);
1547 /* Clock lane configuration: no more HS request */
1548 hdsi->Instance->CLCR &= ~DSI_CLCR_DPCC;
1550 /* Use system PLL as byte lane clock source before stopping DSIPHY clock source */
1551 __HAL_RCC_DSI_CONFIG(RCC_DSICLKSOURCE_PLLR);
1553 /* ULPS Request on Clock and Data Lanes */
1554 hdsi->Instance->PUCR |= (DSI_PUCR_URCL | DSI_PUCR_URDL);
1556 /* Get tick */
1557 tickstart = HAL_GetTick();
1559 /* Wait until all active lanes exit ULPM */
1560 if((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE)
1562 while((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UANC)) != RESET)
1564 /* Check for the Timeout */
1565 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1567 /* Process Unlocked */
1568 __HAL_UNLOCK(hdsi);
1570 return HAL_TIMEOUT;
1574 else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES)
1576 while((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC)) != RESET)
1578 /* Check for the Timeout */
1579 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1581 /* Process Unlocked */
1582 __HAL_UNLOCK(hdsi);
1584 return HAL_TIMEOUT;
1589 /* Turn off the DSI PLL */
1590 __HAL_DSI_PLL_DISABLE(hdsi);
1592 /* Process unlocked */
1593 __HAL_UNLOCK(hdsi);
1595 return HAL_OK;
1599 * @brief Exit the ULPM (Ultra Low Power Mode) with the D-PHY PLL turned off
1600 * (both data and clock lanes are in ULPM)
1601 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1602 * the configuration information for the DSI.
1603 * @retval HAL status
1605 HAL_StatusTypeDef HAL_DSI_ExitULPM(DSI_HandleTypeDef *hdsi)
1607 uint32_t tickstart = 0;
1609 /* Process locked */
1610 __HAL_LOCK(hdsi);
1612 /* Turn on the DSI PLL */
1613 __HAL_DSI_PLL_ENABLE(hdsi);
1615 /* Get tick */
1616 tickstart = HAL_GetTick();
1618 /* Wait for the lock of the PLL */
1619 while(__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_PLLLS) == RESET)
1621 /* Check for the Timeout */
1622 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1624 /* Process Unlocked */
1625 __HAL_UNLOCK(hdsi);
1627 return HAL_TIMEOUT;
1631 /* Exit ULPS on Clock and Data Lanes */
1632 hdsi->Instance->PUCR |= (DSI_PUCR_UECL | DSI_PUCR_UEDL);
1634 /* Get tick */
1635 tickstart = HAL_GetTick();
1637 /* Wait until all active lanes exit ULPM */
1638 if((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE)
1640 while((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UANC)) != (DSI_PSR_UAN0 | DSI_PSR_UANC))
1642 /* Check for the Timeout */
1643 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1645 /* Process Unlocked */
1646 __HAL_UNLOCK(hdsi);
1648 return HAL_TIMEOUT;
1652 else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES)
1654 while((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC)) != (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC))
1656 /* Check for the Timeout */
1657 if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE)
1659 /* Process Unlocked */
1660 __HAL_UNLOCK(hdsi);
1662 return HAL_TIMEOUT;
1667 /* De-assert the ULPM requests and the ULPM exit bits */
1668 hdsi->Instance->PUCR = 0;
1670 /* Switch the lanbyteclock source in the RCC from system PLL to D-PHY */
1671 __HAL_RCC_DSI_CONFIG(RCC_DSICLKSOURCE_DSIPHY);
1673 /* Restore clock lane configuration to HS */
1674 hdsi->Instance->CLCR |= DSI_CLCR_DPCC;
1676 /* Process unlocked */
1677 __HAL_UNLOCK(hdsi);
1679 return HAL_OK;
1683 * @brief Start test pattern generation
1684 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1685 * the configuration information for the DSI.
1686 * @param Mode: Pattern generator mode
1687 * This parameter can be one of the following values:
1688 * 0 : Color bars (horizontal or vertical)
1689 * 1 : BER pattern (vertical only)
1690 * @param Orientation: Pattern generator orientation
1691 * This parameter can be one of the following values:
1692 * 0 : Vertical color bars
1693 * 1 : Horizontal color bars
1694 * @retval HAL status
1696 HAL_StatusTypeDef HAL_DSI_PatternGeneratorStart(DSI_HandleTypeDef *hdsi, uint32_t Mode, uint32_t Orientation)
1698 /* Process locked */
1699 __HAL_LOCK(hdsi);
1701 /* Configure pattern generator mode and orientation */
1702 hdsi->Instance->VMCR &= ~(DSI_VMCR_PGM | DSI_VMCR_PGO);
1703 hdsi->Instance->VMCR |= ((Mode<<20) | (Orientation<<24));
1705 /* Enable pattern generator by setting PGE bit */
1706 hdsi->Instance->VMCR |= DSI_VMCR_PGE;
1708 /* Process unlocked */
1709 __HAL_UNLOCK(hdsi);
1711 return HAL_OK;
1715 * @brief Stop test pattern generation
1716 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1717 * the configuration information for the DSI.
1718 * @retval HAL status
1720 HAL_StatusTypeDef HAL_DSI_PatternGeneratorStop(DSI_HandleTypeDef *hdsi)
1722 /* Process locked */
1723 __HAL_LOCK(hdsi);
1725 /* Disable pattern generator by clearing PGE bit */
1726 hdsi->Instance->VMCR &= ~DSI_VMCR_PGE;
1728 /* Process unlocked */
1729 __HAL_UNLOCK(hdsi);
1731 return HAL_OK;
1735 * @brief Set Slew-Rate And Delay Tuning
1736 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1737 * the configuration information for the DSI.
1738 * @param CommDelay: Communication delay to be adjusted.
1739 * This parameter can be any value of @ref DSI_Communication_Delay
1740 * @param Lane: select between clock or data lanes.
1741 * This parameter can be any value of @ref DSI_Lane_Group
1742 * @param Value: Custom value of the slew-rate or delay
1743 * @retval HAL status
1745 HAL_StatusTypeDef HAL_DSI_SetSlewRateAndDelayTuning(DSI_HandleTypeDef *hdsi, uint32_t CommDelay, uint32_t Lane, uint32_t Value)
1747 /* Process locked */
1748 __HAL_LOCK(hdsi);
1750 /* Check function parameters */
1751 assert_param(IS_DSI_COMMUNICATION_DELAY(CommDelay));
1752 assert_param(IS_DSI_LANE_GROUP(Lane));
1754 switch(CommDelay)
1756 case DSI_SLEW_RATE_HSTX:
1757 if(Lane == DSI_CLOCK_LANE)
1759 /* High-Speed Transmission Slew Rate Control on Clock Lane */
1760 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_HSTXSRCCL;
1761 hdsi->Instance->WPCR[1] |= Value<<16;
1763 else if(Lane == DSI_DATA_LANES)
1765 /* High-Speed Transmission Slew Rate Control on Data Lanes */
1766 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_HSTXSRCDL;
1767 hdsi->Instance->WPCR[1] |= Value<<18;
1769 break;
1770 case DSI_SLEW_RATE_LPTX:
1771 if(Lane == DSI_CLOCK_LANE)
1773 /* Low-Power transmission Slew Rate Compensation on Clock Lane */
1774 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_LPSRCCL;
1775 hdsi->Instance->WPCR[1] |= Value<<6;
1777 else if(Lane == DSI_DATA_LANES)
1779 /* Low-Power transmission Slew Rate Compensation on Data Lanes */
1780 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_LPSRCDL;
1781 hdsi->Instance->WPCR[1] |= Value<<8;
1783 break;
1784 case DSI_HS_DELAY:
1785 if(Lane == DSI_CLOCK_LANE)
1787 /* High-Speed Transmission Delay on Clock Lane */
1788 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_HSTXDCL;
1789 hdsi->Instance->WPCR[1] |= Value;
1791 else if(Lane == DSI_DATA_LANES)
1793 /* High-Speed Transmission Delay on Data Lanes */
1794 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_HSTXDDL;
1795 hdsi->Instance->WPCR[1] |= Value<<2;
1797 break;
1798 default:
1799 break;
1802 /* Process unlocked */
1803 __HAL_UNLOCK(hdsi);
1805 return HAL_OK;
1809 * @brief Low-Power Reception Filter Tuning
1810 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1811 * the configuration information for the DSI.
1812 * @param Frequency: cutoff frequency of low-pass filter at the input of LPRX
1813 * @retval HAL status
1815 HAL_StatusTypeDef HAL_DSI_SetLowPowerRXFilter(DSI_HandleTypeDef *hdsi, uint32_t Frequency)
1817 /* Process locked */
1818 __HAL_LOCK(hdsi);
1820 /* Low-Power RX low-pass Filtering Tuning */
1821 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_LPRXFT;
1822 hdsi->Instance->WPCR[1] |= Frequency<<25;
1824 /* Process unlocked */
1825 __HAL_UNLOCK(hdsi);
1827 return HAL_OK;
1831 * @brief Activate an additional current path on all lanes to meet the SDDTx parameter
1832 * defined in the MIPI D-PHY specification
1833 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1834 * the configuration information for the DSI.
1835 * @param State: ENABLE or DISABLE
1836 * @retval HAL status
1838 HAL_StatusTypeDef HAL_DSI_SetSDD(DSI_HandleTypeDef *hdsi, FunctionalState State)
1840 /* Process locked */
1841 __HAL_LOCK(hdsi);
1843 /* Check function parameters */
1844 assert_param(IS_FUNCTIONAL_STATE(State));
1846 /* Activate/Disactivate additional current path on all lanes */
1847 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_SDDC;
1848 hdsi->Instance->WPCR[1] |= ((uint32_t)State << 12);
1850 /* Process unlocked */
1851 __HAL_UNLOCK(hdsi);
1853 return HAL_OK;
1857 * @brief Custom lane pins configuration
1858 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1859 * the configuration information for the DSI.
1860 * @param CustomLane: Function to be applyed on selected lane.
1861 * This parameter can be any value of @ref DSI_CustomLane
1862 * @param Lane: select between clock or data lane 0 or data lane 1.
1863 * This parameter can be any value of @ref DSI_Lane_Select
1864 * @param State: ENABLE or DISABLE
1865 * @retval HAL status
1867 HAL_StatusTypeDef HAL_DSI_SetLanePinsConfiguration(DSI_HandleTypeDef *hdsi, uint32_t CustomLane, uint32_t Lane, FunctionalState State)
1869 /* Process locked */
1870 __HAL_LOCK(hdsi);
1872 /* Check function parameters */
1873 assert_param(IS_DSI_CUSTOM_LANE(CustomLane));
1874 assert_param(IS_DSI_LANE(Lane));
1875 assert_param(IS_FUNCTIONAL_STATE(State));
1877 switch(CustomLane)
1879 case DSI_SWAP_LANE_PINS:
1880 if(Lane == DSI_CLOCK_LANE)
1882 /* Swap pins on clock lane */
1883 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_SWCL;
1884 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 6);
1886 else if(Lane == DSI_DATA_LANE0)
1888 /* Swap pins on data lane 0 */
1889 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_SWDL0;
1890 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 7);
1892 else if(Lane == DSI_DATA_LANE1)
1894 /* Swap pins on data lane 1 */
1895 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_SWDL1;
1896 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 8);
1898 break;
1899 case DSI_INVERT_HS_SIGNAL:
1900 if(Lane == DSI_CLOCK_LANE)
1902 /* Invert HS signal on clock lane */
1903 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_HSICL;
1904 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 9);
1906 else if(Lane == DSI_DATA_LANE0)
1908 /* Invert HS signal on data lane 0 */
1909 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_HSIDL0;
1910 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 10);
1912 else if(Lane == DSI_DATA_LANE1)
1914 /* Invert HS signal on data lane 1 */
1915 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_HSIDL1;
1916 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 11);
1918 break;
1919 default:
1920 break;
1923 /* Process unlocked */
1924 __HAL_UNLOCK(hdsi);
1926 return HAL_OK;
1930 * @brief Set custom timing for the PHY
1931 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
1932 * the configuration information for the DSI.
1933 * @param Timing: PHY timing to be adjusted.
1934 * This parameter can be any value of @ref DSI_PHY_Timing
1935 * @param State: ENABLE or DISABLE
1936 * @param Value: Custom value of the timing
1937 * @retval HAL status
1939 HAL_StatusTypeDef HAL_DSI_SetPHYTimings(DSI_HandleTypeDef *hdsi, uint32_t Timing, FunctionalState State, uint32_t Value)
1941 /* Process locked */
1942 __HAL_LOCK(hdsi);
1944 /* Check function parameters */
1945 assert_param(IS_DSI_PHY_TIMING(Timing));
1946 assert_param(IS_FUNCTIONAL_STATE(State));
1948 switch(Timing)
1950 case DSI_TCLK_POST:
1951 /* Enable/Disable custom timing setting */
1952 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_TCLKPOSTEN;
1953 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 27);
1955 if(State)
1957 /* Set custom value */
1958 hdsi->Instance->WPCR[4] &= ~DSI_WPCR4_TCLKPOST;
1959 hdsi->Instance->WPCR[4] |= Value & DSI_WPCR4_TCLKPOST;
1962 break;
1963 case DSI_TLPX_CLK:
1964 /* Enable/Disable custom timing setting */
1965 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_TLPXCEN;
1966 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 26);
1968 if(State)
1970 /* Set custom value */
1971 hdsi->Instance->WPCR[3] &= ~DSI_WPCR3_TLPXC;
1972 hdsi->Instance->WPCR[3] |= (Value << 24) & DSI_WPCR3_TLPXC;
1975 break;
1976 case DSI_THS_EXIT:
1977 /* Enable/Disable custom timing setting */
1978 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_THSEXITEN;
1979 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 25);
1981 if(State)
1983 /* Set custom value */
1984 hdsi->Instance->WPCR[3] &= ~DSI_WPCR3_THSEXIT;
1985 hdsi->Instance->WPCR[3] |= (Value << 16) & DSI_WPCR3_THSEXIT;
1988 break;
1989 case DSI_TLPX_DATA:
1990 /* Enable/Disable custom timing setting */
1991 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_TLPXDEN;
1992 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 24);
1994 if(State)
1996 /* Set custom value */
1997 hdsi->Instance->WPCR[3] &= ~DSI_WPCR3_TLPXD;
1998 hdsi->Instance->WPCR[3] |= (Value << 8) & DSI_WPCR3_TLPXD;
2001 break;
2002 case DSI_THS_ZERO:
2003 /* Enable/Disable custom timing setting */
2004 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_THSZEROEN;
2005 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 23);
2007 if(State)
2009 /* Set custom value */
2010 hdsi->Instance->WPCR[3] &= ~DSI_WPCR3_THSZERO;
2011 hdsi->Instance->WPCR[3] |= Value & DSI_WPCR3_THSZERO;
2014 break;
2015 case DSI_THS_TRAIL:
2016 /* Enable/Disable custom timing setting */
2017 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_THSTRAILEN;
2018 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 22);
2020 if(State)
2022 /* Set custom value */
2023 hdsi->Instance->WPCR[2] &= ~DSI_WPCR2_THSTRAIL;
2024 hdsi->Instance->WPCR[2] |= (Value << 24) & DSI_WPCR2_THSTRAIL;
2027 break;
2028 case DSI_THS_PREPARE:
2029 /* Enable/Disable custom timing setting */
2030 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_THSPREPEN;
2031 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 21);
2033 if(State)
2035 /* Set custom value */
2036 hdsi->Instance->WPCR[2] &= ~DSI_WPCR2_THSPREP;
2037 hdsi->Instance->WPCR[2] |= (Value << 16) & DSI_WPCR2_THSPREP;
2040 break;
2041 case DSI_TCLK_ZERO:
2042 /* Enable/Disable custom timing setting */
2043 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_TCLKZEROEN;
2044 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 20);
2046 if(State)
2048 /* Set custom value */
2049 hdsi->Instance->WPCR[2] &= ~DSI_WPCR2_TCLKZERO;
2050 hdsi->Instance->WPCR[2] |= (Value << 8) & DSI_WPCR2_TCLKZERO;
2053 break;
2054 case DSI_TCLK_PREPARE:
2055 /* Enable/Disable custom timing setting */
2056 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_TCLKPREPEN;
2057 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 19);
2059 if(State)
2061 /* Set custom value */
2062 hdsi->Instance->WPCR[2] &= ~DSI_WPCR2_TCLKPREP;
2063 hdsi->Instance->WPCR[2] |= Value & DSI_WPCR2_TCLKPREP;
2066 break;
2067 default:
2068 break;
2071 /* Process unlocked */
2072 __HAL_UNLOCK(hdsi);
2074 return HAL_OK;
2078 * @brief Force the Clock/Data Lane in TX Stop Mode
2079 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
2080 * the configuration information for the DSI.
2081 * @param Lane: select between clock or data lanes.
2082 * This parameter can be any value of @ref DSI_Lane_Group
2083 * @param State: ENABLE or DISABLE
2084 * @retval HAL status
2086 HAL_StatusTypeDef HAL_DSI_ForceTXStopMode(DSI_HandleTypeDef *hdsi, uint32_t Lane, FunctionalState State)
2088 /* Process locked */
2089 __HAL_LOCK(hdsi);
2091 /* Check function parameters */
2092 assert_param(IS_DSI_LANE_GROUP(Lane));
2093 assert_param(IS_FUNCTIONAL_STATE(State));
2095 if(Lane == DSI_CLOCK_LANE)
2097 /* Force/Unforce the Clock Lane in TX Stop Mode */
2098 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_FTXSMCL;
2099 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 12);
2101 else if(Lane == DSI_DATA_LANES)
2103 /* Force/Unforce the Data Lanes in TX Stop Mode */
2104 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_FTXSMDL;
2105 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 13);
2108 /* Process unlocked */
2109 __HAL_UNLOCK(hdsi);
2111 return HAL_OK;
2115 * @brief Forces LP Receiver in Low-Power Mode
2116 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
2117 * the configuration information for the DSI.
2118 * @param State: ENABLE or DISABLE
2119 * @retval HAL status
2121 HAL_StatusTypeDef HAL_DSI_ForceRXLowPower(DSI_HandleTypeDef *hdsi, FunctionalState State)
2123 /* Process locked */
2124 __HAL_LOCK(hdsi);
2126 /* Check function parameters */
2127 assert_param(IS_FUNCTIONAL_STATE(State));
2129 /* Force/Unforce LP Receiver in Low-Power Mode */
2130 hdsi->Instance->WPCR[1] &= ~DSI_WPCR1_FLPRXLPM;
2131 hdsi->Instance->WPCR[1] |= ((uint32_t)State << 22);
2133 /* Process unlocked */
2134 __HAL_UNLOCK(hdsi);
2136 return HAL_OK;
2140 * @brief Force Data Lanes in RX Mode after a BTA
2141 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
2142 * the configuration information for the DSI.
2143 * @param State: ENABLE or DISABLE
2144 * @retval HAL status
2146 HAL_StatusTypeDef HAL_DSI_ForceDataLanesInRX(DSI_HandleTypeDef *hdsi, FunctionalState State)
2148 /* Process locked */
2149 __HAL_LOCK(hdsi);
2151 /* Check function parameters */
2152 assert_param(IS_FUNCTIONAL_STATE(State));
2154 /* Force Data Lanes in RX Mode */
2155 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_TDDL;
2156 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 16);
2158 /* Process unlocked */
2159 __HAL_UNLOCK(hdsi);
2161 return HAL_OK;
2165 * @brief Enable a pull-down on the lanes to prevent from floating states when unused
2166 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
2167 * the configuration information for the DSI.
2168 * @param State: ENABLE or DISABLE
2169 * @retval HAL status
2171 HAL_StatusTypeDef HAL_DSI_SetPullDown(DSI_HandleTypeDef *hdsi, FunctionalState State)
2173 /* Process locked */
2174 __HAL_LOCK(hdsi);
2176 /* Check function parameters */
2177 assert_param(IS_FUNCTIONAL_STATE(State));
2179 /* Enable/Disable pull-down on lanes */
2180 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_PDEN;
2181 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 18);
2183 /* Process unlocked */
2184 __HAL_UNLOCK(hdsi);
2186 return HAL_OK;
2190 * @brief Switch off the contention detection on data lanes
2191 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
2192 * the configuration information for the DSI.
2193 * @param State: ENABLE or DISABLE
2194 * @retval HAL status
2196 HAL_StatusTypeDef HAL_DSI_SetContentionDetectionOff(DSI_HandleTypeDef *hdsi, FunctionalState State)
2198 /* Process locked */
2199 __HAL_LOCK(hdsi);
2201 /* Check function parameters */
2202 assert_param(IS_FUNCTIONAL_STATE(State));
2204 /* Contention Detection on Data Lanes OFF */
2205 hdsi->Instance->WPCR[0] &= ~DSI_WPCR0_CDOFFDL;
2206 hdsi->Instance->WPCR[0] |= ((uint32_t)State << 14);
2208 /* Process unlocked */
2209 __HAL_UNLOCK(hdsi);
2211 return HAL_OK;
2215 * @}
2218 /** @defgroup DSI_Group4 Peripheral State and Errors functions
2219 * @brief Peripheral State and Errors functions
2221 @verbatim
2222 ===============================================================================
2223 ##### Peripheral State and Errors functions #####
2224 ===============================================================================
2225 [..]
2226 This subsection provides functions allowing to
2227 (+) Check the DSI state.
2228 (+) Get error code.
2230 @endverbatim
2231 * @{
2235 * @brief Return the DSI state
2236 * @param hdsi: pointer to a DSI_HandleTypeDef structure that contains
2237 * the configuration information for the DSI.
2238 * @retval HAL state
2240 HAL_DSI_StateTypeDef HAL_DSI_GetState(DSI_HandleTypeDef *hdsi)
2242 return hdsi->State;
2246 * @}
2250 * @}
2252 #endif /*STM32F769xx | STM32F779xx */
2253 #endif /* HAL_DSI_MODULE_ENABLED */
2255 * @}
2259 * @}
2262 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/