Merge pull request #10558 from iNavFlight/MrD_Correct-comments-on-OSD-symbols
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_dcmi.c
blob58873b971c887a1827a6c11b261bd4229c599aa1
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_dcmi.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief DCMI HAL module driver
8 * This file provides firmware functions to manage the following
9 * functionalities of the Digital Camera Interface (DCMI) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State and Error functions
15 @verbatim
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
19 [..]
20 The sequence below describes how to use this driver to capture image
21 from a camera module connected to the DCMI Interface.
22 This sequence does not take into account the configuration of the
23 camera module, which should be made before to configure and enable
24 the DCMI to capture images.
26 (#) Program the required configuration through following parameters:
27 horizontal and vertical polarity, pixel clock polarity, Capture Rate,
28 Synchronization Mode, code of the frame delimiter and data width
29 using HAL_DCMI_Init() function.
31 (#) Configure the DMA2_Stream1 channel1 to transfer Data from DCMI DR
32 register to the destination memory buffer.
34 (#) Program the required configuration through following parameters:
35 DCMI mode, destination memory Buffer address and the data length
36 and enable capture using HAL_DCMI_Start_DMA() function.
38 (#) Optionally, configure and Enable the CROP feature to select a rectangular
39 window from the received image using HAL_DCMI_ConfigCrop()
40 and HAL_DCMI_EnableCROP() functions
42 (#) The capture can be stopped using HAL_DCMI_Stop() function.
44 (#) To control DCMI state you can use the function HAL_DCMI_GetState().
46 *** DCMI HAL driver macros list ***
47 =============================================
48 [..]
49 Below the list of most used macros in DCMI HAL driver.
51 (+) __HAL_DCMI_ENABLE: Enable the DCMI peripheral.
52 (+) __HAL_DCMI_DISABLE: Disable the DCMI peripheral.
53 (+) __HAL_DCMI_GET_FLAG: Get the DCMI pending flags.
54 (+) __HAL_DCMI_CLEAR_FLAG: Clear the DCMI pending flags.
55 (+) __HAL_DCMI_ENABLE_IT: Enable the specified DCMI interrupts.
56 (+) __HAL_DCMI_DISABLE_IT: Disable the specified DCMI interrupts.
57 (+) __HAL_DCMI_GET_IT_SOURCE: Check whether the specified DCMI interrupt has occurred or not.
59 [..]
60 (@) You can refer to the DCMI HAL driver header file for more useful macros
62 @endverbatim
63 ******************************************************************************
64 * @attention
66 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
68 * Redistribution and use in source and binary forms, with or without modification,
69 * are permitted provided that the following conditions are met:
70 * 1. Redistributions of source code must retain the above copyright notice,
71 * this list of conditions and the following disclaimer.
72 * 2. Redistributions in binary form must reproduce the above copyright notice,
73 * this list of conditions and the following disclaimer in the documentation
74 * and/or other materials provided with the distribution.
75 * 3. Neither the name of STMicroelectronics nor the names of its contributors
76 * may be used to endorse or promote products derived from this software
77 * without specific prior written permission.
79 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
80 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
81 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
82 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
83 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
84 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
85 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
86 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
87 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
88 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
90 ******************************************************************************
91 */
93 /* Includes ------------------------------------------------------------------*/
94 #include "stm32f7xx_hal.h"
96 /** @addtogroup STM32F7xx_HAL_Driver
97 * @{
99 /** @defgroup DCMI DCMI
100 * @brief DCMI HAL module driver
101 * @{
104 #ifdef HAL_DCMI_MODULE_ENABLED
105 #if defined (DCMI)
107 /* Private typedef -----------------------------------------------------------*/
108 /* Private define ------------------------------------------------------------*/
109 #define HAL_TIMEOUT_DCMI_STOP ((uint32_t)1000) /* Set timeout to 1s */
111 #define DCMI_POSITION_CWSIZE_VLINE (uint32_t)POSITION_VAL(DCMI_CWSIZE_VLINE) /*!< Required left shift to set crop window vertical line count */
112 #define DCMI_POSITION_CWSTRT_VST (uint32_t)POSITION_VAL(DCMI_CWSTRT_VST) /*!< Required left shift to set crop window vertical start line count */
114 #define DCMI_POSITION_ESCR_LSC (uint32_t)POSITION_VAL(DCMI_ESCR_LSC) /*!< Required left shift to set line start delimiter */
115 #define DCMI_POSITION_ESCR_LEC (uint32_t)POSITION_VAL(DCMI_ESCR_LEC) /*!< Required left shift to set line end delimiter */
116 #define DCMI_POSITION_ESCR_FEC (uint32_t)POSITION_VAL(DCMI_ESCR_FEC) /*!< Required left shift to set frame end delimiter */
118 /* Private macro -------------------------------------------------------------*/
119 /* Private variables ---------------------------------------------------------*/
120 /* Private function prototypes -----------------------------------------------*/
121 static void DCMI_DMAXferCplt(DMA_HandleTypeDef *hdma);
122 static void DCMI_DMAError(DMA_HandleTypeDef *hdma);
124 /* Exported functions --------------------------------------------------------*/
126 /** @defgroup DCMI_Exported_Functions DCMI Exported Functions
127 * @{
130 /** @defgroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions
131 * @brief Initialization and Configuration functions
133 @verbatim
134 ===============================================================================
135 ##### Initialization and Configuration functions #####
136 ===============================================================================
137 [..] This section provides functions allowing to:
138 (+) Initialize and configure the DCMI
139 (+) De-initialize the DCMI
141 @endverbatim
142 * @{
146 * @brief Initializes the DCMI according to the specified
147 * parameters in the DCMI_InitTypeDef and create the associated handle.
148 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
149 * the configuration information for DCMI.
150 * @retval HAL status
152 HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi)
154 /* Check the DCMI peripheral state */
155 if(hdcmi == NULL)
157 return HAL_ERROR;
160 /* Check function parameters */
161 assert_param(IS_DCMI_ALL_INSTANCE(hdcmi->Instance));
162 assert_param(IS_DCMI_PCKPOLARITY(hdcmi->Init.PCKPolarity));
163 assert_param(IS_DCMI_VSPOLARITY(hdcmi->Init.VSPolarity));
164 assert_param(IS_DCMI_HSPOLARITY(hdcmi->Init.HSPolarity));
165 assert_param(IS_DCMI_SYNCHRO(hdcmi->Init.SynchroMode));
166 assert_param(IS_DCMI_CAPTURE_RATE(hdcmi->Init.CaptureRate));
167 assert_param(IS_DCMI_EXTENDED_DATA(hdcmi->Init.ExtendedDataMode));
168 assert_param(IS_DCMI_MODE_JPEG(hdcmi->Init.JPEGMode));
170 assert_param(IS_DCMI_BYTE_SELECT_MODE(hdcmi->Init.ByteSelectMode));
171 assert_param(IS_DCMI_BYTE_SELECT_START(hdcmi->Init.ByteSelectStart));
172 assert_param(IS_DCMI_LINE_SELECT_MODE(hdcmi->Init.LineSelectMode));
173 assert_param(IS_DCMI_LINE_SELECT_START(hdcmi->Init.LineSelectStart));
175 if(hdcmi->State == HAL_DCMI_STATE_RESET)
177 /* Init the low level hardware */
178 HAL_DCMI_MspInit(hdcmi);
181 /* Change the DCMI state */
182 hdcmi->State = HAL_DCMI_STATE_BUSY;
183 /* Configures the HS, VS, DE and PC polarity */
184 hdcmi->Instance->CR &= ~(DCMI_CR_PCKPOL | DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_EDM_0 |\
185 DCMI_CR_EDM_1 | DCMI_CR_FCRC_0 | DCMI_CR_FCRC_1 | DCMI_CR_JPEG |\
186 DCMI_CR_ESS | DCMI_CR_BSM_0 | DCMI_CR_BSM_1 | DCMI_CR_OEBS |\
187 DCMI_CR_LSM | DCMI_CR_OELS);
189 hdcmi->Instance->CR |= (uint32_t)(hdcmi->Init.SynchroMode | hdcmi->Init.CaptureRate |\
190 hdcmi->Init.VSPolarity | hdcmi->Init.HSPolarity |\
191 hdcmi->Init.PCKPolarity | hdcmi->Init.ExtendedDataMode |\
192 hdcmi->Init.JPEGMode | hdcmi->Init.ByteSelectMode |\
193 hdcmi->Init.ByteSelectStart | hdcmi->Init.LineSelectMode |\
194 hdcmi->Init.LineSelectStart);
196 if(hdcmi->Init.SynchroMode == DCMI_SYNCHRO_EMBEDDED)
198 hdcmi->Instance->ESCR = (((uint32_t)hdcmi->Init.SyncroCode.FrameStartCode) |\
199 ((uint32_t)hdcmi->Init.SyncroCode.LineStartCode << DCMI_POSITION_ESCR_LSC)|\
200 ((uint32_t)hdcmi->Init.SyncroCode.LineEndCode << DCMI_POSITION_ESCR_LEC) |\
201 ((uint32_t)hdcmi->Init.SyncroCode.FrameEndCode << DCMI_POSITION_ESCR_FEC));
205 /* Enable the Line, Vsync, Error and Overrun interrupts */
206 __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR);
208 /* Update error code */
209 hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE;
211 /* Initialize the DCMI state*/
212 hdcmi->State = HAL_DCMI_STATE_READY;
214 return HAL_OK;
218 * @brief Deinitializes the DCMI peripheral registers to their default reset
219 * values.
220 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
221 * the configuration information for DCMI.
222 * @retval HAL status
225 HAL_StatusTypeDef HAL_DCMI_DeInit(DCMI_HandleTypeDef *hdcmi)
227 /* DeInit the low level hardware */
228 HAL_DCMI_MspDeInit(hdcmi);
230 /* Update error code */
231 hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE;
233 /* Initialize the DCMI state*/
234 hdcmi->State = HAL_DCMI_STATE_RESET;
236 /* Release Lock */
237 __HAL_UNLOCK(hdcmi);
239 return HAL_OK;
243 * @brief Initializes the DCMI MSP.
244 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
245 * the configuration information for DCMI.
246 * @retval None
248 __weak void HAL_DCMI_MspInit(DCMI_HandleTypeDef* hdcmi)
250 /* Prevent unused argument(s) compilation warning */
251 UNUSED(hdcmi);
253 /* NOTE : This function Should not be modified, when the callback is needed,
254 the HAL_DCMI_MspInit could be implemented in the user file
259 * @brief DeInitializes the DCMI MSP.
260 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
261 * the configuration information for DCMI.
262 * @retval None
264 __weak void HAL_DCMI_MspDeInit(DCMI_HandleTypeDef* hdcmi)
266 /* Prevent unused argument(s) compilation warning */
267 UNUSED(hdcmi);
269 /* NOTE : This function Should not be modified, when the callback is needed,
270 the HAL_DCMI_MspDeInit could be implemented in the user file
275 * @}
277 /** @defgroup DCMI_Exported_Functions_Group2 IO operation functions
278 * @brief IO operation functions
280 @verbatim
281 ===============================================================================
282 ##### IO operation functions #####
283 ===============================================================================
284 [..] This section provides functions allowing to:
285 (+) Configure destination address and data length and
286 Enables DCMI DMA request and enables DCMI capture
287 (+) Stop the DCMI capture.
288 (+) Handles DCMI interrupt request.
290 @endverbatim
291 * @{
295 * @brief Enables DCMI DMA request and enables DCMI capture
296 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
297 * the configuration information for DCMI.
298 * @param DCMI_Mode: DCMI capture mode snapshot or continuous grab.
299 * @param pData: The destination memory Buffer address (LCD Frame buffer).
300 * @param Length: The length of capture to be transferred.
301 * @retval HAL status
303 HAL_StatusTypeDef HAL_DCMI_Start_DMA(DCMI_HandleTypeDef* hdcmi, uint32_t DCMI_Mode, uint32_t pData, uint32_t Length)
305 /* Initialize the second memory address */
306 uint32_t SecondMemAddress = 0;
308 /* Check function parameters */
309 assert_param(IS_DCMI_CAPTURE_MODE(DCMI_Mode));
311 /* Process Locked */
312 __HAL_LOCK(hdcmi);
314 /* Lock the DCMI peripheral state */
315 hdcmi->State = HAL_DCMI_STATE_BUSY;
317 /* Enable DCMI by setting DCMIEN bit */
318 __HAL_DCMI_ENABLE(hdcmi);
320 /* Configure the DCMI Mode */
321 hdcmi->Instance->CR &= ~(DCMI_CR_CM);
322 hdcmi->Instance->CR |= (uint32_t)(DCMI_Mode);
324 /* Set the DMA memory0 conversion complete callback */
325 hdcmi->DMA_Handle->XferCpltCallback = DCMI_DMAXferCplt;
327 /* Set the DMA error callback */
328 hdcmi->DMA_Handle->XferErrorCallback = DCMI_DMAError;
330 /* Set the dma abort callback */
331 hdcmi->DMA_Handle->XferAbortCallback = NULL;
333 /* Reset transfer counters value */
334 hdcmi->XferCount = 0;
335 hdcmi->XferTransferNumber = 0;
337 if(Length <= 0xFFFF)
339 /* Enable the DMA Stream */
340 HAL_DMA_Start_IT(hdcmi->DMA_Handle, (uint32_t)&hdcmi->Instance->DR, (uint32_t)pData, Length);
342 else /* DCMI_DOUBLE_BUFFER Mode */
344 /* Set the DMA memory1 conversion complete callback */
345 hdcmi->DMA_Handle->XferM1CpltCallback = DCMI_DMAXferCplt;
347 /* Initialize transfer parameters */
348 hdcmi->XferCount = 1;
349 hdcmi->XferSize = Length;
350 hdcmi->pBuffPtr = pData;
352 /* Get the number of buffer */
353 while(hdcmi->XferSize > 0xFFFF)
355 hdcmi->XferSize = (hdcmi->XferSize/2);
356 hdcmi->XferCount = hdcmi->XferCount*2;
359 /* Update DCMI counter and transfer number*/
360 hdcmi->XferCount = (hdcmi->XferCount - 2);
361 hdcmi->XferTransferNumber = hdcmi->XferCount;
363 /* Update second memory address */
364 SecondMemAddress = (uint32_t)(pData + (4*hdcmi->XferSize));
366 /* Start DMA multi buffer transfer */
367 HAL_DMAEx_MultiBufferStart_IT(hdcmi->DMA_Handle, (uint32_t)&hdcmi->Instance->DR, (uint32_t)pData, SecondMemAddress, hdcmi->XferSize);
370 /* Enable Capture */
371 hdcmi->Instance->CR |= DCMI_CR_CAPTURE;
373 /* Release Lock */
374 __HAL_UNLOCK(hdcmi);
376 /* Return function status */
377 return HAL_OK;
381 * @brief Disable DCMI DMA request and Disable DCMI capture
382 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
383 * the configuration information for DCMI.
384 * @retval HAL status
386 HAL_StatusTypeDef HAL_DCMI_Stop(DCMI_HandleTypeDef* hdcmi)
388 register uint32_t count = HAL_TIMEOUT_DCMI_STOP * (SystemCoreClock /8/1000);
389 HAL_StatusTypeDef status = HAL_OK;
391 /* Process locked */
392 __HAL_LOCK(hdcmi);
394 /* Lock the DCMI peripheral state */
395 hdcmi->State = HAL_DCMI_STATE_BUSY;
397 /* Disable Capture */
398 hdcmi->Instance->CR &= ~(DCMI_CR_CAPTURE);
400 /* Check if the DCMI capture effectively disabled */
403 if (count-- == 0)
405 /* Update error code */
406 hdcmi->ErrorCode |= HAL_DCMI_ERROR_TIMEOUT;
408 status = HAL_TIMEOUT;
409 break;
412 while((hdcmi->Instance->CR & DCMI_CR_CAPTURE) != 0);
414 /* Disable the DCMI */
415 __HAL_DCMI_DISABLE(hdcmi);
417 /* Disable the DMA */
418 HAL_DMA_Abort(hdcmi->DMA_Handle);
420 /* Update error code */
421 hdcmi->ErrorCode |= HAL_DCMI_ERROR_NONE;
423 /* Change DCMI state */
424 hdcmi->State = HAL_DCMI_STATE_READY;
426 /* Process Unlocked */
427 __HAL_UNLOCK(hdcmi);
429 /* Return function status */
430 return status;
434 * @brief Suspend DCMI capture
435 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
436 * the configuration information for DCMI.
437 * @retval HAL status
439 HAL_StatusTypeDef HAL_DCMI_Suspend(DCMI_HandleTypeDef* hdcmi)
441 register uint32_t count = HAL_TIMEOUT_DCMI_STOP * (SystemCoreClock /8/1000);
442 HAL_StatusTypeDef status = HAL_OK;
444 /* Process locked */
445 __HAL_LOCK(hdcmi);
447 if(hdcmi->State == HAL_DCMI_STATE_BUSY)
449 /* Change DCMI state */
450 hdcmi->State = HAL_DCMI_STATE_SUSPENDED;
452 /* Disable Capture */
453 hdcmi->Instance->CR &= ~(DCMI_CR_CAPTURE);
455 /* Check if the DCMI capture effectively disabled */
458 if (count-- == 0)
460 /* Update error code */
461 hdcmi->ErrorCode |= HAL_DCMI_ERROR_TIMEOUT;
463 /* Change DCMI state */
464 hdcmi->State = HAL_DCMI_STATE_READY;
466 status = HAL_TIMEOUT;
467 break;
470 while((hdcmi->Instance->CR & DCMI_CR_CAPTURE) != 0);
472 /* Process Unlocked */
473 __HAL_UNLOCK(hdcmi);
475 /* Return function status */
476 return status;
480 * @brief Resume DCMI capture
481 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
482 * the configuration information for DCMI.
483 * @retval HAL status
485 HAL_StatusTypeDef HAL_DCMI_Resume(DCMI_HandleTypeDef* hdcmi)
487 /* Process locked */
488 __HAL_LOCK(hdcmi);
490 if(hdcmi->State == HAL_DCMI_STATE_SUSPENDED)
492 /* Change DCMI state */
493 hdcmi->State = HAL_DCMI_STATE_BUSY;
495 /* Disable Capture */
496 hdcmi->Instance->CR |= DCMI_CR_CAPTURE;
498 /* Process Unlocked */
499 __HAL_UNLOCK(hdcmi);
501 /* Return function status */
502 return HAL_OK;
506 * @brief Handles DCMI interrupt request.
507 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
508 * the configuration information for the DCMI.
509 * @retval None
511 void HAL_DCMI_IRQHandler(DCMI_HandleTypeDef *hdcmi)
513 uint32_t isr_value = READ_REG(hdcmi->Instance->MISR);
515 /* Synchronization error interrupt management *******************************/
516 if((isr_value & DCMI_FLAG_ERRRI) == DCMI_FLAG_ERRRI)
518 /* Clear the Synchronization error flag */
519 __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_ERRRI);
521 /* Update error code */
522 hdcmi->ErrorCode |= HAL_DCMI_ERROR_SYNC;
524 /* Change DCMI state */
525 hdcmi->State = HAL_DCMI_STATE_ERROR;
527 /* Set the synchronization error callback */
528 hdcmi->DMA_Handle->XferAbortCallback = DCMI_DMAError;
530 /* Abort the DMA Transfer */
531 HAL_DMA_Abort_IT(hdcmi->DMA_Handle);
533 /* Overflow interrupt management ********************************************/
534 if((isr_value & DCMI_FLAG_OVRRI) == DCMI_FLAG_OVRRI)
536 /* Clear the Overflow flag */
537 __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_OVRRI);
539 /* Update error code */
540 hdcmi->ErrorCode |= HAL_DCMI_ERROR_OVR;
542 /* Change DCMI state */
543 hdcmi->State = HAL_DCMI_STATE_ERROR;
545 /* Set the overflow callback */
546 hdcmi->DMA_Handle->XferAbortCallback = DCMI_DMAError;
548 /* Abort the DMA Transfer */
549 HAL_DMA_Abort_IT(hdcmi->DMA_Handle);
551 /* Line Interrupt management ************************************************/
552 if((isr_value & DCMI_FLAG_LINERI) == DCMI_FLAG_LINERI)
554 /* Clear the Line interrupt flag */
555 __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_LINERI);
557 /* Line interrupt Callback */
558 HAL_DCMI_LineEventCallback(hdcmi);
560 /* VSYNC interrupt management ***********************************************/
561 if((isr_value & DCMI_FLAG_VSYNCRI) == DCMI_FLAG_VSYNCRI)
563 /* Clear the VSYNC flag */
564 __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_VSYNCRI);
566 /* VSYNC Callback */
567 HAL_DCMI_VsyncEventCallback(hdcmi);
569 /* FRAME interrupt management ***********************************************/
570 if((isr_value & DCMI_FLAG_FRAMERI) == DCMI_FLAG_FRAMERI)
572 /* When snapshot mode, disable Vsync, Error and Overrun interrupts */
573 if((hdcmi->Instance->CR & DCMI_CR_CM) == DCMI_MODE_SNAPSHOT)
575 /* Disable the Line, Vsync, Error and Overrun interrupts */
576 __HAL_DCMI_DISABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR);
579 /* Disable the Frame interrupt */
580 __HAL_DCMI_DISABLE_IT(hdcmi, DCMI_IT_FRAME);
582 /* Clear the End of Frame flag */
583 __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_FRAMERI);
585 /* Frame Callback */
586 HAL_DCMI_FrameEventCallback(hdcmi);
591 * @brief Error DCMI callback.
592 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
593 * the configuration information for DCMI.
594 * @retval None
596 __weak void HAL_DCMI_ErrorCallback(DCMI_HandleTypeDef *hdcmi)
598 /* Prevent unused argument(s) compilation warning */
599 UNUSED(hdcmi);
601 /* NOTE : This function Should not be modified, when the callback is needed,
602 the HAL_DCMI_ErrorCallback could be implemented in the user file
607 * @brief Line Event callback.
608 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
609 * the configuration information for DCMI.
610 * @retval None
612 __weak void HAL_DCMI_LineEventCallback(DCMI_HandleTypeDef *hdcmi)
614 /* NOTE : This function Should not be modified, when the callback is needed,
615 the HAL_DCMI_LineEventCallback could be implemented in the user file
620 * @brief VSYNC Event callback.
621 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
622 * the configuration information for DCMI.
623 * @retval None
625 __weak void HAL_DCMI_VsyncEventCallback(DCMI_HandleTypeDef *hdcmi)
627 /* Prevent unused argument(s) compilation warning */
628 UNUSED(hdcmi);
630 /* NOTE : This function Should not be modified, when the callback is needed,
631 the HAL_DCMI_VsyncEventCallback could be implemented in the user file
636 * @brief Frame Event callback.
637 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
638 * the configuration information for DCMI.
639 * @retval None
641 __weak void HAL_DCMI_FrameEventCallback(DCMI_HandleTypeDef *hdcmi)
643 /* Prevent unused argument(s) compilation warning */
644 UNUSED(hdcmi);
646 /* NOTE : This function Should not be modified, when the callback is needed,
647 the HAL_DCMI_FrameEventCallback could be implemented in the user file
652 * @}
655 /** @defgroup DCMI_Exported_Functions_Group3 Peripheral Control functions
656 * @brief Peripheral Control functions
658 @verbatim
659 ===============================================================================
660 ##### Peripheral Control functions #####
661 ===============================================================================
662 [..] This section provides functions allowing to:
663 (+) Configure the CROP feature.
664 (+) Enable/Disable the CROP feature.
665 (+) Set embedded synchronization delimiters unmasks.
667 @endverbatim
668 * @{
672 * @brief Configure the DCMI CROP coordinate.
673 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
674 * the configuration information for DCMI.
675 * @param YSize: DCMI Line number
676 * @param XSize: DCMI Pixel per line
677 * @param X0: DCMI window X offset
678 * @param Y0: DCMI window Y offset
679 * @retval HAL status
681 HAL_StatusTypeDef HAL_DCMI_ConfigCrop(DCMI_HandleTypeDef *hdcmi, uint32_t X0, uint32_t Y0, uint32_t XSize, uint32_t YSize)
683 /* Process Locked */
684 __HAL_LOCK(hdcmi);
686 /* Lock the DCMI peripheral state */
687 hdcmi->State = HAL_DCMI_STATE_BUSY;
689 /* Check the parameters */
690 assert_param(IS_DCMI_WINDOW_COORDINATE(X0));
691 assert_param(IS_DCMI_WINDOW_HEIGHT(Y0));
692 assert_param(IS_DCMI_WINDOW_COORDINATE(XSize));
693 assert_param(IS_DCMI_WINDOW_COORDINATE(YSize));
695 /* Configure CROP */
696 hdcmi->Instance->CWSIZER = (XSize | (YSize << DCMI_POSITION_CWSIZE_VLINE));
697 hdcmi->Instance->CWSTRTR = (X0 | (Y0 << DCMI_POSITION_CWSTRT_VST));
699 /* Initialize the DCMI state*/
700 hdcmi->State = HAL_DCMI_STATE_READY;
702 /* Process Unlocked */
703 __HAL_UNLOCK(hdcmi);
705 return HAL_OK;
709 * @brief Disable the Crop feature.
710 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
711 * the configuration information for DCMI.
712 * @retval HAL status
714 HAL_StatusTypeDef HAL_DCMI_DisableCrop(DCMI_HandleTypeDef *hdcmi)
716 /* Process Locked */
717 __HAL_LOCK(hdcmi);
719 /* Lock the DCMI peripheral state */
720 hdcmi->State = HAL_DCMI_STATE_BUSY;
722 /* Disable DCMI Crop feature */
723 hdcmi->Instance->CR &= ~(uint32_t)DCMI_CR_CROP;
725 /* Change the DCMI state*/
726 hdcmi->State = HAL_DCMI_STATE_READY;
728 /* Process Unlocked */
729 __HAL_UNLOCK(hdcmi);
731 return HAL_OK;
735 * @brief Enable the Crop feature.
736 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
737 * the configuration information for DCMI.
738 * @retval HAL status
740 HAL_StatusTypeDef HAL_DCMI_EnableCrop(DCMI_HandleTypeDef *hdcmi)
742 /* Process Locked */
743 __HAL_LOCK(hdcmi);
745 /* Lock the DCMI peripheral state */
746 hdcmi->State = HAL_DCMI_STATE_BUSY;
748 /* Enable DCMI Crop feature */
749 hdcmi->Instance->CR |= (uint32_t)DCMI_CR_CROP;
751 /* Change the DCMI state*/
752 hdcmi->State = HAL_DCMI_STATE_READY;
754 /* Process Unlocked */
755 __HAL_UNLOCK(hdcmi);
757 return HAL_OK;
761 * @}
764 /** @defgroup DCMI_Exported_Functions_Group4 Peripheral State functions
765 * @brief Peripheral State functions
767 @verbatim
768 ===============================================================================
769 ##### Peripheral State and Errors functions #####
770 ===============================================================================
771 [..]
772 This subsection provides functions allowing to
773 (+) Check the DCMI state.
774 (+) Get the specific DCMI error flag.
776 @endverbatim
777 * @{
781 * @brief Return the DCMI state
782 * @param hdcmi: pointer to a DCMI_HandleTypeDef structure that contains
783 * the configuration information for DCMI.
784 * @retval HAL state
786 HAL_DCMI_StateTypeDef HAL_DCMI_GetState(DCMI_HandleTypeDef *hdcmi)
788 return hdcmi->State;
792 * @brief Return the DCMI error code
793 * @param hdcmi : pointer to a DCMI_HandleTypeDef structure that contains
794 * the configuration information for DCMI.
795 * @retval DCMI Error Code
797 uint32_t HAL_DCMI_GetError(DCMI_HandleTypeDef *hdcmi)
799 return hdcmi->ErrorCode;
803 * @}
805 /* Private functions ---------------------------------------------------------*/
806 /** @defgroup DCMI_Private_Functions DCMI Private Functions
807 * @{
810 * @brief DMA conversion complete callback.
811 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
812 * the configuration information for the specified DMA module.
813 * @retval None
815 static void DCMI_DMAXferCplt(DMA_HandleTypeDef *hdma)
817 uint32_t tmp = 0;
819 DCMI_HandleTypeDef* hdcmi = ( DCMI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
821 if(hdcmi->XferCount != 0)
823 /* Update memory 0 address location */
824 tmp = ((hdcmi->DMA_Handle->Instance->CR) & DMA_SxCR_CT);
825 if(((hdcmi->XferCount % 2) == 0) && (tmp != 0))
827 tmp = hdcmi->DMA_Handle->Instance->M0AR;
828 HAL_DMAEx_ChangeMemory(hdcmi->DMA_Handle, (tmp + (8*hdcmi->XferSize)), MEMORY0);
829 hdcmi->XferCount--;
831 /* Update memory 1 address location */
832 else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) == 0)
834 tmp = hdcmi->DMA_Handle->Instance->M1AR;
835 HAL_DMAEx_ChangeMemory(hdcmi->DMA_Handle, (tmp + (8*hdcmi->XferSize)), MEMORY1);
836 hdcmi->XferCount--;
839 /* Update memory 0 address location */
840 else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) != 0)
842 hdcmi->DMA_Handle->Instance->M0AR = hdcmi->pBuffPtr;
844 /* Update memory 1 address location */
845 else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) == 0)
847 tmp = hdcmi->pBuffPtr;
848 hdcmi->DMA_Handle->Instance->M1AR = (tmp + (4*hdcmi->XferSize));
849 hdcmi->XferCount = hdcmi->XferTransferNumber;
852 /* Check if the frame is transferred */
853 if(hdcmi->XferCount == hdcmi->XferTransferNumber)
855 /* Enable the Frame interrupt */
856 __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_FRAME);
858 /* When snapshot mode, set dcmi state to ready */
859 if((hdcmi->Instance->CR & DCMI_CR_CM) == DCMI_MODE_SNAPSHOT)
861 hdcmi->State= HAL_DCMI_STATE_READY;
867 * @brief DMA error callback
868 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
869 * the configuration information for the specified DMA module.
870 * @retval None
872 static void DCMI_DMAError(DMA_HandleTypeDef *hdma)
874 DCMI_HandleTypeDef* hdcmi = ( DCMI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
876 if(hdcmi->DMA_Handle->ErrorCode != HAL_DMA_ERROR_FE)
878 /* Initialize the DCMI state*/
879 hdcmi->State = HAL_DCMI_STATE_READY;
881 /* Set DCMI Error Code */
882 hdcmi->ErrorCode |= HAL_DCMI_ERROR_DMA;
885 /* DCMI error Callback */
886 HAL_DCMI_ErrorCallback(hdcmi);
890 * @}
894 * @}
896 #endif /* DCMI */
897 #endif /* HAL_DCMI_MODULE_ENABLED */
899 * @}
903 * @}
906 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/