summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/include/stm32/dma2d.h415
-rw-r--r--nuttx/arch/arm/include/stm32/ltdc.h97
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig11
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_dma2d.h231
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_ccm.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dma2d.c2208
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dma2d.h87
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_ltdc.c841
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_ltdc.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c6
10 files changed, 3482 insertions, 418 deletions
diff --git a/nuttx/arch/arm/include/stm32/dma2d.h b/nuttx/arch/arm/include/stm32/dma2d.h
new file mode 100644
index 000000000..70fc71c7c
--- /dev/null
+++ b/nuttx/arch/arm/include/stm32/dma2d.h
@@ -0,0 +1,415 @@
+/*******************************************************************************
+ * arch/arm/src/include/stm32/dma2d.h
+ *
+ * Copyright (C) 2015 Marco Krahl. All rights reserved.
+ * Author: Marco Krahl <ocram.lhark@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************/
+
+#ifndef __ARCH_ARM_INCLUDE_STM32_DMA2D_H
+#define __ARCH_ARM_INCLUDE_STM32_DMA2D_H
+
+/*******************************************************************************
+ * Included Files
+ ******************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdbool.h>
+#include <nuttx/video/fb.h>
+
+/*******************************************************************************
+ * Pre-processor Definitions
+ ******************************************************************************/
+
+/*******************************************************************************
+ * Public Types
+ ******************************************************************************/
+
+struct ltdc_area_s; /* see arch/chip/ltdc.h */
+
+/* Blend mode definitions */
+
+enum dma2d_blend_e
+{
+ DMA2D_BLEND_NONE = 0, /* Disable all blend operation */
+ DMA2D_BLEND_ALPHA = 0x1, /* Enable alpha blending */
+ DMA2D_BLEND_PIXELALPHA = 0x2, /* Enable alpha blending from pixel color */
+};
+
+/* The layer is controlled through the following structure */
+
+struct dma2d_layer_s
+{
+ /* Name: getvideoinfo
+ *
+ * Description:
+ * Get video information about the layer
+ *
+ * Parameter:
+ * layer - Reference to the layer control structure
+ * vinfo - Reference to the video info structure
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*getvideoinfo)(FAR struct dma2d_layer_s *layer,
+ FAR struct fb_videoinfo_s *vinfo);
+
+ /* Name: getplaneinfo
+ *
+ * Description:
+ * Get plane information about the layer
+ *
+ * Parameter:
+ * layer - Reference to the layer control structure
+ * planeno - Number of the plane
+ * pinfo - Reference to the plane info structure
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*getplaneinfo)(FAR struct dma2d_layer_s *layer, int planeno,
+ FAR struct fb_planeinfo_s *pinfo);
+
+ /* Name: getlid
+ *
+ * Description:
+ * Get a specific layer identifier.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * lid - Reference to store the layer id
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*getlid)(FAR struct dma2d_layer_s *layer, int *lid);
+
+#ifdef CONFIG_STM32_DMA2D_L8
+ /* Name: setclut
+ *
+ * Description:
+ * Configure layer clut (color lookup table).
+ * Non clut is defined during initializing.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * cmap - color lookup table with up the 256 entries
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*setclut)(FAR struct dma2d_layer_s *layer,
+ const FAR struct fb_cmap_s *cmap);
+
+ /* Name: getclut
+ *
+ * Description:
+ * Get configured layer clut (color lookup table).
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * cmap - Reference to valid color lookup table accept up the 256 color
+ * entries
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*getclut)(FAR struct dma2d_layer_s *layer, FAR struct fb_cmap_s *cmap);
+#endif
+
+ /* Name: setalpha
+ *
+ * Description:
+ * Configure layer alpha value factor into blend operation.
+ * During the layer blend operation the source alpha value is multiplied
+ * with this alpha value. If the source color format doesn't support alpha
+ * channel (e.g. non ARGB8888) this alpha value will be used as constant
+ * alpha value for blend operation.
+ * Default value during initializing: 0xff
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * alpha - Alpha value
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*setalpha)(FAR struct dma2d_layer_s *layer, uint8_t alpha);
+
+ /* Name: getalpha
+ *
+ * Description:
+ * Get configured layer alpha value factor for blend operation.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * alpha - Reference to store the alpha value
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*getalpha)(FAR struct dma2d_layer_s *layer, uint8_t *alpha);
+
+ /* Name: setblendmode
+ *
+ * Description:
+ * Configure blend mode of the layer.
+ * Default mode during initializing: DMA2D_BLEND_NONE
+ * Blendmode is active after next update.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * mode - Blend mode (see DMA2D_BLEND_*)
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ * Procedure information:
+ * DMA2D_BLEND_NONE:
+ * Informs the driver to disable all blend operation for the given layer.
+ * That means the layer is opaque.
+ *
+ * DMA2D_BLEND_ALPHA:
+ * Informs the driver to enable alpha blending for the given layer.
+ *
+ * DMA2D_BLEND_PIXELALPHA:
+ * Informs the driver to use the pixel alpha value of the layer instead
+ * the constant alpha value. This is only useful for ARGB8888
+ * color format.
+ */
+
+ int (*setblendmode)(FAR struct dma2d_layer_s *layer, uint32_t mode);
+
+ /* Name: getblendmode
+ *
+ * Description:
+ * Get configured blend mode of the layer.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * mode - Reference to store the blend mode
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ */
+
+ int (*getblendmode)(FAR struct dma2d_layer_s *layer, uint32_t *mode);
+
+ /* Name: blit
+ *
+ * Description:
+ * Copy selected area from a source layer to selected position of the
+ * destination layer.
+ *
+ * Parameter:
+ * dest - Reference to the destination layer
+ * destxpos - Selected x target position of the destination layer
+ * destypos - Selected y target position of the destination layer
+ * src - Reference to the source layer
+ * srcarea - Reference to the selected area of the source layer
+ *
+ * Return:
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the
+ * selected source area outside the visible area of the
+ * destination layer. (The visible area usually represents the
+ * display size)
+ * -ECANCELED - Operation cancelled, something goes wrong.
+ */
+
+ int (*blit)(FAR struct dma2d_layer_s *dest,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *src,
+ FAR const struct ltdc_area_s *srcarea);
+
+ /* Name: blend
+ *
+ * Description:
+ * Blends the selected area from a background layer with selected position
+ * of the foreground layer. Copies the result to the selected position of
+ * the destination layer. Note! The content of the foreground and background
+ * layer keeps unchanged as long destination layer is unequal to the
+ * foreground and background layer.
+ *
+ * Parameter:
+ * dest - Reference to the destination layer
+ * fore - Reference to the foreground layer
+ * forexpos - Selected x target position of the foreground layer
+ * foreypos - Selected y target position of the foreground layer
+ * back - Reference to the background layer
+ * backarea - Reference to the selected area of the background layer
+ *
+ * Return:
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the
+ * selected source area outside the visible area of the
+ * destination layer. (The visible area usually represents the
+ * display size)
+ * -ECANCELED - Operation cancelled, something goes wrong.
+ */
+
+ int (*blend)(FAR struct dma2d_layer_s *dest,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *fore,
+ fb_coord_t forexpos, fb_coord_t foreypos,
+ FAR const struct dma2d_layer_s *back,
+ FAR const struct ltdc_area_s *backarea);
+
+ /* Name: fillarea
+ *
+ * Description:
+ * Fill the selected area of the whole layer with a specific color.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * area - Reference to the valid area structure select the area
+ * color - Color to fill the selected area. Color must be formatted
+ * according to the layer pixel format.
+ *
+ * Return:
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the
+ * selected area outside the visible area of the layer.
+ * -ECANCELED - Operation cancelled, something goes wrong.
+ */
+
+ int (*fillarea)(FAR struct dma2d_layer_s *layer,
+ FAR const struct ltdc_area_s *area,
+ uint32_t color);
+};
+
+/*******************************************************************************
+ * Public Data
+ ******************************************************************************/
+
+/*******************************************************************************
+ * Public Functions
+ ******************************************************************************/
+
+/*******************************************************************************
+ * Name: up_dma2dgetlayer
+ *
+ * Description:
+ * Get a dma2d layer structure by the layer identifier
+ *
+ * Parameter:
+ * lid - Layer identifier
+ *
+ * Return:
+ * Reference to the dma2d layer control structure on success or Null if no
+ * related exist.
+ *
+ ******************************************************************************/
+
+FAR struct dma2d_layer_s * up_dma2dgetlayer(int lid);
+
+/******************************************************************************
+ * Name: up_dma2dcreatelayer
+ *
+ * Description:
+ * Create a new dma2d layer object to interact with the dma2d controller
+ *
+ * Parameter:
+ * width - Layer width
+ * height - Layer height
+ * fmt - Pixel format of the layer
+ *
+ * Return:
+ * On success - A valid dma2d layer reference
+ * On error - NULL and errno is set to
+ * -EINVAL if one of the parameter is invalid
+ * -ENOMEM if no memory available or exceeds
+ * CONFIG_STM32_DMA2D_NLAYERS
+ *
+ ******************************************************************************/
+
+FAR struct dma2d_layer_s *up_dma2dcreatelayer(fb_coord_t width,
+ fb_coord_t height,
+ uint8_t fmt);
+
+/******************************************************************************
+ * Name: up_dma2dremovelayer
+ *
+ * Description:
+ * Remove and deallocate the dma2d layer
+ *
+ * Parameter:
+ * layer - Reference to the layer to remove
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ *****************************************************************************/
+
+int up_dma2dremovelayer(FAR struct dma2d_layer_s *layer);
+
+/******************************************************************************
+ * Name: up_dma2dinitialize
+ *
+ * Description:
+ * Initialize the dma2d controller
+ *
+ * Return:
+ * OK - On success
+ * An error if initializing failed.
+ *
+ ******************************************************************************/
+
+int up_dma2dinitialize(void);
+
+/******************************************************************************
+ * Name: up_dma2duninitialize
+ *
+ * Description:
+ * Uninitialize the dma2d controller
+ *
+ ******************************************************************************/
+
+void up_dma2duninitialize(void);
+
+#endif /* __ARCH_ARM_INCLUDE_STM32_DMA2D_H */
diff --git a/nuttx/arch/arm/include/stm32/ltdc.h b/nuttx/arch/arm/include/stm32/ltdc.h
index 24f2632e1..bd57f45b7 100644
--- a/nuttx/arch/arm/include/stm32/ltdc.h
+++ b/nuttx/arch/arm/include/stm32/ltdc.h
@@ -1,7 +1,7 @@
/*******************************************************************************
* arch/arm/src/include/stm32/ltdc.h
*
- * Copyright (C) 2014 Marco Krahl. All rights reserved.
+ * Copyright (C) 2014-2015 Marco Krahl. All rights reserved.
* Author: Marco Krahl <ocram.lhark@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
@@ -53,15 +53,18 @@
* Public Types
******************************************************************************/
+struct dma2d_layer_s; /* see arch/chip/dma2d.h */
+
/* Blend mode definitions */
enum ltdc_blend_e
{
LTDC_BLEND_NONE = 0, /* Disable all blend operation */
LTDC_BLEND_ALPHA = 0x1, /* Enable alpha blending */
- LTDC_BLEND_COLORKEY = 0x2, /* Enable colorkey */
- LTDC_BLEND_SRCPIXELALPHA = 0x4, /* Use pixel alpha of source */
- LTDC_BLEND_DESTPIXELALPHA = 0x8 /* Use pixel alpha of destination */
+ LTDC_BLEND_PIXELALPHA = 0x2, /* Enable alpha blending from pixel color */
+ LTDC_BLEND_COLORKEY = 0x4, /* Enable colorkey */
+ LTDC_BLEND_ALPHAINV = 0x8, /* Inverse alpha blending of source */
+ LTDC_BLEND_PIXELALPHAINV = 0x10 /* Invers pixel alpha blending of source */
};
/* layer control definitions */
@@ -73,6 +76,9 @@ enum ltdc_layer_e
LTDC_LAYER_BOTTOM = 0x2, /* the initialized bottom layer */
LTDC_LAYER_ACTIVE = 0x4, /* The current visible flip layer */
LTDC_LAYER_INACTIVE = 0x8 /* The current invisible flip layer */
+#ifdef CONFIG_STM32_DMA2D
+ ,LTDC_LAYER_DMA2D = 0x10 /* The dma2d interface layer id */
+#endif
};
/* Update operation flag */
@@ -447,8 +453,9 @@ struct ltdc_layer_s
* mode - operation mode (see LTDC_UPDATE_*)
*
* Return:
- * OK - On success
- * -EINVAL - If one of the parameter invalid
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid
+ * -ECANCELED - Operation cancelled, something goes wrong
*
* Procedure information:
* LTDC_UPDATE_SIM:
@@ -480,59 +487,81 @@ struct ltdc_layer_s
* Name: blit
*
* Description:
- * Copy selected area from a background layer to selected position of the
- * foreground layer. Copies the result to the destination layer.
+ * Copy selected area from a source layer to selected position of the
+ * destination layer.
*
* Parameter:
* dest - Reference to the destination layer
- * fore - Reference to the foreground layer
- * forexpos - Selected x target position of the destination layer
- * foreypos - Selected y target position of the destination layer
- * back - Reference to the background layer
- * backarea - Reference to the selected area of the background layer
+ * destxpos - Selected x position of the destination layer
+ * destypos - Selected y position of the destination layer
+ * src - Reference to the source layer
+ * srcarea - Reference to the selected area of the source layer
*
* Return:
- * OK - On success
- * -EINVAL - If one of the parameter invalid or if the size of the selected
- * source area outside the visible area of the destination layer.
- * (The visible area usually represents the display size)
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * source area outside the visible area of the destination layer.
+ * (The visible area usually represents the display size)
*
*/
int (*blit)(FAR struct ltdc_layer_s *dest,
- FAR struct ltdc_layer_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct ltdc_layer_s *back,
- FAR const struct ltdc_area_s *backarea);
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *src,
+ FAR const struct ltdc_area_s *srcarea);
/*
*
* Name: blend
*
* Description:
- * Blend the selected area from a background layer with selected position of
- * the foreground layer. Blends the result with the destination layer.
- * Note! This is the same as the blit operation but with blending depending
- * on the blendmode settings of the layer.
+ * Blends the selected area from a foreground layer with selected position
+ * of the background layer. Copy the result to the destination layer. Note!
+ * The content of the foreground and background layer is not changed.
*
* Parameter:
* dest - Reference to the destination layer
+ * destxpos - Selected x position of the destination layer
+ * destypos - Selected y position of the destination layer
* fore - Reference to the foreground layer
- * forexpos - Selected x target position of the destination layer
- * foreypos - Selected y target position of the destination layer
+ * forexpos - Selected x position of the foreground layer
+ * foreypos - Selected y position of the foreground layer
* back - Reference to the background layer
* backarea - Reference to the selected area of the background layer
*
* Return:
- * OK - On success
- * -EINVAL - If one of the parameter invalid or if the size of the selected
- * source area outside the visible area of the destination layer.
- * (The visible area usually represents the display size)
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * source area outside the visible area of the destination layer.
+ * (The visible area usually represents the display size)
*
*/
int (*blend)(FAR struct ltdc_layer_s *dest,
- FAR struct ltdc_layer_s *fore,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *fore,
fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct ltdc_layer_s *back,
- FAR const struct ltdc_area_s *backarea)
+ FAR const struct dma2d_layer_s *back,
+ FAR const struct ltdc_area_s *backarea);
+
+ /*
+ * Name: fillarea
+ *
+ * Description:
+ * Fill the selected area of the whole layer with a specific color.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * area - Reference to the valid area structure select the area
+ * color - Color to fill the selected area. Color must be formatted
+ * according to the layer pixel format.
+ *
+ * Return:
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * area outside the visible area of the layer.
+ *
+ */
+ int (*fillarea)(FAR struct ltdc_layer_s *layer,
+ FAR const struct ltdc_area_s *area,
+ uint32_t color);
#endif
};
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 38be09791..030c80582 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -3944,7 +3944,13 @@ config FB_CMAP
bool "Enable color map support"
default y
---help---
- Enabling color map suport is neccessary for ltdc L8 format.
+ Enabling color map support is neccessary for ltdc L8 format.
+
+config FB_TRANSPARENCY
+ bool "Enable transparency color map support"
+ default y
+ ---help---
+ Enabling transparency color map support is neccessary for ltdc L8 format.
endif
endmenu
@@ -3964,14 +3970,17 @@ config STM32_DMA2D_NLAYERS
menu "Supported pixel format"
config STM32_DMA2D_L8
+ depends on FB_CMAP
bool "8 bpp L8 (8-bit CLUT)"
default y
config STM32_DMA2D_AL44
+ depends on FB_CMAP
bool "8 bpp AL44 (4-bit alpha + 4-bit CLUT)"
default n
config STM32_DMA2D_AL88
+ depends on FB_CMAP
bool "16 bpp AL88 (8-bit alpha + 8-bit CLUT)"
default n
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_dma2d.h b/nuttx/arch/arm/src/stm32/chip/stm32_dma2d.h
new file mode 100644
index 000000000..7d15605b7
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_dma2d.h
@@ -0,0 +1,231 @@
+/******************************************************************************
+ * arch/arm/src/stm32/chip/stm32_dma2d.h
+ *
+ * Copyright (C) 2014-2015 Marco Krahl. All rights reserved.
+ * Author: Marco Krahl <ocram.lhark@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ *****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_CHIP_STM32_DMA2D_H
+#define __ARCH_ARM_SRC_STM32_CHIP_STM32_DMA2D_H
+
+/*****************************************************************************
+ * Included Files
+ *****************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/stm32_memorymap.h"
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+#define STM32_DMA2D_NCLUT 256 /* Number of entries in the CLUT */
+
+/* DMA2D Register Offsets ****************************************************/
+
+#define STM32_DMA2D_CR_OFFSET 0x0000 /* DMA2D Control Register */
+#define STM32_DMA2D_ISR_OFFSET 0x0004 /* DMA2D Interrupt Status Register */
+#define STM32_DMA2D_IFCR_OFFSET 0x0008 /* DMA2D Interrupt Flag Clear Register */
+#define STM32_DMA2D_FGMAR_OFFSET 0x000C /* DMA2D Foreground Memory Address Register */
+#define STM32_DMA2D_FGOR_OFFSET 0x0010 /* DMA2D Foreground Offset Register */
+#define STM32_DMA2D_BGMAR_OFFSET 0x0014 /* DMA2D Background Memory Address Register */
+#define STM32_DMA2D_BGOR_OFFSET 0x0018 /* DMA2D Background Offset Register */
+#define STM32_DMA2D_FGPFCCR_OFFSET 0x001C /* DMA2D Foreground PFC Control Register */
+#define STM32_DMA2D_FGCOLR_OFFSET 0x0020 /* DMA2D Foreground Color Register */
+#define STM32_DMA2D_BGPFCCR_OFFSET 0x0024 /* DMA2D Background PFC Control Register */
+#define STM32_DMA2D_BGCOLR_OFFSET 0x0028 /* DMA2D Background Color Register */
+#define STM32_DMA2D_FGCMAR_OFFSET 0x002C /* DMA2D Foreground CLUT Memory Address Register */
+#define STM32_DMA2D_BGCMAR_OFFSET 0x0030 /* DMA2D Background CLUT Memory Address Register */
+#define STM32_DMA2D_OPFCCR_OFFSET 0x0034 /* DMA2D Output PFC Control Register */
+#define STM32_DMA2D_OCOLR_OFFSET 0x0038 /* DMA2D Output Color Register */
+#define STM32_DMA2D_OMAR_OFFSET 0x003C /* DMA2D Output Memory Address Register */
+#define STM32_DMA2D_OOR_OFFSET 0x0040 /* DMA2D Output Offset Register */
+#define STM32_DMA2D_NLR_OFFSET 0x0044 /* DMA2D Number Of Line Register */
+#define STM32_DMA2D_LWR_OFFSET 0x0048 /* DMA2D Line Watermark Register */
+#define STM32_DMA2D_AMTCR_OFFSET 0x004C /* DMA2D AHB Master Time Configuration Register */
+
+/* DMA2D Register Addresses **************************************************/
+
+#define STM32_DMA2D_CR (STM32_DMA2D_BASE+STM32_DMA2D_CR_OFFSET)
+#define STM32_DMA2D_ISR (STM32_DMA2D_BASE+STM32_DMA2D_ISR_OFFSET)
+#define STM32_DMA2D_IFCR (STM32_DMA2D_BASE+STM32_DMA2D_IFCR_OFFSET)
+#define STM32_DMA2D_FGMAR (STM32_DMA2D_BASE+STM32_DMA2D_FGMAR_OFFSET)
+#define STM32_DMA2D_FGOR (STM32_DMA2D_BASE+STM32_DMA2D_FGOR_OFFSET)
+#define STM32_DMA2D_BGMAR (STM32_DMA2D_BASE+STM32_DMA2D_BGMAR_OFFSET)
+#define STM32_DMA2D_BGOR (STM32_DMA2D_BASE+STM32_DMA2D_BGOR_OFFSET)
+#define STM32_DMA2D_FGPFCCR (STM32_DMA2D_BASE+STM32_DMA2D_FGPFCCR_OFFSET)
+#define STM32_DMA2D_FGCOLR (STM32_DMA2D_BASE+STM32_DMA2D_FGCOLR_OFFSET)
+#define STM32_DMA2D_BGPFCCR (STM32_DMA2D_BASE+STM32_DMA2D_BGPFCCR_OFFSET)
+#define STM32_DMA2D_BGCOLR (STM32_DMA2D_BASE+STM32_DMA2D_BGCOLR_OFFSET)
+#define STM32_DMA2D_FGCMAR (STM32_DMA2D_BASE+STM32_DMA2D_FGCMAR_OFFSET)
+#define STM32_DMA2D_BGCMAR (STM32_DMA2D_BASE+STM32_DMA2D_BGCMAR_OFFSET)
+#define STM32_DMA2D_OPFCCR (STM32_DMA2D_BASE+STM32_DMA2D_OPFCCR_OFFSET)
+#define STM32_DMA2D_OCOLR (STM32_DMA2D_BASE+STM32_DMA2D_OCOLR_OFFSET)
+#define STM32_DMA2D_OMAR (STM32_DMA2D_BASE+STM32_DMA2D_OMAR_OFFSET)
+#define STM32_DMA2D_OOR (STM32_DMA2D_BASE+STM32_DMA2D_OOR_OFFSET)
+#define STM32_DMA2D_NLR (STM32_DMA2D_BASE+STM32_DMA2D_NLR_OFFSET)
+#define STM32_DMA2D_LWR (STM32_DMA2D_BASE+STM32_DMA2D_LWR_OFFSET)
+
+/* DMA2D Register Bit Definitions ********************************************/
+
+/* DMA2D Control Register */
+
+#define DMA2D_CR_START (1 << 0) /* Start Bit */
+#define DMA2D_CR_SUSP (1 << 1) /* Suspend Bit */
+#define DMA2D_CR_ABORT (1 << 2) /* Abort Bit */
+#define DMA2D_CR_TEIE (1 << 8) /* Transfer Error Interupt Enable Bit */
+#define DMA2D_CR_TCIE (1 << 9) /* Transfer Complete Interrupt Enable Bit */
+#define DMA2D_CR_TWIE (1 << 10) /* Transfer Watermark Interrupt Enable Bit */
+#define DMA2D_CR_CAEIE (1 << 11) /* CLUT Access Error Interrupt Enable Bit */
+#define DMA2D_CR_CTCIE (1 << 12) /* CLUT Transfer Complete Interrupt Enable Bit */
+#define DMA2D_CR_CEIE (1 << 13) /* Configuration Error Interrupt Enable Bit */
+#define DMA2D_CR_MODE_SHIFT (16) /* Bits 16-17 DMA2D mode Bits */
+#define DMA2D_CR_MODE_MASK (3 << DMA2D_CR_MODE_SHIFT)
+#define DMA2D_CR_MODE(n) ((uint32_t)(n) << DMA2D_CR_MODE_SHIFT)
+
+/* DMA2D Interrupt Status Register */
+
+#define DMA2D_ISR_TEIF (1 << 0) /* Transfer error interrupt flag */
+#define DMA2D_ISR_TCIF (1 << 1) /* Transfer Complete Interrupt flag */
+#define DMA2D_ISR_TWIF (1 << 2) /* Transfer Watermark Interrupt flag */
+#define DMA2D_ISR_CAEIF (1 << 3) /* CLUT Access Error Interrupt flag */
+#define DMA2D_ISR_CTCIF (1 << 4) /* CLUT Transfer Complete Interrupt flag */
+#define DMA2D_ISR_CEIF (1 << 5) /* Configuration Error Interrupt flag */
+
+/* DMA2D Interrupt Flag Clear Register */
+
+#define DMA2D_IFCR_CTEIF (1 << 0) /* Clear Transfer Interrupt Flag */
+#define DMA2D_IFCR_CTCIF (1 << 1) /* Clear Transfer Complete Interrupt Flag */
+#define DMA2D_IFCR_CTWIF (1 << 2) /* Clear Transfer Watermark Interrupt Flag */
+#define DMA2D_IFCR_CAECIF (1 << 3) /* Clear CLUT Access Error Interrupt Flag */
+#define DMA2D_IFCR_CCTCIF (1 << 4) /* Clear CLUT Transfer Complete Interrupt Flag */
+#define DMA2D_IFCR_CCEIF (1 << 5) /* Clear Configuration Error Interrupt Flag */
+
+/* DMA2D Foreground Memory Access Register */
+
+/* DMA2D Background Memory Access Register */
+
+/* DMA2D Foreground/Background Offset Register */
+
+#define DMA2D_xGOR_SHIFT (0) /* Bits 0-13 Line Offset */
+#define DMA2D_xGOR_MASK (0x3FFF << DMA2D_xGOR_SHIFT)
+#define DMA2D_xGOR(n) ((uint32_t)(n) << DMA2D_xGOR_SHIFT)
+
+/* DMA2D Foreground/Background PFC Control Register */
+
+#define DMA2D_xGPFCCR_CM_SHIFT (0) /* Bits 0-3 Color Mode */
+#define DMA2D_xGPFCCR_CM_MASK (0xF << DMA2D_xGPFCCR_CM_SHIFT)
+#define DMA2D_xGPFCCR_CM(n) ((uint32_t)(n) << DMA2D_xGPFCCR_CM_SHIFT)
+#define DMA2D_xGPFCCR_CCM (1 << 4) /* CLUT Color Mode */
+#define DMA2D_xGPFCCR_START (1 << 5) /* Start */
+#define DMA2D_xGPFCCR_CS_SHIFT (8) /* Bits 8-15 CLUT Size */
+#define DMA2D_xGPFCCR_CS_MASK (0xFF << DMA2D_xGPFCCR_CS_SHIFT)
+#define DMA2D_xGPFCCR_CS(n) ((uint32_t)(n) << DMA2D_xGPFCCR_CS_SHIFT)
+#define DMA2D_xGPFCCR_AM_SHIFT (16) /* Bits 16-17 Alpha Mode */
+#define DMA2D_xGPFCCR_AM_MASK (3 << DMA2D_xGPFCCR_AM_SHIFT)
+#define DMA2D_xGPFCCR_AM(n) ((uint32_t)(n) << DMA2D_xGPFCCR_AM_SHIFT)
+#define DMA2D_xGPFCCR_ALPHA_SHIFT (24) /* Bits 24-31 Alpha Value */
+#define DMA2D_xGPFCCR_ALPHA_MASK (0xFF << DMA2D_xGPFCCR_ALPHA_SHIFT)
+#define DMA2D_xGPFCCR_ALPHA(n) ((uint32_t)(n) << DMA2D_xGPFCCR_ALPHA_SHIFT)
+
+/* DMA2D Foreground/Background Color Register */
+
+#define DMA2D_xGCOLR_BLUE_SHIFT (0) /* Bits 0-7 Blue Value */
+#define DMA2D_xGCOLR_BLUE_MASK (0xFF << DMA2D_xGCOLR_BLUE_SHIFT)
+#define DMA2D_xGCOLR_BLUE(n) ((uint32_t)(n) << DMA2D_xGCOLR_BLUE_SHIFT)
+#define DMA2D_xGCOLR_GREEN_SHIFT (8) /* Bits 8-15 Green Value */
+#define DMA2D_xGCOLR_GREEN_MASK (0xFF << DMA2D_xGCOLR_GREEN_SHIFT)
+#define DMA2D_xGCOLR_GREEN(n) ((uint32_t)(n) << DMA2D_xGCOLR_GREEN_SHIFT)
+#define DMA2D_xGCOLR_RED_SHIFT (16) /* Bits 16-23 Red Value */
+#define DMA2D_xGCOLR_RED_MASK (0xFF << DMA2D_xGCOLR_RED_SHIFT)
+#define DMA2D_xGCOLR_RED(n) ((uint32_t)(n) << DMA2D_xGCOLR_RED_SHIFT)
+
+
+/* DMA2D Foreground CLUT Memory Address Register */
+
+/* DMA2D Background CLUT Memory Address Register */
+
+/* DMA2D Output PFC Control Register */
+
+#define DMA2D_OPFCCR_CM_SHIFT (0) /* Bits 0-2 Color Mode */
+#define DMA2D_OPFCCR_CM_MASK (7 << DMA2D_OPFCCR_CM_SHIFT)
+#define DMA2D_OPFCCR_CM(n) ((uint32_t)(n) << DMA2D_OPFCCR_CM_SHIFT)
+
+/* DMA2D Output Color Register */
+
+#define DMA2D_OCOLR_BLUE_SHIFT (0) /* Bits 0-7 Blue Value */
+#define DMA2D_OCOLR_BLUE_MASK (0xFF << DMA2D_OCOLR_BLUE_SHIFT)
+#define DMA2D_OCOLR_BLUE(n) ((uint32_t)(n) << DMA2D_OCOLR_BLUE_SHIFT)
+#define DMA2D_OCOLR_GREEN_SHIFT (8) /* Bits 8-15 Green Value */
+#define DMA2D_OCOLR_GREEN_MASK (0xFF << DMA2D_OCOLR_GREEN_SHIFT)
+#define DMA2D_OCOLR_GREEN(n) ((uint32_t)(n) << DMA2D_OCOLR_GREEN_SHIFT)
+#define DMA2D_OCOLR_RED_SHIFT (16) /* Bits 16-23 Red Value */
+#define DMA2D_OCOLR_RED_MASK (0xFF << DMA2D_OCOLR_RED_SHIFT)
+#define DMA2D_OCOLR_RED(n) ((uint32_t)(n) << DMA2D_OCOLR_RED_SHIFT)
+#define DMA2D_OCOLR_ALPHA_SHIFT (24) /* Bits 24-31 Alpha Value */
+#define DMA2D_OCOLR_ALPHA_MASK (0xFF << DMA2D_OCOLR_ALPHA_SHIFT)
+#define DMA2D_OCOLR_ALPHA(n) ((uint32_t)(n) << DMA2D_OCOLR_ALPHA_SHIFT)
+
+/* DMA2D Output Memory Address Register */
+
+/* DMA2D Output Offset Register */
+
+#define DMA2D_OOR_LO_SHIFT (0) /* Bits 0-13 Line Offset */
+#define DMA2D_OOR_LO_MASK (0x3FFF << DMA2D_OOR_LO_SHIFT)
+#define DMA2D_OOR_LO(n) ((uint32_t)(n) << DMA2D_OOR_LO_SHIFT)
+
+/* DMA2D Number Of Line Register */
+
+#define DMA2D_NLR_NL_SHIFT (0) /* Bits 0-15 Number Of Lines */
+#define DMA2D_NLR_NL_MASK (0xFFFF << DMA2D_NLR_NL_SHIFT)
+#define DMA2D_NLR_NL(n) ((uint32_t)(n) << DMA2D_NLR_NL_SHIFT)
+#define DMA2D_NLR_PL_SHIFT (16) /* Bits 16-29 Pixel per Lines */
+#define DMA2D_NLR_PL_MASK (0x3FFF << DMA2D_NLR_PL_SHIFT)
+#define DMA2D_NLR_PL(n) ((uint32_t)(n) << DMA2D_NLR_PL_SHIFT)
+
+/* DMA2D Line Watermark Register */
+
+#define DMA2D_LWR_LW_SHIFT (0) /* Bits 0-15 Line Watermark */
+#define DMA2D_LWR_LW_MASK (0xFFFF << DMA2D_LWR_LW_SHIFT)
+#define DMA2D_LWR_LW(n) ((uint32_t)(n) << DMA2D_LWR_LW_SHIFT)
+
+/* DMA2D AHB Master Timer Configuration Register */
+
+#define DMA2D_AMTCR_EN (1 << 0) /* Enable */
+#define DMA2D_AMTCR_DT_SHIFT (0) /* Bits 8-15 Dead Time */
+#define DMA2D_AMTCR_DT_MASK (0xFF << DMA2D_AMTCR_DT_SHIFT)
+#define DMA2D_AMTCR_DT(n) ((uint32_t)(n) << DMA2D_AMTCR_DT_SHIFT)
+
+/*****************************************************************************
+ * Public Types
+ *****************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_DMA2D_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_ccm.h b/nuttx/arch/arm/src/stm32/stm32_ccm.h
index 91b330387..c027c54a6 100644
--- a/nuttx/arch/arm/src/stm32/stm32_ccm.h
+++ b/nuttx/arch/arm/src/stm32/stm32_ccm.h
@@ -82,7 +82,7 @@
*/
#define ccm_initialize() \
- mm_initialize(&g_ccm_heap, (uintptr_t)CCM_START, CCM_END-CCM_START)
+ mm_initialize(&g_ccm_heap, (FAR void *)CCM_START, CCM_END-CCM_START)
/* The ccm_addregion interface could be used if, for example, you want to
* add some other memory region to the CCM heap. I don't really know why
diff --git a/nuttx/arch/arm/src/stm32/stm32_dma2d.c b/nuttx/arch/arm/src/stm32/stm32_dma2d.c
index 90396e561..f999d1b08 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dma2d.c
+++ b/nuttx/arch/arm/src/stm32/stm32_dma2d.c
@@ -1,7 +1,7 @@
/******************************************************************************
* arch/arm/src/stm32/stm32_dma2d.c
*
- * Copyright (C) 2014 Marco Krahl. All rights reserved.
+ * Copyright (C) 2014-2015 Marco Krahl. All rights reserved.
* Author: Marco Krahl <ocram.lhark@gmail.com>
*
* References:
@@ -46,35 +46,344 @@
#include <string.h>
#include <errno.h>
#include <debug.h>
+#include <semaphore.h>
+#include <nuttx/irq.h>
#include <nuttx/video/fb.h>
#include <nuttx/kmalloc.h>
-#include <arch/chip/ltdc.h>
+#include <arch/chip/dma2d.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "stm32.h"
#include "chip/stm32_ltdc.h"
-#include "stm32_ltdc.h"
+#include "chip/stm32_dma2d.h"
+#include "chip/stm32_ccm.h"
+#include "stm32_dma2d.h"
/******************************************************************************
* Pre-processor Definitions
******************************************************************************/
+/* output, foreground and background layer */
+
+#define DMA2D_NLAYERS 3
+
+/* DMA2D PFC value definitions */
+
+#define DMA2D_PF_ARGB8888 0
+#define DMA2D_PF_RGB888 1
+#define DMA2D_PF_RGB565 2
+#define DMA2D_PF_ARGB1555 3
+#define DMA2D_PF_ARGB14444 4
+#define DMA2D_PF_L8 5
+#define DMA2D_PF_AL44 6
+#define DMA2D_PF_AL88 7
+#define DMA2D_PF_L4 8
+#define DMA2D_PF_A8 9
+#define DMA2D_PF_A4 10
+
+/* DMA2D blender control */
+
+#define STM32_DMA2D_CR_MODE_BLIT DMA2D_CR_MODE(0)
+#define STM32_DMA2D_CR_MODE_BLITPFC DMA2D_CR_MODE(1)
+#define STM32_DMA2D_CR_MODE_BLEND DMA2D_CR_MODE(2)
+#define STM32_DMA2D_CR_MODE_COLOR DMA2D_CR_MODE(3)
+#define STM32_DMA2D_CR_MODE_CLEAR STM32_DMA2D_CR_MODE_COLOR
+
+/* DMA2D PFC alpha mode */
+
+#define STM32_DMA2D_PFCCR_AM_NONE 0
+#define STM32_DMA2D_PFCCR_AM_CONST 1
+#define STM32_DMA2D_PFCCR_AM_PIXEL 10
+
+/* Only 8 bit per pixel overal supported */
+
+#define DMA2D_PF_BYPP(n) ((n) / 8)
+
+#define DMA2D_CLUT_SIZE STM32_LTDC_NCLUT - 1
+
+/* Layer argb cmap conversion */
+
+#define DMA2D_CLUT_ALPHA(n) ((uint32_t)(n) << 24)
+#define DMA2D_CLUT_RED(n) ((uint32_t)(n) << 16)
+#define DMA2D_CLUT_GREEN(n) ((uint32_t)(n) << 8)
+#define DMA2D_CLUT_BLUE(n) ((uint32_t)(n) << 0)
+
+#define DMA2D_CMAP_ALPHA(n) ((uint32_t)(n) >> 24)
+#define DMA2D_CMAP_RED(n) ((uint32_t)(n) >> 16)
+#define DMA2D_CMAP_GREEN(n) ((uint32_t)(n) >> 8)
+#define DMA2D_CMAP_BLUE(n) ((uint32_t)(n) >> 0)
+
+/* Define shadow layer for ltdc interface */
+
+#ifdef CONFIG_STM32_LTDC_INTERFACE
+# ifdef CONFIG_STM32_LTDC_L2
+# define DMA2D_SHADOW_LAYER 2
+# define DMA2D_SHADOW_LAYER_L1 0
+# define DMA2D_SHADOW_LAYER_L2 1
+# else
+# define DMA2D_SHADOW_LAYER 1
+# define DMA2D_SHADOW_LAYER_L1 0
+# endif
+# define DMA2D_LAYER_NSIZE CONFIG_STM32_DMA2D_NLAYERS + DMA2D_SHADOW_LAYER
+#else
+# define DMA2D_LAYER_NSIZE CONFIG_STM32_DMA2D_NLAYERS
+# define DMA2D_SHADOW_LAYER 0
+#endif
+
+/* Debug option */
+
+#ifdef CONFIG_STM32_DMA2D_REGDEBUG
+# define regdbg dbg
+# define regvdbg vdbg
+#else
+# define regdbg(x...)
+# define regvdbg(x...)
+#endif
+
+/* check clut support */
+
+#ifdef CONFIG_STM32_DMA2D_L8
+# ifndef CONFIG_FB_CMAP
+# error "Enable cmap to support the configured layer formats!"
+# endif
+#endif
+
+/* check ccm heap allocation */
+
+#ifndef CONFIG_STM32_CCMEXCLUDE
+# error "Enable CONFIG_STM32_CCMEXCLUDE from the heap allocation"
+#endif
+
/******************************************************************************
* Private Types
******************************************************************************/
+/* DMA2D General layer information */
+
+struct stm32_dma2d_s
+{
+ struct dma2d_layer_s dma2d; /* public dma2d interface */
+
+ /* Fixed settings */
+
+ int lid; /* Layer identifier */
+ struct fb_videoinfo_s vinfo; /* Layer videoinfo */
+ struct fb_planeinfo_s pinfo; /* Layer planeinfo */
+
+ /* Blending */
+
+ uint32_t blendmode; /* the interface blendmode */
+ uint8_t alpha; /* the alpha value */
+
+ /* Coloring */
+
+#ifdef CONFIG_STM32_DMA2D_L8
+ uint32_t *clut; /* Color lookup table */
+#endif
+
+ /* Operation */
+ uint8_t fmt; /* the controller pixel format */
+ sem_t *lock; /* Ensure mutually exclusive access */
+};
+
+#ifdef CONFIG_STM32_LTDC_INTERFACE
+
+/* This structures provides the DMA2D layer for each LTDC layer */
+
+struct stm32_ltdc_dma2d_s
+{
+ struct stm32_dma2d_s dma2ddev;
+#ifdef CONFIG_STM32_DMA2D_L8
+ FAR struct ltdc_layer_s *ltdc;
+#endif
+};
+
+struct stm32_ltdc_layer_s
+{
+ /* Layer state */
+
+ struct stm32_ltdc_dma2d_s layer[DMA2D_SHADOW_LAYER];
+};
+#endif
+
+/* Interrupt handling */
+
+struct stm32_interrupt_s
+{
+ bool wait; /* Informs that the task is waiting for the irq */
+ bool handled; /* Informs that an irq was handled */
+ int irq; /* irq number */
+ sem_t *sem; /* Semaphore for waiting for irq */
+};
+
+/* This enumeration foreground and background layer supported by the dma2d
+ * controller
+ */
+
+enum stm32_layer_e
+{
+ DMA2D_LAYER_LFORE = 0, /* Foreground Layer */
+ DMA2D_LAYER_LBACK, /* Background Layer */
+ DMA2D_LAYER_LOUT, /* Output Layer */
+};
+
+/* DMA2D memory address register */
+
+static const uintptr_t stm32_mar_layer_t[DMA2D_NLAYERS] =
+{
+ STM32_DMA2D_FGMAR,
+ STM32_DMA2D_BGMAR,
+ STM32_DMA2D_OMAR
+};
+
+/* DMA2D offset register */
+
+static const uintptr_t stm32_or_layer_t[DMA2D_NLAYERS] =
+{
+ STM32_DMA2D_FGOR,
+ STM32_DMA2D_BGOR,
+ STM32_DMA2D_OOR
+};
+
+/* DMA2D pfc control register */
+
+static const uintptr_t stm32_pfccr_layer_t[DMA2D_NLAYERS] =
+{
+ STM32_DMA2D_FGPFCCR,
+ STM32_DMA2D_BGPFCCR,
+ STM32_DMA2D_OPFCCR
+};
+
+/* DMA2D color register */
+
+static const uintptr_t stm32_color_layer_t[DMA2D_NLAYERS] =
+{
+ STM32_DMA2D_FGCOLR,
+ STM32_DMA2D_BGCOLR,
+ STM32_DMA2D_OCOLR
+};
+
+/* DMA2D clut memory address register */
+
+static const uintptr_t stm32_cmar_layer_t[DMA2D_NLAYERS - 1] =
+{
+ STM32_DMA2D_FGCMAR,
+ STM32_DMA2D_BGCMAR
+};
+
/******************************************************************************
* Private Function Prototypes
******************************************************************************/
+/* Private functions */
+
+static int stm32_dma2d_pixelformat(uint8_t fmt, uint8_t *fmtmap);
+static int stm32_dma2d_bpp(uint8_t fmt, uint8_t *bpp);
+static void stm32_dma2d_control(uint32_t setbits, uint32_t clrbits);
+static int stm32_dma2dirq(int irq, void *context);
+static int stm32_dma2d_waitforirq(void);
+static int stm32_dma2d_start(void);
+#ifdef CONFIG_STM32_DMA2D_L8
+static int stm32_dma2d_loadclut(uintptr_t reg);
+#endif
+static uint32_t stm32_dma2d_memaddress(FAR const struct stm32_dma2d_s *layer,
+ fb_coord_t xpos, fb_coord_t ypos);
+static fb_coord_t stm32_dma2d_lineoffset(FAR const struct stm32_dma2d_s *layer,
+ FAR const struct ltdc_area_s *area);
+
+static int stm32_dma2d_lfreelid(void);
+static FAR struct stm32_dma2d_s * stm32_dma2d_lalloc(void);
+static void stm32_dma2d_lfree(FAR struct stm32_dma2d_s *layer);
+static void stm32_dma2d_llayerscleanup(void);
+static bool stm32_dma2d_lvalidate(FAR const struct stm32_dma2d_s *layer);
+static bool stm32_dma2d_lvalidatesize(FAR const struct stm32_dma2d_s *layer,
+ fb_coord_t xpos, fb_coord_t ypos,
+ FAR const struct ltdc_area_s *area);
+static void stm32_dma2d_linit(FAR struct stm32_dma2d_s *layer,
+ int lid, uint8_t fmt);
+
+static void stm32_dma2d_lfifo(FAR const struct stm32_dma2d_s *layer, int lid,
+ fb_coord_t xpos, fb_coord_t ypos,
+ FAR const struct ltdc_area_s *area);
+static void stm32_dma2d_lcolor(FAR const struct stm32_dma2d_s *layer,
+ int lid, uint32_t color);
+static void stm32_dma2d_llnr(FAR struct stm32_dma2d_s *layer,
+ FAR const struct ltdc_area_s *area);
+static int stm32_dma2d_loutpfc(FAR const struct stm32_dma2d_s *layer);
+static void stm32_dma2d_lpfc(FAR const struct stm32_dma2d_s *layer,
+ int lid, uint32_t blendmode);
+/* Public functions */
+
+static int stm32_dma2dgetvideoinfo(FAR struct dma2d_layer_s *layer,
+ FAR struct fb_videoinfo_s *vinfo);
+static int stm32_dma2dgetplaneinfo(FAR struct dma2d_layer_s *layer, int planeno,
+ FAR struct fb_planeinfo_s *pinfo);
+static int stm32_dma2dgetlid(FAR struct dma2d_layer_s *layer, int *lid);
+#ifdef CONFIG_STM32_DMA2D_L8
+static int stm32_dma2dsetclut(FAR struct dma2d_layer_s *layer,
+ const FAR struct fb_cmap_s *cmap);
+static int stm32_dma2dgetclut(FAR struct dma2d_layer_s *layer,
+ FAR struct fb_cmap_s *cmap);
+#endif
+static int stm32_dma2dsetalpha(FAR struct dma2d_layer_s *layer, uint8_t alpha);
+static int stm32_dma2dgetalpha(FAR struct dma2d_layer_s *layer, uint8_t *alpha);
+static int stm32_dma2dsetblendmode(FAR struct dma2d_layer_s *layer,
+ uint32_t mode);
+static int stm32_dma2dgetblendmode(FAR struct dma2d_layer_s *layer,
+ uint32_t *mode);
+static int stm32_dma2dblit(FAR struct dma2d_layer_s *dest,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *src,
+ FAR const struct ltdc_area_s *srcarea);
+static int stm32_dma2dblend(FAR struct dma2d_layer_s *dest,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *fore,
+ fb_coord_t forexpos, fb_coord_t foreypos,
+ FAR const struct dma2d_layer_s *back,
+ FAR const struct ltdc_area_s *backarea);
+static int stm32_dma2dfillarea(FAR struct dma2d_layer_s *layer,
+ FAR const struct ltdc_area_s *area, uint32_t color);
+
/******************************************************************************
* Private Data
******************************************************************************/
+/* Remember the layer references for alloc/deallocation */
+
+static struct stm32_dma2d_s *g_layers[DMA2D_LAYER_NSIZE];
+
+/* The DMA2D semaphore that enforces mutually exclusive access */
+
+static sem_t g_lock;
+
+#ifdef CONFIG_STM32_LTDC_INTERFACE
+/* This structure provides the DMA2D layer for each LTDC layer */
+
+static struct stm32_ltdc_layer_s g_ltdc_layer;
+#endif
+
+/* The initalized state of the driver */
+
+static bool g_initialized;
+
+/* Semaphore for interrupt handling */
+
+static sem_t g_semirq;
+
+/* This structure provides irq handling */
+
+static struct stm32_interrupt_s g_interrupt =
+{
+ .wait = false,
+ .handled = true,
+ .irq = STM32_IRQ_DMA2D,
+ .sem = &g_semirq
+};
+
/******************************************************************************
* Public Data
******************************************************************************/
@@ -84,72 +393,1754 @@
******************************************************************************/
/******************************************************************************
+ * Name: stm32_dma2d_control
+ *
+ * Description:
+ * Change the DMA2D control register
+ *
+ * Parameter:
+ * setbits - The bits to set
+ * clrbits - The bits to clear
+ *
+ ****************************************************************************/
+
+static void stm32_dma2d_control(uint32_t setbits, uint32_t clrbits)
+{
+ uint32_t cr;
+
+ gvdbg("setbits=%08x, clrbits=%08x\n", setbits, clrbits);
+
+ cr = getreg32(STM32_DMA2D_CR);
+ cr &= ~clrbits;
+ cr |= setbits;
+ putreg32(cr, STM32_DMA2D_CR);
+}
+
+/****************************************************************************
+ * Name: stm32_dma2dirq
+ *
+ * Description:
+ * DMA2D interrupt handler
+ *
+ ****************************************************************************/
+
+static int stm32_dma2dirq(int irq, void *context)
+{
+ uint32_t regval = getreg32(STM32_DMA2D_ISR);
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
+
+ regvdbg("irq = %d, regval = %08x\n", irq, regval);
+
+ if (regval & DMA2D_ISR_TCIF)
+ {
+ /* Transfer complete interrupt */
+
+ /* Clear the interrupt status register */
+
+ putreg32(DMA2D_IFCR_CTCIF, STM32_DMA2D_IFCR);
+ }
+#ifdef CONFIG_STM32_DMA2D_L8
+ else if (regval & DMA2D_ISR_CTCIF)
+ {
+ /* CLUT transfer complete interrupt */
+
+ /* Clear the interrupt status register */
+
+ putreg32(DMA2D_IFCR_CCTCIF, STM32_DMA2D_IFCR);
+ }
+#endif
+ else
+ {
+ /* Unknown irq, should not occur */
+
+ return OK;
+ }
+
+ /* Update the handled flag */
+
+ priv->handled = true;
+
+ /* Unlock the semaphore if locked */
+
+ if (priv->wait)
+ {
+
+ int ret = sem_post(priv->sem);
+
+ if (ret != OK)
+ {
+ dbg("sem_post() failed\n");
+ return ret;
+ }
+ }
+
+ return OK;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_waitforirq
+ *
+ * Description:
+ * Helper waits until the dma2d irq occurs. That means that an ongoing clut
+ * loading or dma transfer was completed.
+ * Note! The caller must use this function within irqsave state.
+ *
+ * Return:
+ * On success OK otherwise ERROR
+ *
+ ****************************************************************************/
+
+static int stm32_dma2d_waitforirq(void)
+{
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
+
+ /* Only waits if last enabled interrupt is currently not handled */
+
+ if (!priv->handled)
+ {
+ int ret;
+
+ /* Inform the irq handler the task is able to wait for the irq */
+
+ priv->wait = true;
+
+ ret = sem_wait(priv->sem);
+
+ /* irq or an error occurs, reset the wait flag */
+
+ priv->wait = false;
+
+ if (ret != OK)
+ {
+ dbg("sem_wait() failed\n");
+ return ret;
+ }
+ }
+
+ return OK;
+}
+
+
+#ifdef CONFIG_STM32_DMA2D_L8
+/******************************************************************************
+ * Name: stm32_dma2d_loadclut
+ *
+ * Description:
+ * Starts clut loading but doesn't wait until loading is complete!
+ *
+ * Parameter:
+ * pfcreg - PFC control Register
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ****************************************************************************/
+
+static int stm32_dma2d_loadclut(uintptr_t pfcreg)
+{
+ int ret;
+ uint32_t regval;
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ ret = stm32_dma2d_waitforirq();
+ if (ret == OK)
+ {
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
+
+ /* Reset the handled flag */
+
+ priv->handled = false;
+
+ /* Start clut loading */
+
+ regval = getreg32(pfcreg);
+ regval |= DMA2D_xGPFCCR_START;
+ regvdbg("set regval=%08x\n", regval);
+ putreg32(regval, pfcreg);
+ regvdbg("configured regval=%08x\n", getreg32(pfcreg));
+ }
+
+ irqrestore(flags);
+ return OK;
+}
+#endif
+
+/******************************************************************************
+ * Name: stm32_dma2d_start
+ *
+ * Description:
+ * Starts the dma transfer and waits until completed.
+ *
+ * Parameter:
+ * reg - Register to set the start
+ * startflag - The related flag to start the dma transfer
+ * irqflag - The interrupt enable flag in the DMA2D_CR register
+ *
+ ****************************************************************************/
+
+static int stm32_dma2d_start(void)
+{
+ int ret;
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ ret = stm32_dma2d_waitforirq();
+ if (ret == OK)
+ {
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
+
+ /* Reset the handled flag */
+
+ priv->handled = false;
+
+ /* Start clut loading */
+
+ stm32_dma2d_control(DMA2D_CR_START, 0);
+
+ /* wait until transfer is complete */
+
+ ret = stm32_dma2d_waitforirq();
+ }
+
+ irqrestore(flags);
+ return ret;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_memaddress
+ *
+ * Description:
+ * Helper to calculate the layer memory address
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ *
+ * Return:
+ * memory address
+ *
+ *****************************************************************************/
+
+static uint32_t stm32_dma2d_memaddress(FAR const struct stm32_dma2d_s *layer,
+ fb_coord_t xpos, fb_coord_t ypos)
+{
+ FAR const struct fb_planeinfo_s *pinfo = &layer->pinfo;
+ uint32_t offset;
+
+ offset = xpos * DMA2D_PF_BYPP(layer->pinfo.bpp) + layer->pinfo.stride * ypos;
+
+ gvdbg("%p\n", ((uint32_t) pinfo->fbmem) + offset);
+ return ((uint32_t) pinfo->fbmem) + offset;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lineoffset
+ *
+ * Description:
+ * Helper to calculate the layer line offset
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ *
+ * Return:
+ * line offset
+ *
+ *****************************************************************************/
+
+static fb_coord_t stm32_dma2d_lineoffset(FAR const struct stm32_dma2d_s *layer,
+ FAR const struct ltdc_area_s *area)
+{
+ /* offset at the end of each line in the context to the area layer */
+
+ gvdbg("%d\n", layer->vinfo.xres - area->xres);
+ return layer->vinfo.xres - area->xres;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_pixelformat
+ *
+ * Description:
+ * Helper to map to dma2d controller pixel format
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ * fmt - Reference to the location to store the pixel format
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ *****************************************************************************/
+
+static int stm32_dma2d_pixelformat(uint8_t fmt, uint8_t *fmtmap)
+{
+ gvdbg("fmt=%d, fmtmap=%p\n", fmt, fmtmap);
+
+ /* Map to the controller known format
+ *
+ * Not supported by NuttX:
+ * ARGB8888
+ * ARGB1555
+ * ARGB4444
+ * AL44
+ * AL88
+ * L8 (non output layer only)
+ * L4
+ * A8
+ * A4
+ */
+
+ switch(fmt)
+ {
+#ifdef CONFIG_STM32_DMA2D_RGB565
+ case FB_FMT_RGB16_565:
+ *fmtmap = DMA2D_PF_RGB565;
+ break;
+#endif
+#ifdef CONFIG_STM32_DMA2D_RGB888
+ case FB_FMT_RGB24:
+ *fmtmap = DMA2D_PF_RGB888;
+ break;
+#endif
+#ifdef CONFIG_STM32_DMA2D_L8
+ case FB_FMT_RGB8:
+ *fmtmap = DMA2D_PF_L8;
+ break;
+#endif
+ default:
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+ }
+
+ return OK;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_bpp
+ *
+ * Description:
+ * Helper to get the bits per pixel
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ * bpp - Reference to the location to store the pixel format
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ *****************************************************************************/
+
+static int stm32_dma2d_bpp(uint8_t fmt, uint8_t *bpp)
+{
+ gvdbg("fmt=%d, bpp=%p\n", fmt, bpp);
+
+ switch(fmt)
+ {
+#ifdef CONFIG_STM32_DMA2D_RGB565
+ case FB_FMT_RGB16_565:
+ *bpp = 16;
+ break;
+#endif
+#ifdef CONFIG_STM32_DMA2D_RGB888
+ case FB_FMT_RGB24:
+ *bpp = 24;
+ break;
+#endif
+#ifdef CONFIG_STM32_DMA2D_L8
+ case FB_FMT_RGB8:
+ *bpp = 8;
+ break;
+#endif
+ default:
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+ }
+
+ return OK;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lfreelid
+ *
+ * Description:
+ * Get a free layer id
+ *
+ * Return:
+ * The number of the free layer
+ * -1 if no free layer is available
+ *
+ ******************************************************************************/
+
+static int stm32_dma2d_lfreelid(void)
+{
+ int n;
+
+ for (n = DMA2D_SHADOW_LAYER; n < DMA2D_LAYER_NSIZE; n++)
+ {
+ if (g_layers[n] == NULL)
+ {
+ return n;
+ }
+ }
+
+ return -1;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lalloc
+ *
+ * Description:
+ * Allocate a new layer structure
+ *
+ * Return:
+ * A new allocated layer structure or NULL on error.
+ *
+ ******************************************************************************/
+
+static FAR struct stm32_dma2d_s * stm32_dma2d_lalloc(void)
+{
+ FAR struct stm32_dma2d_s *layer;
+
+#ifdef HAVE_CCM_HEAP
+ /* First try to allocate from the ccm heap */
+
+ layer = ccm_malloc(sizeof(struct stm32_dma2d_s));
+
+ if (!layer)
+ {
+ /* Use default allocator */
+
+ layer = kmm_malloc(sizeof(struct stm32_dma2d_s));
+ }
+#else
+ layer = kmm_malloc(sizeof(struct stm32_dma2d_s));
+#endif
+
+ return layer;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lfree
+ *
+ * Description:
+ * Deallocate the dynamic allocated layer structure
+ *
+ * Input Parameters:
+ * A previous allocated layer structure
+ *
+ ******************************************************************************/
+
+static void stm32_dma2d_lfree(FAR struct stm32_dma2d_s *layer)
+{
+ if (layer)
+ {
+#ifdef HAVE_CCM_HEAP
+ if (((uint32_t)layer & 0xf0000000) == 0x10000000)
+ {
+ ccm_free(layer);
+ }
+ else
+ {
+ kmm_free(layer);
+ }
+#else
+ kmm_free(layer);
+#endif
+ }
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_llayerscleanup
+ *
+ * Description:
+ * Cleanup all allocated layers
+ *
+ ******************************************************************************/
+
+static void stm32_dma2d_llayerscleanup(void)
+{
+ int n;
+
+ /* Do not uninitialize the ltdc related dma2d layer */
+
+ for (n = DMA2D_SHADOW_LAYER; n < DMA2D_LAYER_NSIZE; n++)
+ {
+ FAR struct stm32_dma2d_s *priv = g_layers[n];
+ if (priv)
+ {
+ kmm_free(priv->pinfo.fbmem);
+ stm32_dma2d_lfree(priv);
+ g_layers[n] = NULL;
+ }
+ }
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lvalidate
+ *
+ * Description:
+ * Helper to validate if the layer is valid
+ *
+ * Return:
+ * true if validates otherwise false
+ *
+ ******************************************************************************/
+
+static inline bool stm32_dma2d_lvalidate(FAR const struct stm32_dma2d_s *layer)
+{
+ return layer && layer->lid < DMA2D_LAYER_NSIZE;
+}
+
+/****************************************************************************
+ * Name: stm32_dma2d_lvalidatesize
+ *
+ * Description:
+ * Helper to check if area is outside the whole layer.
+ *
+ * Parameter:
+ * layer - Reference to the layer control structure
+ * xpos - The x position inside the whole layer
+ * ypos - The y position inside the whole layer
+ * area - the area inside the whole layer
+ *
+ * Return:
+ * true if area is inside the whole layer otherwise false
+ *
+ ****************************************************************************/
+
+static bool stm32_dma2d_lvalidatesize(FAR const struct stm32_dma2d_s *layer,
+ fb_coord_t xpos, fb_coord_t ypos,
+ FAR const struct ltdc_area_s *area)
+{
+ return stm32_dma2d_lvalidate(layer) &&
+ ((layer->vinfo.xres - xpos) * (layer->vinfo.yres - ypos) >=
+ area->xres * area->yres);
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_linit
+ *
+ * Description:
+ * Initialize the internal layer structure
+ *
+ * Parameter:
+ *
+ *
+ ******************************************************************************/
+
+static void stm32_dma2d_linit(FAR struct stm32_dma2d_s *layer,
+ int lid, uint8_t fmt)
+{
+ FAR struct dma2d_layer_s *priv = &layer->dma2d;
+
+ gvdbg("layer=%p, lid=%d, fmt=%02x\n", layer, lid, fmt);
+
+ /* initialize the layer interface */
+
+ priv->getvideoinfo = stm32_dma2dgetvideoinfo;
+ priv->getplaneinfo = stm32_dma2dgetplaneinfo;
+ priv->getlid = stm32_dma2dgetlid;
+#ifdef CONFIG_STM32_DMA2D_L8
+ priv->setclut = stm32_dma2dsetclut;
+ priv->getclut = stm32_dma2dgetclut;
+#endif
+ priv->setalpha = stm32_dma2dsetalpha;
+ priv->getalpha = stm32_dma2dgetalpha;
+ priv->setblendmode = stm32_dma2dsetblendmode;
+ priv->getblendmode = stm32_dma2dgetblendmode;
+ priv->blit = stm32_dma2dblit;
+ priv->blend = stm32_dma2dblend;
+ priv->fillarea = stm32_dma2dfillarea;
+
+ /* Initialize the layer structure */
+
+ layer->lid = lid;
+#ifdef CONFIG_STM32_DMA2D_L8
+ layer->clut = 0;
+#endif
+ layer->blendmode = DMA2D_BLEND_NONE;
+ layer->alpha = 255;
+ layer->fmt = fmt;
+ layer->lock = &g_lock;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lfifo
+ *
+ * Description:
+ * Set the fifo for the foreground, background and output layer
+ * Configures the memory address register
+ * Configures the line offset register
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ *
+ ****************************************************************************/
+
+static void stm32_dma2d_lfifo(FAR const struct stm32_dma2d_s *layer, int lid,
+ fb_coord_t xpos, fb_coord_t ypos,
+ FAR const struct ltdc_area_s *area)
+{
+ gvdbg("layer=%p, lid=%d, xpos=%d, ypos=%d, area=%p\n",
+ layer, lid, xpos, ypos, area);
+
+ putreg32(stm32_dma2d_memaddress(layer, xpos, ypos), stm32_mar_layer_t[lid]);
+ putreg32(stm32_dma2d_lineoffset(layer, area), stm32_or_layer_t[lid]);
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lcolor
+ *
+ * Description:
+ * Set the color for the layer
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ *
+ ****************************************************************************/
+
+static void stm32_dma2d_lcolor(FAR const struct stm32_dma2d_s *layer,
+ int lid, uint32_t color)
+{
+ gvdbg("layer=%p, lid=%d, color=%08x\n", layer, lid, color);
+ putreg32(color, stm32_color_layer_t[lid]);
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_llnr
+ *
+ * Description:
+ * Set the number of line register
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ * area - Reference to the area to copy
+ *
+ ****************************************************************************/
+
+static void stm32_dma2d_llnr(FAR struct stm32_dma2d_s *layer,
+ FAR const struct ltdc_area_s *area)
+{
+ uint32_t nlrreg;
+
+ gvdbg("pixel per line: %d, number of lines: %d\n", area->xres, area->yres);
+
+ nlrreg = getreg32(STM32_DMA2D_NLR);
+ nlrreg = (DMA2D_NLR_PL(area->xres)|DMA2D_NLR_NL(area->yres));
+ putreg32(nlrreg, STM32_DMA2D_NLR);
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_loutpfc
+ *
+ * Description:
+ * Set the output PFC control register
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ *
+ ****************************************************************************/
+
+static int stm32_dma2d_loutpfc(FAR const struct stm32_dma2d_s *layer)
+{
+ gvdbg("layer=%p\n", layer);
+
+ /* CLUT format isn't supported by the dma2d controller */
+
+ if (layer->fmt == DMA2D_PF_L8)
+ {
+ /* Destination layer doesn't support CLUT output */
+
+ gdbg("ERROR: Returning ENOSYS, "
+ "output to layer with CLUT format not supported.\n");
+ return -ENOSYS;
+ }
+
+ /* Set the mapped pixel format of source layer */
+
+ putreg32(DMA2D_OPFCCR_CM(layer->fmt), STM32_DMA2D_OPFCCR);
+
+ return OK;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2d_lpfc
+ *
+ * Description:
+ * Configure foreground and background layer PFC control register
+ *
+ * Parameter:
+ * layer - Reference to the common layer state structure
+ *
+ ****************************************************************************/
+
+static void stm32_dma2d_lpfc(FAR const struct stm32_dma2d_s *layer,
+ int lid, uint32_t blendmode)
+{
+ uint32_t pfccrreg;
+
+ gvdbg("layer=%p, lid=%d, blendmode=%08x\n", layer, lid, blendmode);
+
+ /* Set color format */
+
+ pfccrreg = DMA2D_xGPFCCR_CM(layer->fmt);
+
+#ifdef CONFIG_STM32_DMA2D_L8
+ if (layer->fmt == DMA2D_PF_L8)
+ {
+ /* Load CLUT automatically */
+
+ pfccrreg |= DMA2D_xGPFCCR_START;
+
+ /* Set the CLUT color mode */
+
+#ifndef CONFIG_FB_TRANSPARENCY
+ pfccrreg |= DMA2D_xGPFCCR_CCM;
+#endif
+
+ /* Set CLUT size */
+
+ pfccrreg |= DMA2D_xGPFCCR_CS(DMA2D_CLUT_SIZE);
+
+ /* Set the CLUT memory address */
+
+ putreg32((uint32_t) layer->clut, stm32_cmar_layer_t[lid]);
+
+ /* Start async clut loading */
+
+ stm32_dma2d_loadclut(stm32_pfccr_layer_t[lid]);
+ }
+#endif
+
+ if (blendmode & DMA2D_BLEND_NONE)
+ {
+ /* No blend operation */
+
+ pfccrreg |= DMA2D_xGPFCCR_AM(STM32_DMA2D_PFCCR_AM_NONE);
+ }
+ else
+ {
+ /* Set alpha value */
+
+ pfccrreg |= DMA2D_xGPFCCR_ALPHA(layer->alpha);
+
+ /* Set alpha mode */
+
+ if (layer->blendmode & DMA2D_BLEND_ALPHA)
+ {
+ /* Blend with constant alpha */
+
+ pfccrreg |= DMA2D_xGPFCCR_AM(STM32_DMA2D_PFCCR_AM_CONST);
+ }
+ else if (layer->blendmode & DMA2D_BLEND_PIXELALPHA)
+ {
+ /* Blend with pixel alpha value */
+
+ pfccrreg |= DMA2D_xGPFCCR_AM(STM32_DMA2D_PFCCR_AM_PIXEL);
+ }
+ }
+
+ putreg32(pfccrreg, stm32_pfccr_layer_t[lid]);
+}
+
+/******************************************************************************
* Public Functions
******************************************************************************/
/******************************************************************************
+ * Name: stm32_dma2dgetvideoinfo
+ *
+ * Description:
+ * Get video information about the layer
+ *
+ * Parameter:
+ * layer - Reference to the layer control structure
+ * vinfo - Reference to the video info structure
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dgetvideoinfo(FAR struct dma2d_layer_s *layer,
+ FAR struct fb_videoinfo_s *vinfo)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, vinfo=%p\n", layer, vinfo);
+
+ if (stm32_dma2d_lvalidate(priv) && vinfo)
+ {
+ sem_wait(priv->lock);
+ memcpy(vinfo, &priv->vinfo, sizeof(struct fb_videoinfo_s));
+ sem_post(priv->lock);
+
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -ENOSYS;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2dgetplaneinfo
+ *
+ * Description:
+ * Get plane information about the layer
+ *
+ * Parameter:
+ * layer - Reference to the layer control structure
+ * planeno - Number of the plane
+ * pinfo - Reference to the plane info structure
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dgetplaneinfo(FAR struct dma2d_layer_s *layer, int planeno,
+ FAR struct fb_planeinfo_s *pinfo)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, planeno=%d, pinfo=%p\n", layer, planeno, pinfo);
+
+ if (stm32_dma2d_lvalidate(priv) && pinfo && planeno == 0)
+ {
+ sem_wait(priv->lock);
+ memcpy(pinfo, &priv->pinfo, sizeof(struct fb_planeinfo_s));
+ sem_post(priv->lock);
+
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2dgetlid
+ *
+ * Description:
+ * Get a specific layer identifier.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * lid - Reference to store the layer id
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dgetlid(FAR struct dma2d_layer_s *layer, int *lid)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, lid=%p\n", layer, lid);
+
+ if (stm32_dma2d_lvalidate(priv) && lid)
+ {
+ sem_wait(priv->lock);
+ *lid = priv->lid;
+ sem_post(priv->lock);
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+#ifdef CONFIG_STM32_DMA2D_L8
+/******************************************************************************
+ * Name: stm32_dma2dsetclut
+ *
+ * Description:
+ * Configure layer clut (color lookup table).
+ * Non clut is defined during initializing.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * cmap - color lookup table with up the 256 entries
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dsetclut(FAR struct dma2d_layer_s *layer,
+ const FAR struct fb_cmap_s *cmap)
+{
+ int ret;
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, cmap=%p\n", layer, cmap);
+
+ if (stm32_dma2d_lvalidate(priv) && cmap)
+ {
+ sem_wait(priv->lock);
+
+#ifdef CONFIG_STM32_LTDC_INTERFACE
+ if (priv->lid < DMA2D_SHADOW_LAYER)
+ {
+ /* Update the shared color lookup table.
+ *
+ * Background:
+ *
+ * We share the same memory region of the clut table with the LTDC
+ * driver. (see stm32_dma2dinitltdc). This is important because any
+ * changes to the framebuffer and color lookup table by the ltdc
+ * related dma2d layer should also effects to the ltdc visibility,
+ * except operation settings, alpha and blendmode.
+ *
+ * But we can not only update the clut memory region. The LTDC driver
+ * also must update they own LTDC clut register to make the changes
+ * visible. Using the LTDC interface to update the clut table will
+ * also update the clut table of the related dma2d layer.
+ */
+
+ FAR struct ltdc_layer_s *ltdc =
+ g_ltdc_layer.layer[DMA2D_SHADOW_LAYER_L1].ltdc;
+
+ ret = ltdc->setclut(ltdc, cmap);
+
+ sem_post(priv->lock);
+
+ return ret;
+ }
+#endif
+
+ if (priv->fmt != DMA2D_PF_L8)
+ {
+ gdbg("Error: CLUT is not supported for the pixel format: %d\n",
+ priv->vinfo.fmt);
+ ret = -EINVAL;
+ }
+ else if (cmap->first >= STM32_DMA2D_NCLUT)
+ {
+ gdbg("Error: only %d color table entries supported\n",
+ STM32_DMA2D_NCLUT);
+ ret = -EINVAL;
+ }
+ else
+ {
+ uint32_t *clut;
+ int n;
+
+ clut = priv->clut;
+
+ for (n = cmap->first; n < cmap->len && n < STM32_DMA2D_NCLUT; n++)
+ {
+ /* Update the layer clut entry */
+
+#ifndef CONFIG_FB_TRANSPARENCY
+ uint8_t *clut888 = (uint8_t*)clut;
+ uint16_t offset = 3 * n;
+
+ clut888[offset] = cmap->blue[n];
+ clut888[offset + 1] = cmap->green[n];
+ clut888[offset + 2] = cmap->red[n];
+
+ regvdbg("n=%d, red=%02x, green=%02x, blue=%02x\n", n,
+ clut888[offset], clut888[offset + 1],
+ clut888[offset + 2]);
+#else
+ clut[n] = (uint32_t)DMA2D_CLUT_RED(cmap->transp[n]) |
+ (uint32_t)DMA2D_CLUT_GREEN(cmap->red[n]) |
+ (uint32_t)DMA2D_CLUT_GREEN(cmap->green[n]) |
+ (uint32_t)DMA2D_CLUT_BLUE(cmap->blue[n]);
+
+ regvdbg("n=%d, alpha=%02x, red=%02x, green=%02x, blue=%02x\n", n,
+ DMA2D_CLUT_ALPHA(cmap->alpha[n]),
+ DMA2D_CLUT_RED(cmap->red[n]),
+ DMA2D_CLUT_GREEN(cmap->green[n]),
+ DMA2D_CLUT_BLUE(cmap->blue[n]));
+#endif
+ }
+
+
+ ret = OK;
+ }
+
+ sem_post(priv->lock);
+ return ret;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2dgetclut
+ *
+ * Description:
+ * Get configured layer clut (color lookup table).
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * cmap - Reference to valid color lookup table accept up the 256 color
+ * entries
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dgetclut(FAR struct dma2d_layer_s *layer,
+ FAR struct fb_cmap_s *cmap)
+{
+ int ret;
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, cmap=%p\n", layer, cmap);
+
+ if (stm32_dma2d_lvalidate(priv) && cmap)
+ {
+ sem_wait(priv->lock);
+
+ if (priv->fmt != DMA2D_PF_L8)
+ {
+ gdbg("Error: CLUT is not supported for the pixel format: %d\n",
+ priv->vinfo.fmt);
+ ret = -EINVAL;
+ }
+ else if (cmap->first >= STM32_DMA2D_NCLUT)
+ {
+ gdbg("Error: only %d color table entries supported\n",
+ STM32_DMA2D_NCLUT);
+ ret = -EINVAL;
+ }
+ else
+ {
+ /* Copy from the layer clut */
+
+ uint32_t *clut;
+ int n;
+
+ clut = priv->clut;
+
+ for (n = cmap->first; n < cmap->len && n < STM32_DMA2D_NCLUT; n++)
+ {
+#ifndef CONFIG_FB_TRANSPARENCY
+ uint8_t *clut888 = (uint8_t*)clut;
+ uint16_t offset = 3 * n;
+
+ cmap->blue[n] = clut888[offset];
+ cmap->green[n] = clut888[offset + 1];
+ cmap->red[n] = clut888[offset + 2];
+
+ regvdbg("n=%d, red=%02x, green=%02x, blue=%02x\n", n,
+ clut888[offset], clut888[offset + 1],
+ clut888[offset + 2]);
+#else
+ cmap->transp[n] = (uint8_t)DMA2D_CMAP_ALPHA(clut[n]);
+ cmap->red[n] = (uint8_t)DMA2D_CMAP_RED(clut[n]);
+ cmap->green[n] = (uint8_t)DMA2D_CMAP_GREEN(clut[n]);
+ cmap->blue[n] = (uint8_t)DMA2D_CMAP_BLUE(clut[n]);
+
+ regvdbg("n=%d, alpha=%02x, red=%02x, green=%02x, blue=%02x\n", n,
+ DMA2D_CMAP_ALPHA(clut[n]), DMA2D_CMAP_RED(clut[n]),
+ DMA2D_CMAP_GREEN(clut[n]), DMA2D_CMAP_BLUE(clut[n]));
+#endif
+ }
+
+ ret = OK;
+ }
+
+ sem_post(priv->lock);
+
+ return ret;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+#endif
+
+/******************************************************************************
+ * Name: stm32_dma2dsetalpha
+ *
+ * Description:
+ * Configure layer alpha value factor into blend operation.
+ * During the layer blend operation the source alpha value is multiplied
+ * with this alpha value. If the source color format doesn't support alpha
+ * channel (e.g. non ARGB8888) this alpha value will be used as constant
+ * alpha value for blend operation.
+ * Default value during initializing: 0xff
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * alpha - Alpha value
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dsetalpha(FAR struct dma2d_layer_s *layer, uint8_t alpha)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, alpha=%02x\n", layer, alpha);
+
+ if (stm32_dma2d_lvalidate(priv))
+ {
+ sem_wait(priv->lock);
+ priv->alpha = alpha;
+ sem_post(priv->lock);
+
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2dgetalpha
+ *
+ * Description:
+ * Get configured layer alpha value factor for blend operation.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * alpha - Reference to store the alpha value
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ *****************************************************************************/
+
+static int stm32_dma2dgetalpha(FAR struct dma2d_layer_s *layer, uint8_t *alpha)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, alpha=%p\n", layer, alpha);
+
+ if (stm32_dma2d_lvalidate(priv))
+ {
+ sem_wait(priv->lock);
+ *alpha = priv->alpha;
+ sem_post(priv->lock);
+
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/******************************************************************************
+ * Name: stm32_dma2dsetblendmode
+ *
+ * Description:
+ * Configure blend mode of the layer.
+ * Default mode during initializing: DMA2D_BLEND_NONE
+ * Blendmode is active after next update.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * mode - Blend mode (see DMA2D_BLEND_*)
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ * Procedure information:
+ * DMA2D_BLEND_NONE:
+ * Informs the driver to disable all blend operation for the given layer.
+ * That means the layer is opaque.
+ *
+ * DMA2D_BLEND_ALPHA:
+ * Informs the driver to enable alpha blending for the given layer.
+ *
+ * DMA2D_BLEND_PIXELALPHA:
+ * Informs the driver to use the pixel alpha value of the layer instead
+ * the constant alpha value. This is only useful for ARGB8888
+ * color format.
+ *
+ ******************************************************************************/
+
+static int stm32_dma2dsetblendmode(FAR struct dma2d_layer_s *layer,
+ uint32_t mode)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, mode=%08x\n", layer, mode);
+
+ if (stm32_dma2d_lvalidate(priv))
+ {
+ sem_wait(priv->lock);
+ priv->blendmode = mode;
+ sem_post(priv->lock);
+
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/******************************************************************************
+ * Name: stm32_getblendmode
+ *
+ * Description:
+ * Get configured blend mode of the layer.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * mode - Reference to store the blend mode
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ *****************************************************************************/
+
+static int stm32_dma2dgetblendmode(FAR struct dma2d_layer_s *layer,
+ uint32_t *mode)
+{
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, mode=%p\n", layer, mode);
+
+ if (stm32_dma2d_lvalidate(priv) && mode)
+ {
+ sem_wait(priv->lock);
+ *mode = priv->blendmode;
+ sem_post(priv->lock);
+
+ return OK;
+ }
+
+ gdbg("ERROR: Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/******************************************************************************
* Name: stm32_dma2dblit
*
* Description:
- * Copy selected area from a background layer to selected position of the
- * foreground layer. Copies the result to the destination layer.
+ * Copy selected area from a source layer to selected position of the
+ * destination layer.
*
* Parameter:
* dest - Valid reference to the destination layer
- * fore - Valid reference to the foreground layer
- * forexpos - Valid selected x target position of the destination layer
- * foreypos - Valid selected y target position of the destination layer
- * back - Valid reference to the background layer
- * backarea - Valid reference to the selected area of the background layer
+ * destxpos - Valid selected x position of the destination layer
+ * destypos - Valid selected y position of the destination layer
+ * src - Valid reference to the source layer
+ * srcarea - Valid reference to the selected area of the source layer
*
* Return:
- * OK - On success
- * -EINVAL - On error
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * source area outside the visible area of the destination layer.
+ * (The visible area usually represents the display size)
+ * -ECANCELED - Operation cancelled, something goes wrong.
*
****************************************************************************/
-int stm32_dma2dblit(FAR struct stm32_ltdc_s *dest,
- FAR struct stm32_ltdc_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct stm32_ltdc_s *back,
- FAR const struct ltdc_area_s *backarea)
+static int stm32_dma2dblit(FAR struct dma2d_layer_s *dest,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *src,
+ FAR const struct ltdc_area_s *srcarea)
{
- gdbg("Not implemented");
- return -ENOSYS;
+ uint32_t mode;
+ int ret;
+ FAR struct stm32_dma2d_s * destlayer = (FAR struct stm32_dma2d_s *)dest;
+ FAR struct stm32_dma2d_s * srclayer = (FAR struct stm32_dma2d_s *)src;
+
+ gvdbg("dest=%p, destxpos=%d, destypos=%d, src=%p, srcarea=%p\n",
+ dest, destxpos, destypos, src, srcarea);
+
+ if (stm32_dma2d_lvalidatesize(destlayer, destxpos, destypos, srcarea) &&
+ stm32_dma2d_lvalidatesize(srclayer, srcarea->xpos,
+ srcarea->ypos, srcarea))
+ {
+ sem_wait(destlayer->lock);
+
+ /* Set output pfc */
+
+ ret = stm32_dma2d_loutpfc(destlayer);
+
+ if (ret == OK)
+ {
+ /* Set foreground pfc */
+
+ stm32_dma2d_lpfc(srclayer, DMA2D_LAYER_LFORE, DMA2D_BLEND_NONE);
+
+ /* Set foreground fifo */
+
+ stm32_dma2d_lfifo(srclayer, DMA2D_LAYER_LFORE,
+ srcarea->xpos, srcarea->ypos, srcarea);
+
+ /* Set output fifo */
+
+ stm32_dma2d_lfifo(destlayer, DMA2D_LAYER_LOUT,
+ destxpos, destypos, srcarea);
+
+ /* Set number of lines and pixel per line */
+
+ stm32_dma2d_llnr(destlayer, srcarea);
+
+ /* Set dma2d mode for blit operation */
+
+ if (destlayer->fmt == srclayer->fmt)
+ {
+ /* Blit without pfc */
+
+ mode = STM32_DMA2D_CR_MODE_BLIT;
+ }
+ else
+ {
+ /* Blit with pfc */
+
+ mode = STM32_DMA2D_CR_MODE_BLITPFC;
+ }
+
+ stm32_dma2d_control(mode, STM32_DMA2D_CR_MODE_CLEAR);
+
+ /* Start DMA2D and wait until completed */
+
+ ret = stm32_dma2d_start();
+
+ if (ret != OK)
+ {
+ ret = -ECANCELED;
+ gdbg("ERROR: Returning ECANCELED\n");
+ }
+ }
+
+ sem_post(destlayer->lock);
+ }
+ else
+ {
+ ret = -EINVAL;
+ gdbg("ERROR: Returning EINVAL\n");
+ }
+
+ return ret;
}
/****************************************************************************
- *
* Name: stm32_dma2dblend
*
* Description:
- * Blends the selected area from a background layer with selected position of
- * the foreground layer. Blends the result with the destination layer.
- * Note! This is the same as the blit operation but with blending depending on
- * the blendmode settings of the layer.
+ * Blends the selected area from a background layer with selected position
+ * of the foreground layer. Copies the result to the selected position of
+ * the destination layer. Note! The content of the foreground and background
+ * layer keeps unchanged as long destination layer is unequal to the
+ * foreground and background layer.
*
* Parameter:
- * dest - Valid reference to the destination layer
- * fore - Valid reference to the foreground layer
- * forexpos - Valid selected x target position of the destination layer
- * foreypos - Valid selected y target position of the destination layer
- * back - Valid reference to the background layer
- * backarea - Valid reference to the selected area of the background layer
+ * dest - Reference to the destination layer
+ * fore - Reference to the foreground layer
+ * forexpos - Selected x target position of the foreground layer
+ * foreypos - Selected y target position of the foreground layer
+ * back - Reference to the background layer
+ * backarea - Reference to the selected area of the background layer
*
* Return:
- * OK - On success
- * -EINVAL - On error
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * source area outside the visible area of the destination layer.
+ * (The visible area usually represents the display size)
+ * -ECANCELED - Operation cancelled, something goes wrong.
*
****************************************************************************/
-int stm32_dma2dblend(FAR struct stm32_ltdc_s *dest,
- FAR struct stm32_ltdc_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct stm32_ltdc_s *back,
- FAR const struct ltdc_area_s *backarea)
+static int stm32_dma2dblend(FAR struct dma2d_layer_s *dest,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *fore,
+ fb_coord_t forexpos, fb_coord_t foreypos,
+ FAR const struct dma2d_layer_s *back,
+ FAR const struct ltdc_area_s *backarea)
{
- gdbg("Not implemented");
- return -ENOSYS;
+ int ret;
+ FAR struct stm32_dma2d_s * destlayer = (FAR struct stm32_dma2d_s *)dest;
+ FAR struct stm32_dma2d_s * forelayer = (FAR struct stm32_dma2d_s *)fore;
+ FAR struct stm32_dma2d_s * backlayer = (FAR struct stm32_dma2d_s *)back;
+
+ gvdbg("dest=%p, destxpos=%d, destypos=%d, "
+ "fore=%p, forexpos=%d, foreypos=%d, "
+ "back=%p, backarea=%p\n",
+ dest, destxpos, destypos, fore, forexpos, foreypos, back, backarea);
+
+ if (stm32_dma2d_lvalidatesize(destlayer, destxpos, destypos, backarea) &&
+ stm32_dma2d_lvalidatesize(forelayer, forexpos, foreypos, backarea) &&
+ stm32_dma2d_lvalidatesize(backlayer, backarea->xpos,
+ backarea->ypos, backarea))
+ {
+
+ sem_wait(destlayer->lock);
+
+ /* Set output pfc */
+
+ ret = stm32_dma2d_loutpfc(destlayer);
+
+ if (ret == OK)
+ {
+ /* Set background pfc */
+
+ stm32_dma2d_lpfc(backlayer, DMA2D_LAYER_LBACK, backlayer->blendmode);
+
+ /* Set foreground pfc */
+
+ stm32_dma2d_lpfc(forelayer, DMA2D_LAYER_LFORE, forelayer->blendmode);
+
+ /* Set background fifo */
+
+ stm32_dma2d_lfifo(backlayer, DMA2D_LAYER_LBACK,
+ backarea->xpos, backarea->ypos, backarea);
+
+ /* Set foreground fifo */
+
+ stm32_dma2d_lfifo(forelayer, DMA2D_LAYER_LFORE,
+ forexpos, foreypos, backarea);
+
+ /* Set output fifo */
+
+ stm32_dma2d_lfifo(destlayer, DMA2D_LAYER_LOUT,
+ destxpos, destypos, backarea);
+
+ /* Set number of lines and pixel per line */
+
+ stm32_dma2d_llnr(destlayer, backarea);
+
+ /* Set watermark */
+
+ /* Enable DMA2D blender */
+
+ stm32_dma2d_control(STM32_DMA2D_CR_MODE_BLEND,
+ STM32_DMA2D_CR_MODE_CLEAR);
+
+ /* Start DMA2D and wait until completed */
+
+ ret = stm32_dma2d_start();
+
+ if (ret != OK)
+ {
+ ret = -ECANCELED;
+ gdbg("ERROR: Returning ECANCELED\n");
+ }
+ }
+
+ sem_post(destlayer->lock);
+ }
+ else
+ {
+ ret = -EINVAL;
+ gdbg("ERROR: Returning EINVAL\n");
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: stm32_dma2dfillarea
+ *
+ * Description:
+ * Fill the selected area of the whole layer with a specific color.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * area - Reference to the valid area structure select the area
+ * color - Color to fill the selected area. Color must be formatted
+ * according to the layer pixel format.
+ *
+ * Return:
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * area outside the visible area of the layer.
+ * -ECANCELED - Operation cancelled, something goes wrong.
+ *
+ ****************************************************************************/
+
+static int stm32_dma2dfillarea(FAR struct dma2d_layer_s *layer,
+ FAR const struct ltdc_area_s *area,
+ uint32_t color)
+{
+ int ret;
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ gvdbg("layer=%p, area=%p, color=%08x\n", layer, area, color);
+
+ if (stm32_dma2d_lvalidatesize(priv, area->xpos, area->ypos, area))
+ {
+
+ sem_wait(priv->lock);
+
+ /* Set output pfc */
+
+ ret = stm32_dma2d_loutpfc(priv);
+
+ if (ret == OK)
+ {
+ /* Set output fifo */
+
+ stm32_dma2d_lfifo(priv, DMA2D_LAYER_LOUT,
+ area->xpos, area->ypos, area);
+
+ /* Set the output color register */
+
+ stm32_dma2d_lcolor(priv, DMA2D_LAYER_LOUT, color);
+
+ /* Set number of lines and pixel per line */
+
+ stm32_dma2d_llnr(priv, area);
+
+ /* Set register to memory transfer */
+
+ stm32_dma2d_control(STM32_DMA2D_CR_MODE_COLOR,
+ STM32_DMA2D_CR_MODE_CLEAR);
+
+ /* Start DMA2D and wait until completed */
+
+ ret = stm32_dma2d_start();
+
+ if (ret != OK)
+ {
+ ret = -ECANCELED;
+ gdbg("ERROR: Returning ECANCELED\n");
+ }
+ }
+
+ sem_post(priv->lock);
+ }
+ else
+ {
+ ret = -EINVAL;
+ gdbg("ERROR: Returning EINVAL\n");
+ }
+
+ return ret;
+}
+
+/*******************************************************************************
+ * Name: up_dma2dgetlayer
+ *
+ * Description:
+ * Get a dma2d layer structure by the layer identifier
+ *
+ * Parameter:
+ * lid - Layer identifier
+ *
+ * Return:
+ * Reference to the dma2d layer control structure on success or Null if no
+ * related exist.
+ *
+ ******************************************************************************/
+
+FAR struct dma2d_layer_s * up_dma2dgetlayer(int lid)
+{
+ if (lid < DMA2D_LAYER_NSIZE)
+ {
+ FAR struct stm32_dma2d_s *priv;
+ sem_wait(&g_lock);
+ priv = g_layers[lid];
+ sem_post(&g_lock);
+
+ return &priv->dma2d;
+ }
+
+ gdbg("ERROR: EINVAL, Unknown layer identifier\n");
+ errno = EINVAL;
+ return NULL;
+}
+
+/******************************************************************************
+ * Name: up_dma2dcreatelayer
+ *
+ * Description:
+ * Create a new dma2d layer object to interact with the dma2d controller
+ *
+ * Parameter:
+ * width - Layer width
+ * height - Layer height
+ * fmt - Pixel format of the layer
+ *
+ * Return:
+ * On success - A valid dma2d layer reference
+ * On error - NULL and errno is set to
+ * -EINVAL if one of the parameter is invalid
+ * -ENOMEM if no memory available or exceeds
+ * CONFIG_STM32_DMA2D_NLAYERS
+ *
+ ******************************************************************************/
+
+FAR struct dma2d_layer_s *up_dma2dcreatelayer(fb_coord_t width,
+ fb_coord_t height,
+ uint8_t fmt)
+{
+ int ret;
+ int lid;
+ uint8_t fmtmap;
+ uint8_t bpp = 0;
+ FAR struct stm32_dma2d_s *layer = NULL;
+
+ gvdbg("width=%d, height=%d, fmt=%02x \n", width, height, fmt);
+
+ /* Validate if pixel format supported */
+
+ ret = stm32_dma2d_pixelformat(fmt, &fmtmap);
+
+ if (ret != OK)
+ {
+ errno = ret;
+ return NULL;
+ }
+
+ ret = stm32_dma2d_bpp(fmt, &bpp);
+
+ sem_wait(&g_lock);
+
+ /* Get a free layer identifier */
+
+ lid = stm32_dma2d_lfreelid();
+
+ if (lid >= 0)
+ {
+ layer = stm32_dma2d_lalloc();
+
+ if (layer)
+ {
+ uint32_t fblen;
+ void *fbmem;
+ fb_coord_t stride;
+
+ /* Stride calculation for the supported formats */
+
+ stride = width * bpp / 8;
+
+ /* Calculate buffer size */
+
+ fblen = stride * height;
+
+ /* Allocate 32-bit aligned memory for the layer buffer. As reported in
+ * mm_memalign 8-byte alignment is guaranteed by normal malloc calls.
+ * We have also ensure memory is allocated from the SRAM1/2/3 block.
+ * The CCM block is only accessible through the D-BUS but not by
+ * the AHB-BUS. Ensure that CONFIG_STM32_CCMEXCLUDE is set!
+ */
+
+ fbmem = kmm_zalloc(fblen);
+
+ if (fbmem)
+ {
+ FAR struct fb_videoinfo_s *vinfo = &layer->vinfo;
+ FAR struct fb_planeinfo_s *pinfo = &layer->pinfo;
+
+ /* Initialize dma2d structure */
+
+ stm32_dma2d_linit(layer, lid, fmtmap);
+
+ /* Initialize the videoinfo structure */
+
+ vinfo->fmt = fmt;
+ vinfo->xres = width;
+ vinfo->yres = height;
+ vinfo->nplanes = 1;
+
+ /* Initialize the planeinfo structure */
+
+ pinfo->fbmem = fbmem;
+ pinfo->fblen = fblen;
+ pinfo->stride = stride;
+ pinfo->bpp = bpp;
+
+ /* Bind the layer to the identifier */
+
+ g_layers[lid] = layer;
+ }
+ else
+ {
+ /* free the layer struture */
+
+ kmm_free(layer);
+ gdbg("ERROR: ENOMEM, Unable to allocate layer buffer\n");
+ errno = ENOMEM;
+ }
+ }
+ else
+ {
+ gdbg("ERROR: ENOMEM, unable to allocate layer structure\n");
+ errno = ENOMEM;
+ }
+ }
+ else
+ {
+ gdbg("ERROR: EINVAL, no free layer available\n");
+ errno = EINVAL;
+ }
+
+ sem_post(&g_lock);
+ return (FAR struct dma2d_layer_s *)layer;
+}
+
+/******************************************************************************
+ * Name: up_dma2dremovelayer
+ *
+ * Description:
+ * Remove and deallocate the dma2d layer
+ *
+ * Parameter:
+ * layer - Reference to the layer to remove
+ *
+ * Return:
+ * On success - OK
+ * On error - -EINVAL
+ *
+ *****************************************************************************/
+
+int up_dma2dremovelayer(FAR struct dma2d_layer_s *layer)
+{
+ int ret = -EINVAL;
+ FAR struct stm32_dma2d_s *priv = (FAR struct stm32_dma2d_s *)layer;
+
+ /* Check if the layer is valid and unlike a ltdc related layer */
+
+ if (stm32_dma2d_lvalidate(priv) && priv->lid >= DMA2D_SHADOW_LAYER)
+ {
+ sem_wait(priv->lock);
+
+ /* Check also if the layer id is valid to the layer reference */
+
+ if (priv == g_layers[priv->lid])
+ {
+ int lid = priv->lid;
+
+ kmm_free(priv->pinfo.fbmem);
+#ifdef HAVE_CCM_HEAP
+ if (((uint32_t)priv & 0xF0000000) == 0x10000000)
+ {
+ ccm_free(priv);
+ }
+ else
+ {
+ kmm_free(priv);
+ }
+#else
+ kmm_free(priv);
+#endif
+ g_layers[lid] = NULL;
+ ret = OK;
+ }
+
+ sem_post(priv->lock);
+ }
+
+ return ret;
}
/******************************************************************************
@@ -166,6 +2157,63 @@ int stm32_dma2dblend(FAR struct stm32_ltdc_s *dest,
int up_dma2dinitialize(void)
{
+ dbg("Initialize DMA2D driver\n");
+
+ if (g_initialized == false)
+ {
+ /* Abort current dma2d data transfer */
+
+ up_dma2duninitialize();
+
+ /* Enable dma2d is done in rcc_enableahb1, see
+ * arch/arm/src/stm32/stm32f40xxx_rcc.c
+ */
+
+ /* Initialize the DMA2D semaphore that enforces mutually exclusive access
+ * to the driver
+ */
+
+ sem_init(&g_lock, 0, 1);
+
+ /* Initialize the semaphore for interrupt handling */
+
+ sem_init(g_interrupt.sem, 0, 0);
+
+#ifdef CONFIG_STM32_DMA2D_L8
+ /* Enable dma2d transfer and clut loading interrupts only */
+
+ stm32_dma2d_control(DMA2D_CR_TCIE|DMA2D_CR_CTCIE, DMA2D_CR_TEIE|
+ DMA2D_CR_TWIE|DMA2D_CR_CAEIE||DMA2D_CR_CEIE);
+#else
+ /* Enable dma transfer interrupt only */
+
+ stm32_dma2d_control(DMA2D_CR_TCIE, DMA2D_CR_TEIE|DMA2D_CR_TWIE|
+ DMA2D_CR_CAEIE|DMA2D_CR_CTCIE|DMA2D_CR_CEIE);
+#endif
+
+ /* Attach DMA2D interrupt vector */
+
+ (void)irq_attach(g_interrupt.irq, stm32_dma2dirq);
+
+ /* Enable the IRQ at the NVIC */
+
+ up_enable_irq(g_interrupt.irq);
+
+ /* Initialize the dma2d layer for ltdc binding */
+
+#ifdef DMA2D_SHADOW_LAYER_L1
+ g_layers[DMA2D_SHADOW_LAYER_L1] =
+ &g_ltdc_layer.layer[DMA2D_SHADOW_LAYER_L1].dma2ddev;
+#endif
+#ifdef DMA2D_SHADOW_LAYER_L2
+ g_layers[DMA2D_SHADOW_LAYER_L2] =
+ &g_ltdc_layer.layer[DMA2D_SHADOW_LAYER_L2].dma2ddev;
+#endif
+ /* Set initialized state */
+
+ g_initialized = true;
+ }
+
return OK;
}
@@ -179,4 +2227,86 @@ int up_dma2dinitialize(void)
void up_dma2duninitialize(void)
{
+ /* Disable DMA2D interrupts */
+
+ up_disable_irq(g_interrupt.irq);
+ irq_detach(g_interrupt.irq);
+
+ /* Cleanup all layers */
+
+ stm32_dma2d_llayerscleanup();
+
+ /* Abort current dma2d transfer */
+
+ stm32_dma2d_control(DMA2D_CR_ABORT, 0);
+
+ /* Set initialized state */
+
+ g_initialized = false;
+}
+
+#ifdef CONFIG_STM32_LTDC_INTERFACE
+/******************************************************************************
+ * Name: stm32_dma2dinitltdc
+ *
+ * Description:
+ * Get a reference to the dma2d layer coupled with the ltdc layer.
+ * It not intends to use this by user space applications.
+ * It resolves the following requirements:
+ * 1. Share the color lookup table
+ * 2. Share the planeinfo information
+ * 3. Share the videoinfo information
+ *
+ * Parameter:
+ * layer - a valid reference to the low level ltdc layer structure
+ * clut - a pointer to a valid memory region to hold 256 clut colors
+ *
+ * Return:
+ * On success - A valid dma2d layer reference
+ * On error - NULL and errno is set to
+ * -EINVAL if one of the parameter is invalid
+ *
+ ******************************************************************************/
+
+FAR struct dma2d_layer_s * stm32_dma2dinitltdc(FAR struct stm32_ltdc_s *layer)
+{
+ int ret;
+ uint8_t fmt = 0;
+ FAR struct stm32_ltdc_dma2d_s *priv;
+
+ gvdbg("layer=%p\n", layer);
+ DEBUGASSERT(layer && layer->lid >= 0 && layer->lid < DMA2D_SHADOW_LAYER);
+
+ ret = stm32_dma2d_pixelformat(layer->vinfo.fmt, &fmt);
+
+ if (ret != OK)
+ {
+ dbg("Returning -EINVAL, unsupported pixel format: %d\n",
+ layer->vinfo.fmt);
+ errno = -EINVAL;
+ return NULL;
+ }
+
+ priv = &g_ltdc_layer.layer[layer->lid];
+
+ stm32_dma2d_linit(&priv->dma2ddev, layer->lid, fmt);
+
+ memcpy(&priv->dma2ddev.vinfo, &layer->vinfo, sizeof(struct fb_videoinfo_s));
+ memcpy(&priv->dma2ddev.pinfo, &layer->pinfo, sizeof(struct fb_planeinfo_s));
+
+#ifdef CONFIG_STM32_DMA2D_L8
+ /* Verifies that the ltdc layer has a clut. This ensures that DMA2D driver can
+ * support clut format but the LTDC driver does not and vice versa.
+ */
+
+ if (layer->vinfo.fmt == FB_FMT_RGB8)
+ {
+ priv->dma2ddev.clut = layer->clut;
+ priv->ltdc = stm32_ltdcgetlayer(layer->lid);
+ DEBUGASSERT(priv->ltdc != NULL);
+ }
+#endif
+
+ return &priv->dma2ddev.dma2d;
}
+#endif /* CONFIG_STM32_LTDC_INTERFACE */
diff --git a/nuttx/arch/arm/src/stm32/stm32_dma2d.h b/nuttx/arch/arm/src/stm32/stm32_dma2d.h
index adb86db03..4110c5491 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dma2d.h
+++ b/nuttx/arch/arm/src/stm32/stm32_dma2d.h
@@ -1,7 +1,7 @@
/******************************************************************************
* arch/arm/src/stm32/stm32_dma2d.h
*
- * Copyright (C) 2014 Marco Krahl. All rights reserved.
+ * Copyright (C) 2014-2015 Marco Krahl. All rights reserved.
* Author: Marco Krahl <ocram.lhark@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,7 +43,6 @@
#include <nuttx/config.h>
#include <nuttx/video/fb.h>
#include <arch/chip/ltdc.h>
-#include "stm32_ltdc.h"
#ifdef CONFIG_STM32_DMA2D
/******************************************************************************
@@ -62,86 +61,30 @@
* Public Functions
******************************************************************************/
+# ifdef CONFIG_STM32_LTDC_INTERFACE
/******************************************************************************
- * Name: stm32_dma2dblit
+ * Name: stm32_dma2dinitltdc
*
* Description:
- * Copy selected area from a background layer to selected position of the
- * foreground layer. Copies the result to the destination layer.
+ * Get a reference to the dma2d layer coupled with the ltdc layer.
+ * It not intends to use this function by user space applications.
+ * It resolves the following requirements:
+ * 1. Share the color lookup table
+ * 2. Share the planeinfo information
+ * 3. Share the videoinfo information
*
* Parameter:
- * dest - Valid reference to the destination layer
- * fore - Valid reference to the foreground layer
- * forexpos - Valid selected x target position of the destination layer
- * foreypos - Valid selected y target position of the destination layer
- * back - Valid reference to the background layer
- * backarea - Valid reference to the selected area of the background layer
+ * layer - a valid reference to the low level ltdc layer structure
*
* Return:
- * OK - On success
- * -EINVAL - On error
+ * On success - A valid dma2d layer reference
+ * On error - NULL and errno is set to
+ * -EINVAL if one of the parameter is invalid
*
******************************************************************************/
-int stm32_dma2dblit(FAR struct stm32_ltdc_s *dest,
- FAR struct stm32_ltdc_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct stm32_ltdc_s *back,
- FAR const struct ltdc_area_s *backarea);
-
-/******************************************************************************
- *
- * Name: stm32_dma2dblend
- *
- * Description:
- * Blends the selected area from a background layer with selected position of
- * the foreground layer. Blends the result with the destination layer.
- * Note! This is the same as the blit operation but with blending depending on
- * the blendmode settings of the layer.
- *
- * Parameter:
- * dest - Valid reference to the destination layer
- * fore - Valid reference to the foreground layer
- * forexpos - Valid selected x target position of the destination layer
- * foreypos - Valid selected y target position of the destination layer
- * back - Valid reference to the background layer
- * backarea - Valid reference to the selected area of the background layer
- *
- * Return:
- * OK - On success
- * -EINVAL - On error
- *
- ******************************************************************************/
-
-int stm32_dma2dblend(FAR struct stm32_ltdc_s *dest,
- FAR struct stm32_ltdc_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct stm32_ltdc_s *back,
- FAR const struct ltdc_area_s *backarea);
-
-/******************************************************************************
- * Name: up_dma2dinitialize
- *
- * Description:
- * Initialize the dma2d controller
- *
- * Return:
- * OK - On success
- * An error if initializing failed.
- *
- ******************************************************************************/
-
-int up_dma2dinitialize(void);
-
-/******************************************************************************
- * Name: up_dma2duninitialize
- *
- * Description:
- * Uninitialize the dma2d controller
- *
- ******************************************************************************/
-
-void up_dma2duninitialize(void);
+FAR struct dma2d_layer_s * stm32_dma2dinitltdc(FAR struct stm32_ltdc_s *layer);
+# endif /* CONFIG_STM32_LTDC_INTERFACE */
#endif /* CONFIG_STM32_DMA2D */
#endif /* __ARCH_ARM_SRC_STM32_STM32_DMA2D_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_ltdc.c b/nuttx/arch/arm/src/stm32/stm32_ltdc.c
index f9fd8058d..0eeeddbb8 100644
--- a/nuttx/arch/arm/src/stm32/stm32_ltdc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_ltdc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_ltdc.c
*
- * Copyright (C) 2013-2014 Ken Pettit. All rights reserved.
+ * Copyright (C) 2013-2015 Ken Pettit. All rights reserved.
* Authors: Ken Pettit <pettitd@gmail.com>
* Marco Krahl <ocram.lhark@gmail.com>
*
@@ -48,10 +48,12 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/irq.h>
#include <nuttx/video/fb.h>
#include <nuttx/kmalloc.h>
#include <arch/chip/ltdc.h>
+#include <arch/chip/dma2d.h>
#include <arch/board/board.h>
#include "up_arch.h"
@@ -132,13 +134,6 @@
#define STM32_LTDC_GCR_DGW LTDC_GCR_DGW(BOARD_LTDC_GCR_DGW)
#define STN32_LTDC_GCR_DRW LTDC_GCR_DBW(BOARD_LTDC_GCR_DRW)
-/* IER register */
-
-#define STM32_LTDC_IER_LIE LTDC_IER_LIE
-#define STM32_LTDC_IER_FUIE !LTDC_IER_FUIE
-#define STM32_LTDC_IER_TERRIE !LTDC_IER_TERRIE
-#define STM32_LTDC_IER_RRIE LTDC_IER_RRIE
-
/* LIPCR register */
#define STM32_LTDC_LIPCR_LIPOS LTDC_LIPCR_LIPOS(STM32_LTDC_TWCR_TOTALW)
@@ -304,7 +299,8 @@
#define STM32_LTDC_BUFFER_SIZE CONFIG_STM32_LTDC_FB_SIZE
#define STM32_LTDC_BUFFER_FREE (STM32_LTDC_BUFFER_SIZE - STM32_TOTAL_FBSIZE)
-#define STM32_LTDC_BUFFER_START (CONFIG_STM32_LTDC_FB_BASE + STM32_LTDC_BUFFER_FREE/2)
+#define STM32_LTDC_BUFFER_START (CONFIG_STM32_LTDC_FB_BASE + \
+ STM32_LTDC_BUFFER_FREE/2)
#if STM32_LTDC_BUFFER_FREE < 0
# error "STM32_LTDC_BUFFER_SIZE not large enough for frame buffers"
@@ -386,23 +382,49 @@
#define STM32_LTDC_BF1_RESET 6
#define STM32_LTDC_BF2_RESET 7
-/*
- * Waits upon vertical sync
- * Note! Position is reserved in current SRCR register but not used
- */
+/* Check pixel format support by DMA2D driver */
-#define LTDC_SRCR_WAIT 4
+#ifdef CONFIG_STM32_DMA2D
+# if defined(CONFIG_STM32_LTDC_L1_L8) || \
+ defined(CONFIG_STM32_LTDC_L2_L8)
+# if !defined(CONFIG_STM32_DMA2D_L8)
+# error "DMA2D must support FB_FMT_RGB8 pixel format"
+# endif
+# endif
+# if defined(CONFIG_STM32_LTDC_L1_RGB565) || \
+ defined(CONFIG_STM32_LTDC_L2_RGB565)
+# if !defined(CONFIG_STM32_DMA2D_RGB565)
+# error "DMA2D must support FB_FMT_RGB16_565 pixel format"
+# endif
+# endif
+# if defined(CONFIG_STM32_LTDC_L1_RGB888) || \
+ defined(CONFIG_STM32_LTDC_L2_RGB888)
+# if !defined(CONFIG_STM32_DMA2D_RGB888)
+# error "DMA2D must support FB_FMT_RGB24 pixel format"
+# endif
+# endif
+#endif
/* Calculate the size of the layers clut table */
#ifdef CONFIG_FB_CMAP
-#define STM32_LTDC_CLUT_ENTRIES 256
+# if defined(CONFIG_STM32_DMA2D) && !defined(CONFIG_STM32_DMA2D_L8)
+# error "DMA2D must also support L8 CLUT pixel format if supported by LTDC"
+# endif
# ifdef STM32_LTDC_L1CMAP
-# define STM32_LAYER_CLUT_SIZE 1 * 3 * STM32_LTDC_CLUT_ENTRIES
+# ifdef CONFIG_FB_TRANSPARENCY
+# define STM32_LAYER_CLUT_SIZE STM32_LTDC_NCLUT * sizeof(uint32_t)
+# else
+# define STM32_LAYER_CLUT_SIZE STM32_LTDC_NCLUT * 3 * sizeof(uint8_t)
+# endif
# endif
# ifdef STM32_LTDC_L2CMAP
# undef STM32_LAYER_CLUT_SIZE
-# define STM32_LAYER_CLUT_SIZE 2 * 3 * STM32_LTDC_CLUT_ENTRIES
+# ifdef CONFIG_FB_TRANSPARENCY
+# define STM32_LAYER_CLUT_SIZE STM32_LTDC_NCLUT * sizeof(uint32_t) * 2
+# else
+# define STM32_LAYER_CLUT_SIZE STM32_LTDC_NCLUT * 3 * sizeof(uint8_t) * 2
+# endif
# endif
#endif
@@ -423,12 +445,21 @@
#define LTDC_L2CLUT_GREENOFFSET 1024
#define LTDC_L2CLUT_BLUEOFFSET 1280
-/* Layer rgb clut register position */
+/* Layer argb clut register position */
#define LTDC_CLUT_ADD(n) ((uint32_t)(n) << 24)
+#define LTDC_CLUT_ALPHA(n) LTDC_CLUT_ADD(n)
#define LTDC_CLUT_RED(n) ((uint32_t)(n) << 16)
#define LTDC_CLUT_GREEN(n) ((uint32_t)(n) << 8)
#define LTDC_CLUT_BLUE(n) ((uint32_t)(n) << 0)
+#define LTDC_CLUT_RGB888_MASK 0xffffff
+
+/* Layer argb cmap conversion */
+
+#define LTDC_CMAP_ALPHA(n) ((uint32_t)(n) >> 24)
+#define LTDC_CMAP_RED(n) ((uint32_t)(n) >> 16)
+#define LTDC_CMAP_GREEN(n) ((uint32_t)(n) >> 8)
+#define LTDC_CMAP_BLUE(n) ((uint32_t)(n) >> 0)
/****************************************************************************
* Private Types
@@ -463,6 +494,9 @@ struct stm32_layer_s
/* Operation */
uint8_t operation; /* Operation flags */
+#ifdef CONFIG_STM32_DMA2D
+ FAR struct dma2d_layer_s *dma2d; /* dma2d interface */
+#endif
};
/* This structure provides the state of each LTDC layer */
@@ -488,15 +522,21 @@ struct stm32_ltdcdev_s
#ifdef STM32_LAYER_CLUT_SIZE
enum stm32_clut_e
{
- LTDC_L1CLUT_RED = LTDC_L1CLUT_REDOFFSET,
- LTDC_L1CLUT_GREEN = LTDC_L1CLUT_GREENOFFSET,
- LTDC_L1CLUT_BLUE = LTDC_L1CLUT_BLUEOFFSET,
- LTDC_L2CLUT_RED = LTDC_L2CLUT_REDOFFSET,
- LTDC_L2CLUT_GREEN = LTDC_L2CLUT_GREENOFFSET,
- LTDC_L2CLUT_BLUE = LTDC_L2CLUT_BLUEOFFSET
+ LTDC_L1CLUT_OFFSET = 0,
+ LTDC_L2CLUT_OFFSET = STM32_LTDC_NCLUT * sizeof(uint32_t)
};
#endif
+/* Interrupt handling */
+
+struct stm32_interrupt_s
+{
+ bool wait; /* Informs that the task is waiting for the irq */
+ bool handled; /* Informs that an irq was handled */
+ int irq; /* irq number */
+ sem_t *sem; /* Semaphore for waiting for irq */
+};
+
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -509,15 +549,16 @@ static void stm32_ltdc_periphconfig(void);
static void stm32_ltdc_bgcolor(uint32_t rgb);
static void stm32_ltdc_dither(bool enable, uint8_t red,
uint8_t green, uint8_t blue);
-static void stm32_ltdc_interrupt(uint32_t mask, uint32_t value);
-static void stm32_ltdc_reload(uint8_t value);
+static int stm32_ltdcirq(int irq, void *context);
+static int stm32_ltdc_waitforirq(void);
+static int stm32_ltdc_reload(uint8_t value, bool waitvblank);
/* Layer and layer register operation */
static inline void stm32_ltdc_lsetopac(FAR struct stm32_layer_s *layer);
static inline void stm32_ltdc_lunsetopac(FAR struct stm32_layer_s *layer);
static inline uint8_t stm32_ltdc_lgetopac(FAR struct stm32_layer_s *layer);
-static inline bool stm32_ltdc_lvalidate(FAR struct stm32_layer_s *layer);
+static inline bool stm32_ltdc_lvalidate(FAR const struct stm32_layer_s *layer);
#ifdef CONFIG_STM32_LTDC_INTERFACE
static int stm32_ltdc_lvalidatearea(FAR struct stm32_layer_s *layer,
fb_coord_t xpos, fb_coord_t ypos,
@@ -536,10 +577,10 @@ static void stm32_ltdc_lblendmode(FAR struct stm32_layer_s *layer,
uint8_t bf1, uint8_t bf2);
#ifdef STM32_LAYER_CLUT_SIZE
-static void stm32_ltdc_cmapcpy(FAR struct fb_cmap_s *dest,
- FAR const struct fb_cmap_s *src);
-static void stm32_ltdc_lclut(FAR struct stm32_layer_s *layer);
-static void stm32_ltdc_lclutenable(FAR struct stm32_layer_s* layer, bool enable);
+static void stm32_ltdc_lclut(FAR struct stm32_layer_s *layer,
+ FAR const struct fb_cmap_s *cmap);
+static void stm32_ltdc_lclutenable(FAR struct stm32_layer_s* layer,
+ bool enable);
#endif
static void stm32_ltdc_linit(int lid);
static void stm32_ltdc_lenable(FAR struct stm32_layer_s *layer);
@@ -598,15 +639,18 @@ static int stm32_update(FAR struct ltdc_layer_s *layer, uint32_t mode);
#ifdef CONFIG_STM32_DMA2D
static int stm32_blit(FAR struct ltdc_layer_s *dest,
- FAR struct ltdc_layer_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct ltdc_layer_s *back,
- FAR const struct ltdc_area_s *backarea);
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *src,
+ FAR const struct ltdc_area_s *srcarea);
static int stm32_blend(FAR struct ltdc_layer_s *dest,
- FAR struct ltdc_layer_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct ltdc_layer_s *back,
- FAR const struct ltdc_area_s *backarea);
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *fore,
+ fb_coord_t forexpos, fb_coord_t foreypos,
+ FAR const struct dma2d_layer_s *back,
+ FAR const struct ltdc_area_s *backarea);
+static int stm32_fillarea(FAR struct ltdc_layer_s *layer,
+ FAR const struct ltdc_area_s *area,
+ uint32_t color);
#endif
#endif /* CONFIG_STM32_LTDC_INTERFACE */
@@ -652,38 +696,28 @@ static const struct fb_vtable_s g_vtable =
static sem_t g_lock;
-/* The layer active state */
+/* The semaphore for interrupt handling */
-static uint8_t g_lactive;
+static sem_t g_semirq;
-#ifdef STM32_LAYER_CLUT_SIZE
-/* The layers clut table entries */
+/* This structure provides irq handling */
-static uint8_t g_clut[STM32_LAYER_CLUT_SIZE];
-
-/* The layer 1 cmap */
-
-#ifdef STM32_LTDC_L1CMAP
-static struct fb_cmap_s g_cmap_l1 =
+static struct stm32_interrupt_s g_interrupt =
{
- .len = STM32_LTDC_CLUT_ENTRIES,
- .red = &g_clut[LTDC_L1CLUT_RED],
- .green = &g_clut[LTDC_L1CLUT_GREEN],
- .blue = &g_clut[LTDC_L1CLUT_BLUE]
+ .wait = false,
+ .handled = true,
+ .irq = STM32_IRQ_LTDCINT,
+ .sem = &g_semirq
};
-#endif
-/* The layer 2 cmap */
+/* The layer active state */
-#ifdef STM32_LTDC_L2CMAP
-static struct fb_cmap_s g_cmap_l2 =
-{
- .len = STM32_LTDC_CLUT_ENTRIES,
- .red = &g_clut[LTDC_L2CLUT_RED],
- .green = &g_clut[LTDC_L2CLUT_GREEN],
- .blue = &g_clut[LTDC_L2CLUT_BLUE]
-};
-#endif
+static uint8_t g_lactive;
+
+#ifdef STM32_LAYER_CLUT_SIZE
+/* The layers clut table entries */
+
+static uint32_t g_clut[STM32_LAYER_CLUT_SIZE];
#endif
/* The initialized state of the overall LTDC layers */
@@ -710,7 +744,7 @@ static struct stm32_ltdcdev_s g_ltdc =
.nplanes = 1
}
#ifdef STM32_LTDC_L1CMAP
- ,.cmap = &g_cmap_l1
+ ,.clut = &g_clut[LTDC_L1CLUT_OFFSET]
#endif
}
}
@@ -735,7 +769,7 @@ static struct stm32_ltdcdev_s g_ltdc =
.nplanes = 1
}
#ifdef STM32_LTDC_L2CMAP
- ,.cmap = &g_cmap_l2
+ ,.clut = &g_clut[LTDC_L2CLUT_OFFSET]
#endif
}
}
@@ -876,6 +910,10 @@ static const uintptr_t stm32_clutwr_layer_t[LTDC_NLAYERS] =
};
#endif
+/* The initialized state of the driver */
+
+static bool g_initialized;
+
/****************************************************************************
* Public Data
****************************************************************************/
@@ -1037,74 +1075,196 @@ static void stm32_ltdc_dither(bool enable,
}
/****************************************************************************
- * Name: stm32_ltdc_interrupt
+ * Name: stm32_ltdc_linepos
*
* Description:
- * Configures specific interrupt
+ * Configures line position register
+ *
+ ****************************************************************************/
+
+static void stm32_ltdc_linepos(void)
+{
+ /* Configure LTDC_LIPCR */
+
+ regvdbg("set LTDC_LIPCR=%08x\n", STM32_LTDC_LIPCR_LIPOS);
+ putreg32(STM32_LTDC_LIPCR_LIPOS, STM32_LTDC_LIPCR);
+ regvdbg("configured LTDC_LIPCR=%08x\n", getreg32(STM32_LTDC_LIPCR));
+}
+
+/****************************************************************************
+ * Name: stm32_ltdc_irqctrl
+ *
+ * Description:
+ * Control interrupts generated by the ltdc controller
*
* Parameter:
- * mask - Interrupt mask
- * value - Interrupt value
+ * setirqs - set interrupt mask
+ * clrirqs - clear interrupt mask
*
****************************************************************************/
-static void stm32_ltdc_interrupt(uint32_t mask, uint32_t value)
+static void stm32_ltdc_irqctrl(uint32_t setirqs, uint32_t clrirqs)
{
uint32_t regval;
- /* Get interrupts */
-
regval = getreg32(STM32_LTDC_IER);
- regvdbg("get LTDC_IER=%08x\n", regval);
- regval &= ~mask;
-
- /* Set interrupt */
-
- regval |= value;
+ regval &= ~clrirqs;
+ regval |= setirqs;
regvdbg("set LTDC_IER=%08x\n", regval);
putreg32(regval, STM32_LTDC_IER);
regvdbg("configured LTDC_IER=%08x\n", getreg32(STM32_LTDC_IER));
+}
- /* Configure LTDC_LIPCR */
+/****************************************************************************
+ * Name: stm32_ltdcirq
+ *
+ * Description:
+ * LTDC interrupt handler
+ *
+ ****************************************************************************/
- regvdbg("set LTDC_LIPCR=%08x\n", STM32_LTDC_LIPCR_LIPOS);
- putreg32(STM32_LTDC_LIPCR_LIPOS, STM32_LTDC_LIPCR);
- regvdbg("configured LTDC_LIPCR=%08x\n", getreg32(STM32_LTDC_LIPCR));
+static int stm32_ltdcirq(int irq, void *context)
+{
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
+
+ uint32_t regval = getreg32(STM32_LTDC_ISR);
+
+ regvdbg("irq = %d, regval = %08x\n", irq, regval);
+
+ if (regval & LTDC_ISR_RRIF)
+ {
+ /* Register reload interrupt */
+
+ /* Clear the interrupt status register */
+
+ putreg32(LTDC_ICR_CRRIF, STM32_LTDC_ICR);
+
+ /* Update the handled flag */
+
+ priv->handled = true;
+
+ /* Unlock the semaphore if locked */
+
+ if (priv->wait)
+ {
+ int ret = sem_post(priv->sem);
+
+ if (ret != OK)
+ {
+ dbg("sem_post() failed\n");
+ return ret;
+ }
+ }
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_ltdc_waitforirq
+ *
+ * Description:
+ * Helper waits until the ltdc irq occurs. In the current design That means
+ * that a register reload was been completed.
+ * Note! The caller must use this function within irqsave state.
+ *
+ * Return:
+ * OK - On success otherwise ERROR
+ *
+ ****************************************************************************/
+
+static int stm32_ltdc_waitforirq(void)
+{
+ int ret = OK;
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
+
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ /* Only waits if last enabled interrupt is currently not handled */
+
+ if (!priv->handled)
+ {
+ /* Inform the irq handler the task is able to wait for the irq */
+
+ priv->wait = true;
+
+ ret = sem_wait(priv->sem);
+
+ /* irq or an error occurs, reset the wait flag */
+
+ priv->wait = false;
+
+ if (ret != OK)
+ {
+ dbg("sem_wait() failed\n");
+ }
+ }
+
+ irqrestore(flags);
+ return ret;
}
/****************************************************************************
* Name: stm32_ltdc_reload
*
* Description:
- * Reload the layer shadow register and make layer changes visible
+ * Reload the layer shadow register and make layer changes visible.
+ * Note! The caller must ensure that a previous register reloading has been
+ * completed.
*
* Parameter:
- * value - Reload flag (e.g. upon vertical blank or immediately)
+ * value - Reload flag (e.g. upon vertical blank or immediately)
+ * waitvblank - Wait until register reload is finished
*
****************************************************************************/
-static void stm32_ltdc_reload(uint8_t value)
+static int stm32_ltdc_reload(uint8_t value, bool waitvblank)
{
- /* Check if last reload is finished */
+ int ret = OK;
+ FAR struct stm32_interrupt_s *priv = &g_interrupt;
- while ((getreg32(STM32_LTDC_SRCR) & (LTDC_SRCR_VBR|LTDC_SRCR_IMR)) != 0)
+ if (value == LTDC_SRCR_VBR)
{
+ irqstate_t flags;
+
+ /* Prepare shadow register reload for later detection by the task.
+ * At this point the last register reload must be completed. This is done
+ * in stm32_update before the next operation is triggered and manipulates
+ * the shadow register. This handling is only neccessary in the case of
+ * the application causes shadow register reload.
+ */
+
+ flags = irqsave();
+
+ ASSERT(priv->handled == true);
+
+ /* Reset the handled flag */
+
+ priv->handled = false;
+ irqrestore(flags);
}
- /* Reload shadow register */
+ /* Reloads the shadow register.
+ * Note! This will not trigger an register reload interrupt if
+ * immediately reload is set.
+ */
- regvdbg("set LTDC_SRCR=%08x\n", value & ~LTDC_SRCR_WAIT);
- putreg32(value & ~LTDC_SRCR_WAIT, STM32_LTDC_SRCR);
+ regvdbg("set LTDC_SRCR=%08x\n", value);
+ putreg32(value, STM32_LTDC_SRCR);
regvdbg("configured LTDC_SRCR=%08x\n", getreg32(STM32_LTDC_SRCR));
- /* Wait until registers reloaded */
-
- if (value & LTDC_SRCR_WAIT)
+ if (waitvblank & (value == LTDC_SRCR_VBR))
{
- while ((getreg32(STM32_LTDC_SRCR) & (value & ~LTDC_SRCR_WAIT)) != 0)
- {
- }
+ /* Wait upon vertical blanking period */
+
+ ret = stm32_ltdc_waitforirq();
}
+
+ /* Otherwise check if reload is completed before the next operation */
+
+ return ret;
}
/****************************************************************************
@@ -1123,6 +1283,26 @@ static void stm32_global_configure(void)
sem_init(&g_lock, 0, 1);
+ /* Initialize the semaphore for interrupt handling */
+
+ sem_init(g_interrupt.sem, 0, 0);
+
+ /* Attach LTDC interrupt vector */
+
+ (void)irq_attach(g_interrupt.irq, stm32_ltdcirq);
+
+ /* Enable the IRQ at the NVIC */
+
+ up_enable_irq(g_interrupt.irq);
+
+ /* Enable register reload interrupt only */
+
+ stm32_ltdc_irqctrl(LTDC_IER_RRIE,LTDC_IER_TERRIE|LTDC_IER_FUIE|LTDC_IER_LIE);
+
+ /* Configure line interrupt */
+
+ stm32_ltdc_linepos();
+
/* Set the default active layer */
#ifndef CONFIG_STM32_LTDC_L2
@@ -1152,22 +1332,6 @@ static void stm32_global_configure(void)
/* Configure background color of the controller */
stm32_ltdc_bgcolor(STM32_LTDC_BACKCOLOR);
-
- /* Enable line interrupt */
-
- stm32_ltdc_interrupt(STM32_LTDC_IER_LIE, 1);
-
- /* Disable fifo underrun interrupt */
-
- stm32_ltdc_interrupt(STM32_LTDC_IER_FUIE, 0);
-
- /* Disable transfer error interrupt */
-
- stm32_ltdc_interrupt(STM32_LTDC_IER_TERRIE, 0);
-
- /* Enable register reload interrupt */
-
- stm32_ltdc_interrupt(STM32_LTDC_IER_RRIE, 1);
}
/****************************************************************************
@@ -1305,7 +1469,7 @@ static inline uint8_t stm32_ltdc_lgetopac(FAR struct stm32_layer_s *layer)
*
****************************************************************************/
-static inline bool stm32_ltdc_lvalidate(FAR struct stm32_layer_s *layer)
+static inline bool stm32_ltdc_lvalidate(FAR const struct stm32_layer_s *layer)
{
#ifdef CONFIG_STM32_LTDC_L2
return layer == &LAYER_L1 || layer == &LAYER_L2;
@@ -1531,7 +1695,7 @@ static inline void stm32_ltdc_lframebuffer(FAR struct stm32_layer_s *layer)
pinfo->stride * priv->ypos;
regvdbg("set LTDC_L%dCFBAR=%08x\n", priv->lid + 1, pinfo->fbmem + offset);
- putreg32(pinfo->fbmem + offset, stm32_cfbar_layer_t[priv->lid]);
+ putreg32((uint32_t)pinfo->fbmem + offset, stm32_cfbar_layer_t[priv->lid]);
/* Configure LxCFBLR register */
@@ -1684,34 +1848,56 @@ static void stm32_ltdc_lcolorkey(FAR struct stm32_layer_s *layer)
****************************************************************************/
#ifdef STM32_LAYER_CLUT_SIZE
-static void stm32_ltdc_lclut(FAR struct stm32_layer_s *layer)
+static void stm32_ltdc_lclut(FAR struct stm32_layer_s *layer,
+ FAR const struct fb_cmap_s *cmap)
{
- int n;
- uint32_t regval;
- FAR struct fb_cmap_s *cmap = layer->state.cmap;
+ int n;
+ uint32_t regval;
+ uint32_t *clut;
irqstate_t flags;
/* Disable clut during register update */
stm32_ltdc_lclutenable(layer, false);
+ /* Set the clut memory address */
+
+ clut = layer->state.clut;
+
/* Reload shadow control register.
* This never changed any layer setting as long the layer register not up to
* date. This is what stm32_update does.
*/
- stm32_ltdc_reload(LTDC_SRCR_IMR);
+ stm32_ltdc_reload(LTDC_SRCR_IMR, false);
flags = irqsave();
/* Update the clut registers */
- for (n = cmap->first; n < cmap->len - cmap->first; n++)
+ for (n = cmap->first; n < cmap->len && n < STM32_LTDC_NCLUT; n++)
{
- regval = (uint32_t)LTDC_CLUT_ADD(n) |
- (uint32_t)LTDC_CLUT_RED(cmap->red[n]) |
- (uint32_t)LTDC_CLUT_GREEN(cmap->green[n]) |
- (uint32_t)LTDC_CLUT_BLUE(cmap->blue[n]);
+ /* Update the layer clut entry */
+#ifndef CONFIG_FB_TRANSPARENCY
+ uint8_t *clut888 = (uint8_t*)clut;
+ uint16_t offset = 3 * n;
+
+ clut888[offset] = cmap->blue[n];
+ clut888[offset + 1] = cmap->green[n];
+ clut888[offset + 2] = cmap->red[n];
+
+ regval = (uint32_t)LTDC_CLUT_BLUE(clut888[offset]) |
+ (uint32_t)LTDC_CLUT_GREEN(clut888[offset + 1]) |
+ (uint32_t)LTDC_CLUT_RED(clut888[offset + 2]) |
+ (uint32_t)LTDC_CLUT_ADD(n);
+#else
+ clut[n] = (uint32_t)LTDC_CLUT_ALPHA(cmap->transp[n]) |
+ (uint32_t)LTDC_CLUT_RED(cmap->red[n]) |
+ (uint32_t)LTDC_CLUT_GREEN(cmap->green[n]) |
+ (uint32_t)LTDC_CLUT_BLUE(cmap->blue[n]);
+ regval = (uint32_t)LTDC_CLUT_ADD(n) | (clut[n] & LTDC_CLUT_RGB888_MASK);
+#endif
+
regvdbg("set LTDC_L%dCLUTWR = %08x, cmap->first = %d, cmap->len = %d\n",
layer->state.lid + 1, regval, cmap->first, cmap->len);
@@ -1726,7 +1912,7 @@ static void stm32_ltdc_lclut(FAR struct stm32_layer_s *layer)
/* Reload shadow control register */
- stm32_ltdc_reload(LTDC_SRCR_IMR);
+ stm32_ltdc_reload(LTDC_SRCR_IMR, false);
}
#endif
@@ -1885,6 +2071,7 @@ static void stm32_ltdc_lclear(FAR struct stm32_layer_s *layer,
* - layer colorkey
* - layer alpha
* - layer blendmode
+ * - layer dma2d interface binding
*
* Parameter
* layer - Reference to the layer control structure
@@ -1923,14 +2110,12 @@ static void stm32_ltdc_linit(int lid)
#ifdef CONFIG_STM32_DMA2D
ltdc->blit = stm32_blit;
ltdc->blend = stm32_blend;
+ ltdc->fillarea = stm32_fillarea;
#endif
#endif
/* Initialize the layer state */
-#ifdef STM32_LAYER_CLUT_SIZE
- state->cmap->first = 0;
-#endif
state->area.xpos = 0;
state->area.ypos = 0;
state->area.xres = STM32_LTDC_WIDTH;
@@ -1970,44 +2155,14 @@ static void stm32_ltdc_linit(int lid)
stm32_ltdc_lclutenable(layer, false);
}
#endif
-}
-
-/****************************************************************************
- * Name: stm32_ltdc_cmapcpy
- *
- * Description:
- * Copies a color table
- * Note! Caller must check if first position is out of range
- *
- * Parameter:
- * dest - color cmap to copy to
- * src - color map to copy from
- *
- * Return:
- * On success - OK
- * On error - -EINVAL
- *
- ****************************************************************************/
-
-#ifdef STM32_LAYER_CLUT_SIZE
-static void stm32_ltdc_cmapcpy(FAR struct fb_cmap_s *dest,
- FAR const struct fb_cmap_s *src)
-{
- int n;
- for (n = src->first; n < src->len && n < STM32_LTDC_CLUT_ENTRIES; n++)
- {
- regvdbg("n = %d, red = %02x, green = %02x, blue = %02x\n",
- n, src->red[n], src->green[n], src->blue[n]);
- dest->red[n] = src->red[n];
- dest->green[n] = src->green[n];
- dest->blue[n] = src->blue[n];
- }
+#ifdef CONFIG_STM32_DMA2D
+ /* Bind the dma2d interface */
- dest->first = src->first;
- dest->len = src->len;
-}
+ layer->dma2d = stm32_dma2dinitltdc(state);
+ DEBUGASSERT(layer->dma2d);
#endif
+}
/****************************************************************************
* Public Functions
@@ -2121,8 +2276,8 @@ static int stm32_getcmap(struct fb_vtable_s *vtable,
* cmap - the color table
*
* Return:
- * On success - OK
- * On error - -EINVAL
+ * On success - OK
+ * On error - -EINVAL
*
****************************************************************************/
@@ -2159,7 +2314,7 @@ static int stm32_lgetvideoinfo(struct ltdc_layer_s *layer,
gvdbg("layer=%p vinfo=%p\n", layer, vinfo);
FAR struct stm32_layer_s *priv = (FAR struct stm32_layer_s *)layer;
- if (priv == &LAYER_L1 || priv == &LAYER_L2)
+ if (stm32_ltdc_lvalidate(priv))
{
memcpy(vinfo, &priv->state.vinfo, sizeof(struct fb_videoinfo_s));
@@ -2239,20 +2394,17 @@ static int stm32_setclut(struct ltdc_layer_s *layer,
priv->state.vinfo.fmt);
ret = -EINVAL;
}
- else if (cmap->first > STM32_LTDC_CLUT_ENTRIES)
+ else if (cmap->first >= STM32_LTDC_NCLUT)
{
- gdbg("Error: CLUT offset is out of range: %d\n", cmap->first);
+ gdbg("Error: only %d color table entries supported\n",
+ STM32_LTDC_NCLUT);
ret = -EINVAL;
}
else
{
- /* Copy to the layer cmap */
-
- stm32_ltdc_cmapcpy(priv->state.cmap, cmap);
+ /* Update layer clut and clut register */
- /* Update layer clut register */
-
- stm32_ltdc_lclut(priv);
+ stm32_ltdc_lclut(priv, cmap);
ret = OK;
}
@@ -2293,28 +2445,65 @@ static int stm32_getclut(struct ltdc_layer_s *layer,
if (priv == &LAYER_L1 || priv == &LAYER_L2)
{
sem_wait(priv->state.lock);
+#ifdef CONFIG_STM32_DMA2D
+ /*
+ * Note! We share the same color lookup table with the dma2d driver and
+ * the getclut implementation works in the same way.
+ * To prevent redundant code we simply call the getclut function of the
+ * dma2d interface.
+ */
+ ret = priv->dma2d->getclut(priv->dma2d, cmap);
+#else
if (priv->state.vinfo.fmt != FB_FMT_RGB8)
{
gdbg("Error: CLUT is not supported for the pixel format: %d\n",
priv->state.vinfo.fmt);
ret = -EINVAL;
}
- else if (cmap->len < priv->state.cmap->len)
+ else if (cmap->first >= STM32_LTDC_NCLUT)
{
- gdbg("Error: cmap must accept %d color table entries: %d\n",
- priv->state.cmap->len);
+ gdbg("Error: only %d color table entries supported\n",
+ STM32_LTDC_NCLUT);
ret = -EINVAL;
}
else
{
- /* Copy from the layer cmap */
+ /* Copy from the layer clut */
+
+ uint32_t *clut;
+ int n;
- stm32_ltdc_cmapcpy(cmap, priv->state.cmap);
+ clut = priv->state.clut;
+
+ for (n = cmap->first; n < cmap->len && n < STM32_LTDC_NCLUT; n++)
+ {
+# ifndef CONFIG_FB_TRANSPARENCY
+ uint8_t *clut888 = (uint8_t*)clut;
+ uint16_t offset = 3 * n;
+
+ cmap->blue[n] = clut888[offset];
+ cmap->green[n] = clut888[offset + 1];
+ cmap->red[n] = clut888[offset + 2];
+
+ regvdbg("n=%d, red=%02x, green=%02x, blue=%02x\n", n,
+ clut888[offset], clut888[offset + 1],
+ clut888[offset + 2]);
+# else
+ cmap->transp[n] = (uint8_t)LTDC_CMAP_ALPHA(clut[n]);
+ cmap->red[n] = (uint8_t)LTDC_CMAP_RED(clut[n]);
+ cmap->green[n] = (uint8_t)LTDC_CMAP_GREEN(clut[n]);
+ cmap->blue[n] = (uint8_t)LTDC_CMAP_BLUE(clut[n]);
+
+ regvdbg("n=%d, alpha=%02x, red=%02x, green=%02x, blue=%02x\n", n,
+ DMA2D_CMAP_ALPHA(clut[n]), DMA2D_CMAP_RED(clut[n]),
+ DMA2D_CMAP_GREEN(clut[n]), DMA2D_CMAP_BLUE(clut[n]));
+# endif
+ }
ret = OK;
}
-
+#endif
sem_post(priv->state.lock);
return ret;
@@ -2383,6 +2572,11 @@ static int stm32_getlid(FAR struct ltdc_layer_s *layer, int *lid, uint32_t flag)
*lid = LTDC_LAYER_L1;
break;
#endif
+#ifdef CONFIG_STM32_DMA2D
+ case LTDC_LAYER_DMA2D:
+ ret = priv->dma2d->getlid(priv->dma2d, lid);
+ break;
+#endif
default:
ret = EINVAL;
gdbg("Returning EINVAL\n");
@@ -2620,7 +2814,7 @@ static int stm32_getalpha(FAR struct ltdc_layer_s *layer, uint8_t *alpha)
*
* Description:
* Configure blend mode of the layer.
- * Default mode during initialzing: LTDC_BLEND_NONE
+ * Default mode during initializing: LTDC_BLEND_NONE
* Blendmode is active after next update.
*
* Parameter:
@@ -2658,6 +2852,7 @@ static int stm32_getalpha(FAR struct ltdc_layer_s *layer, uint8_t *alpha)
static int stm32_setblendmode(FAR struct ltdc_layer_s *layer, uint32_t mode)
{
FAR struct stm32_layer_s *priv = (FAR struct stm32_layer_s *)layer;
+ uint32_t blendmode = mode;
gvdbg("layer = %p, mode = %08x\n", layer, mode);
if (stm32_ltdc_lvalidate(priv))
@@ -2666,33 +2861,56 @@ static int stm32_setblendmode(FAR struct ltdc_layer_s *layer, uint32_t mode)
sem_wait(priv->state.lock);
- /* Disable alpha blending by default */
-
- priv->bf1 = LTDC_BF1_CONST_ALPHA;
- priv->bf2 = LTDC_BF2_CONST_ALPHA;
- stm32_ltdc_lsetopac(priv);
-
/* Disable colorkeying by default */
priv->operation &=~ LTDC_LAYER_ENABLECOLORKEY;
- if (mode & LTDC_BLEND_ALPHA)
+ if (blendmode & (LTDC_BLEND_ALPHA|LTDC_BLEND_PIXELALPHA|
+ LTDC_BLEND_ALPHAINV|LTDC_BLEND_PIXELALPHAINV))
{
- /* Initialize blend factor */
+ /* Enable any alpha blending */
- if (mode & LTDC_BLEND_SRCPIXELALPHA)
- {
- priv->bf1 = LTDC_BF1_PIXEL_ALPHA;
- }
- else if (mode & LTDC_BLEND_DESTPIXELALPHA)
- {
- priv->bf2 = LTDC_BF2_PIXEL_ALPHA;
- }
+ stm32_ltdc_lunsetopac(priv);
+ }
+ else
+ {
+ /* Disable any alpha blending */
- /* Enable blending, restore the alpha value */
+ stm32_ltdc_lsetopac(priv);
+ }
- stm32_ltdc_lunsetopac(priv);
- mode &= ~LTDC_BLEND_ALPHA;
+ if (blendmode & LTDC_BLEND_ALPHA || blendmode == LTDC_BLEND_NONE)
+ {
+ /* alpha blending introduce LTDC_BLEND_ALPHAINV */
+
+ priv->bf1 = LTDC_BF1_CONST_ALPHA;
+ priv->bf2 = LTDC_BF2_CONST_ALPHA;
+ blendmode &= ~LTDC_BLEND_ALPHA;
+ }
+
+ if (blendmode & LTDC_BLEND_PIXELALPHA)
+ {
+ /* pixel alpha blending introduce LTDC_BLEND_PIXELALPHAINV */
+
+ priv->bf1 = LTDC_BF1_PIXEL_ALPHA;
+ priv->bf2 = LTDC_BF2_PIXEL_ALPHA;
+ blendmode &= ~LTDC_BLEND_PIXELALPHA;
+ }
+
+ if (blendmode & LTDC_BLEND_ALPHAINV)
+ {
+ /* alpha blending of source input */
+
+ priv->bf2 = LTDC_BF2_CONST_ALPHA;
+ blendmode &= ~LTDC_BLEND_ALPHAINV;
+ }
+
+ if (blendmode & LTDC_BLEND_PIXELALPHAINV)
+ {
+ /* pixel alpha blending of source input */
+
+ priv->bf2 = LTDC_BF2_PIXEL_ALPHA;
+ blendmode &= ~LTDC_BLEND_PIXELALPHAINV;
}
if (mode & LTDC_BLEND_COLORKEY)
@@ -2700,12 +2918,11 @@ static int stm32_setblendmode(FAR struct ltdc_layer_s *layer, uint32_t mode)
/* Enable colorkeying */
priv->operation |= LTDC_LAYER_ENABLECOLORKEY;
- mode &= ~LTDC_BLEND_COLORKEY;
+ blendmode &= ~LTDC_BLEND_COLORKEY;
}
-
- if (mode & ~(LTDC_BLEND_SRCPIXELALPHA|LTDC_BLEND_DESTPIXELALPHA))
+ if (blendmode)
{
- gdbg("Unknown blendmode %02x\n", mode);
+ gdbg("Unknown blendmode %02x\n", blendmode);
ret = -EINVAL;
}
@@ -2718,7 +2935,6 @@ static int stm32_setblendmode(FAR struct ltdc_layer_s *layer, uint32_t mode)
}
sem_post(priv->state.lock);
-
return ret;
}
@@ -2875,8 +3091,9 @@ static int stm32_getarea(FAR struct ltdc_layer_s *layer,
* mode - operation mode
*
* Return:
- * OK - On success
- * -EINVAL - If one of the parameter invalid
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid
+ * -ECANCELED - Operation cancelled, something goes wrong
*
* Procedure information:
* LTDC_UPDATE_SIM:
@@ -2916,6 +3133,7 @@ static int stm32_update(FAR struct ltdc_layer_s *layer, uint32_t mode)
{
/* Reload immediately by default */
+ bool waitvblank = false;
uint8_t reload = LTDC_SRCR_IMR;
sem_wait(priv->state.lock);
@@ -2927,7 +3145,15 @@ static int stm32_update(FAR struct ltdc_layer_s *layer, uint32_t mode)
if (mode & LTDC_SYNC_WAIT)
{
- reload |= LTDC_SRCR_WAIT;
+ waitvblank = true;
+ }
+
+ /* Ensures that last register reload operation has been completed */
+
+ if (stm32_ltdc_waitforirq() != OK)
+ {
+ gdbg("Returning ECANCELED\n");
+ return -ECANCELED;
}
/* Update the given layer */
@@ -2965,7 +3191,8 @@ static int stm32_update(FAR struct ltdc_layer_s *layer, uint32_t mode)
/* Set blendfactor for current active layer to there reset value */
- stm32_ltdc_lblendmode(active, STM32_LTDC_BF1_RESET, STM32_LTDC_BF2_RESET);
+ stm32_ltdc_lblendmode(active, STM32_LTDC_BF1_RESET,
+ STM32_LTDC_BF2_RESET);
/* Set blendfactor for current inactive layer */
@@ -3000,7 +3227,7 @@ static int stm32_update(FAR struct ltdc_layer_s *layer, uint32_t mode)
/* Make the changes visible */
- stm32_ltdc_reload(reload);
+ stm32_ltdc_reload(reload, waitvblank);
sem_post(priv->state.lock);
@@ -3011,53 +3238,48 @@ static int stm32_update(FAR struct ltdc_layer_s *layer, uint32_t mode)
return -EINVAL;
}
-
#ifdef CONFIG_STM32_DMA2D
/****************************************************************************
- * Name: blit
+ * Name: stm32_blit
*
* Description:
- * Copy selected area from a background layer to selected position of the
- * foreground layer. Copies the result to the destination layer.
+ * Copy selected area from a source layer to selected position of the
+ * destination layer.
*
* Parameter:
* dest - Reference to the destination layer
- * fore - Reference to the foreground layer
- * forexpos - Selected x target position of the destination layer
- * foreypos - Selected y target position of the destination layer
- * back - Reference to the background layer
- * backarea - Reference to the selected area of the background layer
+ * destxpos - Selected x position of the destination layer
+ * destypos - Selected y position of the destination layer
+ * src - Reference to the source layer
+ * srcarea - Reference to the selected area of the source layer
*
* Return:
- * OK - On success
- * -EINVAL - If one of the parameter invalid or if the size of the selected
- * source area outside the visible area of the destination layer.
- * (The visible area usually represents the display size)
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * source area outside the visible area of the destination layer.
+ * (The visible area usually represents the display size)
*
****************************************************************************/
static int stm32_blit(FAR struct ltdc_layer_s *dest,
- FAR struct ltdc_layer_s *fore,
- fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct ltdc_layer_s *back,
- FAR const struct ltdc_area_s *backarea)
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *src,
+ FAR const struct ltdc_area_s *srcarea)
{
- FAR struct stm32_layer_s *destlayer = (FAR struct stm32_layer_s *)dest;
- FAR struct stm32_layer_s *forelayer = (FAR struct stm32_layer_s *)fore;
- FAR struct stm32_layer_s *backlayer = (FAR struct stm32_layer_s *)back;
+ FAR struct stm32_layer_s *priv = (FAR struct stm32_layer_s *)dest;
- gvdbg("dest = %p, fore = %p, forexpos = %d, foreypos = %d, back = %p, \
- backarea = %p\n", dest, fore, forexpos, foreypos, back, backarea);
+ gvdbg("dest = %p, destxpos = %d, destypos = %d, src = %p, srcarea = %p\n",
+ dest, destxpos, destypos, src, srcarea);
- if (stm32_ltdc_lvalidate(destlayer) &&
- stm32_ltdc_lvalidate(forelayer) &&
- stm32_ltdc_lvalidate(backlayer))
+ if (stm32_ltdc_lvalidate(priv))
{
- return stm32_dma2dblit(&destlayer->state,
- &forelayer->state,
- forexpos, foreypos,
- &backlayer->state,
- backarea);
+ int ret;
+
+ sem_wait(priv->state.lock);
+ priv->dma2d->blit(priv->dma2d, destxpos, destypos, src, srcarea);
+ sem_post(priv->state.lock);
+
+ return ret;
}
gdbg("Returning EINVAL\n");
@@ -3065,53 +3287,96 @@ static int stm32_blit(FAR struct ltdc_layer_s *dest,
}
/****************************************************************************
- *
- * Name: blend
+ * Name: stm32_blend
*
* Description:
- * Blends the selected area from a background layer with selected position of
- * the foreground layer. Blends the result with the destination layer.
- * Note! This is the same as the blit operation but with blending depending on
- * the blendmode settings of the layer.
+ * Blends the selected area from a foreground layer with selected position
+ * of the background layer. Copy the result to the destination layer. Note!
+ * The content of the foreground and background layer is not changed.
*
* Parameter:
* dest - Reference to the destination layer
+ * destxpos - Selected x position of the destination layer
+ * destypos - Selected y position of the destination layer
* fore - Reference to the foreground layer
- * forexpos - Selected x target position of the destination layer
- * foreypos - Selected y target position of the destination layer
+ * forexpos - Selected x position of the foreground layer
+ * foreypos - Selected y position of the foreground layer
* back - Reference to the background layer
* backarea - Reference to the selected area of the background layer
*
* Return:
- * OK - On success
- * -EINVAL - If one of the parameter invalid or if the size of the selected
- * source area outside the visible area of the destination layer.
- * (The visible area usually represents the display size)
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * source area outside the visible area of the destination layer.
+ * (The visible area usually represents the display size)
*
****************************************************************************/
static int stm32_blend(FAR struct ltdc_layer_s *dest,
- FAR struct ltdc_layer_s *fore,
+ fb_coord_t destxpos, fb_coord_t destypos,
+ FAR const struct dma2d_layer_s *fore,
fb_coord_t forexpos, fb_coord_t foreypos,
- FAR struct ltdc_layer_s *back,
+ FAR const struct dma2d_layer_s *back,
FAR const struct ltdc_area_s *backarea)
{
- FAR struct stm32_layer_s *destlayer = (FAR struct stm32_layer_s *)dest;
- FAR struct stm32_layer_s *forelayer = (FAR struct stm32_layer_s *)fore;
- FAR struct stm32_layer_s *backlayer = (FAR struct stm32_layer_s *)back;
+ FAR struct stm32_layer_s *priv = (FAR struct stm32_layer_s *)dest;
+
+ gvdbg("dest=%p, destxpos=%d, destypos=%d, "
+ "fore=%p, forexpos=%d foreypos=%d, "
+ "back=%p, backarea=%p\n",
+ dest, destxpos, destypos, fore, forexpos, foreypos, back, backarea);
+
+ if (stm32_ltdc_lvalidate(priv))
+ {
+ int ret;
+
+ sem_wait(priv->state.lock);
+ priv->dma2d->blend(priv->dma2d, destxpos, destypos,
+ fore, forexpos, foreypos, back, backarea);
+ sem_post(priv->state.lock);
+
+ return ret;
+ }
+
+ gdbg("Returning EINVAL\n");
+ return -EINVAL;
+}
+
+/****************************************************************************
+ * Name: fillarea
+ *
+ * Description:
+ * Fill the selected area of the whole layer with a specific color.
+ *
+ * Parameter:
+ * layer - Reference to the layer structure
+ * area - Reference to the valid area structure select the area
+ * color - Color to fill the selected area. Color must be formatted
+ * according to the layer pixel format.
+ *
+ * Return:
+ * OK - On success
+ * -EINVAL - If one of the parameter invalid or if the size of the selected
+ * area outside the visible area of the layer.
+ *
+ ****************************************************************************/
- gvdbg("dest = %p, fore = %p, forexpos = %d, foreypos = %d, back = %p, \
- backarea = %p\n", dest, fore, forexpos, foreypos, back, backarea);
+static int stm32_fillarea(FAR struct ltdc_layer_s *layer,
+ FAR const struct ltdc_area_s *area,
+ uint32_t color)
+{
+ FAR struct stm32_layer_s *priv = (FAR struct stm32_layer_s *)layer;
+ gvdbg("layer = %p, area = %p, color = %08x\n", layer, area, color);
- if (stm32_ltdc_lvalidate(destlayer) &&
- stm32_ltdc_lvalidate(forelayer) &&
- stm32_ltdc_lvalidate(backlayer))
+ if (stm32_ltdc_lvalidate(priv))
{
- return stm32_dma2dblend(&destlayer->state,
- &forelayer->state,
- forexpos, foreypos,
- &backlayer->state,
- backarea);
+ int ret;
+
+ sem_wait(priv->state.lock);
+ priv->dma2d->fillarea(priv->dma2d, area, color);
+ sem_post(priv->state.lock);
+
+ return ret;
}
gdbg("Returning EINVAL\n");
@@ -3163,7 +3428,16 @@ FAR struct ltdc_layer_s *stm32_ltdcgetlayer(int lid)
int stm32_ltdcinitialize(void)
{
- gvdbg("Initialize LTDC driver\n");
+#ifdef CONFIG_STM32_DMA2D
+ int ret;
+#endif
+
+ dbg("Initialize LTDC driver\n");
+
+ if (g_initialized == true)
+ {
+ return OK;
+ }
/* Disable the LCD */
@@ -3181,6 +3455,17 @@ int stm32_ltdcinitialize(void)
gvdbg("Configure global register\n");
stm32_global_configure();
+#ifdef CONFIG_STM32_DMA2D
+ /* Initialize the dma2d controller */
+
+ ret = up_dma2dinitialize();
+
+ if (ret != OK)
+ {
+ return ret;
+ }
+#endif
+
/* Initialize ltdc layer */
gvdbg("Initialize ltdc layer\n");
@@ -3205,13 +3490,16 @@ int stm32_ltdcinitialize(void)
/* Reload shadow register */
gvdbg("Reload shadow register\n");
- stm32_ltdc_reload(LTDC_SRCR_IMR);
+ stm32_ltdc_reload(LTDC_SRCR_IMR, false);
/* Turn the LCD on */
gvdbg("Enabling the display\n");
stm32_lcd_enable(true);
+ /* Set initialized state */
+
+ g_initialized = true;
return OK;
}
@@ -3233,6 +3521,7 @@ int stm32_ltdcinitialize(void)
struct fb_vtable_s *stm32_ltdcgetvplane(int vplane)
{
gvdbg("vplane: %d\n", vplane);
+
if (vplane == 0)
{
return (struct fb_vtable_s *)&g_vtable;
@@ -3252,9 +3541,21 @@ struct fb_vtable_s *stm32_ltdcgetvplane(int vplane)
void stm32_ltdcuninitialize(void)
{
+ /* Disable all ltdc interrupts */
+
+ stm32_ltdc_irqctrl(0, LTDC_IER_RRIE|LTDC_IER_TERRIE|
+ LTDC_IER_FUIE|LTDC_IER_LIE);
+
+ up_disable_irq(g_interrupt.irq);
+ irq_detach(g_interrupt.irq);
+
/* Disable the LCD controller */
stm32_lcd_enable(false);
+
+ /* Set initialized state */
+
+ g_initialized = false;
}
/****************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/stm32_ltdc.h b/nuttx/arch/arm/src/stm32/stm32_ltdc.h
index c0e60bd18..9214d83e3 100644
--- a/nuttx/arch/arm/src/stm32/stm32_ltdc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_ltdc.h
@@ -81,7 +81,7 @@ struct stm32_ltdc_s
uint32_t color; /* Layer color definition */
#ifdef CONFIG_FB_CMAP
- struct fb_cmap_s *cmap; /* Reference to the valid color lookup table */
+ uint32_t *clut; /* 32-bit aligned clut color table */
#endif
/* Blending */
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
index 9721e906b..c761533df 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
@@ -209,6 +209,12 @@ static inline void rcc_enableahb1(void)
#endif /* CONFIG_STM32_OTGHS */
+#ifdef CONFIG_STM32_DMA2D
+ /* DMA2D clock */
+
+ regval |= RCC_AHB1ENR_DMA2DEN;
+#endif
+
putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */
}