aboutsummaryrefslogtreecommitdiffstats
path: root/boards
diff options
context:
space:
mode:
authorJoel Bodenmann <joel@embedded.pro>2017-10-28 11:58:02 +0200
committerJoel Bodenmann <joel@embedded.pro>2017-10-28 11:58:02 +0200
commit025bc66666401f1a1a9f16ecddf5655141d11839 (patch)
treea9077104e030aa31f9bf62f9d62fbefd9d05865d /boards
parent2a249e6140307c1cfaa1ce6f7775caf3f7be4b79 (diff)
downloaduGFX-025bc66666401f1a1a9f16ecddf5655141d11839.tar.gz
uGFX-025bc66666401f1a1a9f16ecddf5655141d11839.tar.bz2
uGFX-025bc66666401f1a1a9f16ecddf5655141d11839.zip
STM32F469i-Discovery board files
Diffstat (limited to 'boards')
-rw-r--r--boards/base/STM32F469i-Discovery/CubeHAL/STM32_FLASH.ld186
-rw-r--r--boards/base/STM32F469i-Discovery/CubeHAL/board_STM32LTDC.h309
-rw-r--r--boards/base/STM32F469i-Discovery/CubeHAL/ft6x06.h88
-rw-r--r--boards/base/STM32F469i-Discovery/CubeHAL/gmouse_lld_FT6x06_board.h110
-rw-r--r--boards/base/STM32F469i-Discovery/STM32_FLASH.ld189
-rw-r--r--boards/base/STM32F469i-Discovery/board.mk33
-rw-r--r--boards/base/STM32F469i-Discovery/board_STM32LTDC.h292
-rw-r--r--boards/base/STM32F469i-Discovery/gmouse_lld_FT6x06_board.h85
-rw-r--r--boards/base/STM32F469i-Discovery/otm8009a.c454
-rw-r--r--boards/base/STM32F469i-Discovery/otm8009a.h224
-rw-r--r--boards/base/STM32F469i-Discovery/startup_stm32f469xx.s589
-rw-r--r--boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.c529
-rw-r--r--boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.h169
-rw-r--r--boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.c176
-rw-r--r--boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.h69
-rw-r--r--boards/base/STM32F469i-Discovery/stm32f469i_raw32_system.c450
-rw-r--r--boards/base/STM32F469i-Discovery/stm32f469i_raw32_ugfx.c110
17 files changed, 3685 insertions, 377 deletions
diff --git a/boards/base/STM32F469i-Discovery/CubeHAL/STM32_FLASH.ld b/boards/base/STM32F469i-Discovery/CubeHAL/STM32_FLASH.ld
new file mode 100644
index 00000000..8cdd7c0e
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/CubeHAL/STM32_FLASH.ld
@@ -0,0 +1,186 @@
+/*
+ * GCC linker script for STM32 microcontrollers (ARM Cortex-M).
+ *
+ * It exports the symbols needed for the CMSIS assembler startup script for GCC
+ * ARM toolchains (_sidata, _sdata, _edata, _sbss, _ebss) and sets the entry
+ * point to Reset_Handler.
+ *
+ * Adapt FLASH/RAM size for your particular device below.
+ *
+ * @author Bjørn Forsman
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 320K
+ ccmram (rw) : ORIGIN = 0x10000000, LENGTH = 64k
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 2048K
+}
+
+ENTRY(Reset_Handler)
+
+/*
+ * Reserve memory for heap and stack. The linker will issue an error if there
+ * is not enough memory.
+ *
+ * NOTE: The reserved heap and stack will be added to the bss column of the
+ * binutils size command.
+ */
+_heap_size = 0x200; /* required amount of heap */
+_stack_size = 0x400; /* required amount of stack */
+
+/*
+ * The stack starts at the end of RAM and grows downwards. Full-descending
+ * stack; decrement first, then store.
+ */
+_estack = ORIGIN(ram) + LENGTH(ram);
+
+SECTIONS
+{
+ /* Reset and ISR vectors */
+ .isr_vector :
+ {
+ __isr_vector_start__ = .;
+ KEEP(*(.isr_vector)) /* without 'KEEP' the garbage collector discards this section */
+ ASSERT(. != __isr_vector_start__, "The .isr_vector section is empty");
+ } >flash
+
+
+ /* Text section (code and read-only data) */
+ .text :
+ {
+ . = ALIGN(4);
+ _stext = .;
+ *(.text*) /* code */
+ *(.rodata*) /* read only data */
+
+ /*
+ * NOTE: .glue_7 and .glue_7t sections are not needed because Cortex-M
+ * only supports Thumb instructions, no ARM/Thumb interworking.
+ */
+
+ /* Static constructors and destructors */
+ KEEP(*(.init))
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ _etext = .;
+ } >flash
+
+
+ /*
+ * Stack unwinding and exception handling sections.
+ *
+ * ARM compilers emit object files with .ARM.extab and .ARM.exidx sections
+ * when using C++ exceptions. Also, at least GCC emits those sections when
+ * dividing large numbers (64-bit) in C. So we have to handle them.
+ *
+ * (ARM uses .ARM.extab and .ARM.exidx instead of the .eh_frame section
+ * used on x86.)
+ */
+ .ARM.extab : /* exception unwinding information */
+ {
+ *(.ARM.extab*)
+ } >flash
+ .ARM.exidx : /* index entries for section unwinding */
+ {
+ *(.ARM.exidx*)
+ } >flash
+
+
+ /*
+ * Newlib and Eglibc (at least) need these for C++ support.
+ *
+ * (Copied from Sourcery CodeBench Lite: arm-none-eabi-gcc -V)
+ */
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN(__preinit_array_start = .);
+ KEEP(*(.preinit_array*))
+ PROVIDE_HIDDEN(__preinit_array_end = .);
+ } >flash
+ .init_array :
+ {
+ PROVIDE_HIDDEN(__init_array_start = .);
+ KEEP(*(SORT(.init_array.*)))
+ KEEP(*(.init_array*))
+ PROVIDE_HIDDEN(__init_array_end = .);
+ } >flash
+ .fini_array :
+ {
+ PROVIDE_HIDDEN(__fini_array_start = .);
+ KEEP(*(SORT(.fini_array.*)))
+ KEEP(*(.fini_array*))
+ PROVIDE_HIDDEN(__fini_array_end = .);
+ } >flash
+
+
+ /*
+ * Initialized data section. This section is programmed into FLASH (LMA
+ * address) and copied to RAM (VMA address) in startup code.
+ */
+ _sidata = .;
+ .data : AT(_sidata) /* LMA address is _sidata (in FLASH) */
+ {
+ . = ALIGN(4);
+ _sdata = .; /* data section VMA address (in RAM) */
+ *(.data*)
+ . = ALIGN(4);
+ _edata = .;
+ } >ram
+
+ /*
+ * CCM-RAM data section. Initialization variables can be placed here
+ * when the initialization code is provided by the user. Else it is used
+ * as an extra piece of memory for heap/stack
+ */
+ _eidata = (_sidata + SIZEOF(.data));
+ .ccm : AT(_sidata + SIZEOF(.data)) /* We want LMA address to be in FLASH (if used for init data) */
+ {
+ . = ALIGN(4);
+ _sccm = .; /* data section VMA address (in CCMRAM) */
+ *(.ccm)
+ . = ALIGN(4);
+ _eccm = .;
+ } >ccmram
+
+
+ /* Uninitialized data section (zeroed out by startup code) */
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .;
+ __bss_start__ = _sbss;
+ *(.bss*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = .;
+ __bss_end__ = _ebss;
+ } >ram
+
+
+ /*
+ * Reserve memory for heap and stack. The linker will issue an error if
+ * there is not enough memory.
+ */
+ ._heap :
+ {
+ . = ALIGN(4);
+ _end = .;
+ __end__ = _end;
+ . = . + _heap_size;
+ . = ALIGN(4);
+ } >ram
+ ._stack :
+ {
+ . = ALIGN(4);
+ . = . + _stack_size;
+ . = ALIGN(4);
+ } >ram
+}
+
+/* Nice to have */
+__isr_vector_size__ = SIZEOF(.isr_vector);
+__text_size__ = SIZEOF(.text);
+__data_size__ = SIZEOF(.data);
+__bss_size__ = SIZEOF(.bss);
diff --git a/boards/base/STM32F469i-Discovery/CubeHAL/board_STM32LTDC.h b/boards/base/STM32F469i-Discovery/CubeHAL/board_STM32LTDC.h
new file mode 100644
index 00000000..00a66c21
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/CubeHAL/board_STM32LTDC.h
@@ -0,0 +1,309 @@
+/*
+ * This file is subject to the terms of the GFX License. If a copy of
+ * the license was not distributed with this file, you can obtain one at:
+ *
+ * http://ugfx.org/license.html
+ */
+
+#ifndef _GDISP_LLD_BOARD_H
+#define _GDISP_LLD_BOARD_H
+
+/* Avoid naming collisions with CubeHAL. */
+#undef Red
+#undef Green
+#undef Blue
+
+/* HAL drivers needed for configuration. */
+#include "stm32f4xx_hal.h"
+#include "stm32f4xx_hal_rcc.h"
+#include "stm32f4xx_hal_gpio.h"
+#include "stm32f4xx_hal_dsi.h"
+/* sdram driver provided by ST. */
+#include "stm32f469i_discovery_sdram.h"
+/* OTM8009A driver provided by ST. */
+#include "otm8009a.h"
+
+/** Manually set the LTDC timing. */
+#ifndef GFX_LTDC_TIMING_SET
+ #define GFX_LTDC_TIMING_SET
+#endif
+
+/** Most boards will be revision A. */
+#ifndef USE_STM32469I_DISCO_REVA
+ #define USE_STM32469I_DISCO_REVA
+#endif
+
+/** @brief Panel parameters
+ *
+ * This panel is a KoD KM-040TMP-02-0621 DSI LCD Display.
+ */
+
+static const ltdcConfig driverCfg = {
+ 800, 480, // Width, Height (pixels)
+ 1, 2, // Horizontal, Vertical sync (pixels)
+ 15, 34, // Horizontal, Vertical back porch (pixels)
+ 16, 34, // Horizontal, Vertical front porch (pixels)
+ 0, // Sync flags
+ 0x000000, // Clear color (RGB888)
+
+ { // Background layer config
+ (LLDCOLOR_TYPE *)SDRAM_DEVICE_ADDR, // Frame buffer address
+ 800, 480, // Width, Height (pixels)
+ 800 * LTDC_PIXELBYTES, // Line pitch (bytes)
+ LTDC_PIXELFORMAT, // Pixel format
+ 0, 0, // Start pixel position (x, y)
+ 800, 480, // Size of virtual layer (cx, cy)
+ LTDC_COLOR_FUCHSIA, // Default color (ARGB8888)
+ 0x980088, // Color key (RGB888)
+ LTDC_BLEND_FIX1_FIX2, // Blending factors
+ 0, // Palette (RGB888, can be NULL)
+ 0, // Palette length
+ 0xFF, // Constant alpha factor
+ LTDC_LEF_ENABLE // Layer configuration flags
+ },
+
+ LTDC_UNUSED_LAYER_CONFIG // Foreground layer config
+};
+
+/** Display timing setting */
+#define KoD_FREQUENCY_DIVIDER 7
+
+/** Global DSI handle to hold DSI parameters. */
+DSI_HandleTypeDef dsiHandle;
+
+static GFXINLINE void reset_lcd(GDisplay* g);
+
+/**
+ * @brief Function to intialize the STM32F46i-DISCO board.
+ *
+ * @param g: Structure holding display parameters.
+ */
+static GFXINLINE void init_board(GDisplay *g) {
+
+ // As we are not using multiple displays we set g->board to NULL as we don't use it
+ g->board = 0;
+
+#ifdef GFX_LTDC_TIMING_SET
+ // KoD LCD clock configuration
+ // PLLSAI_VCO Input = HSE_VALUE/PLL_M = 1 Mhz
+ // PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN = 384 Mhz
+ // PLLLCDCLK = PLLSAI_VCO Output/PLLSAIR = 384/7 = 54.857 Mhz
+ // LTDC clock frequency = PLLLCDCLK / LTDC_PLLSAI_DIVR_2 = 54.857/2 = 27.429Mhz
+ #define STM32_SAISRC_NOCLOCK (0 << 23) /**< No clock. */
+ #define STM32_SAISRC_PLL (1 << 23) /**< SAI_CKIN is PLL. */
+ #define STM32_SAIR_DIV2 (0 << 16) /**< R divided by 2. */
+ #define STM32_SAIR_DIV4 (1 << 16) /**< R divided by 4. */
+ #define STM32_SAIR_DIV8 (2 << 16) /**< R divided by 8. */
+ #define STM32_SAIR_DIV16 (3 << 16) /**< R divided by 16. */
+
+ #define STM32_PLLSAIN_VALUE 384
+ #define STM32_PLLSAIQ_VALUE 4
+ #define STM32_PLLSAIR_VALUE KoD_FREQUENCY_DIVIDER
+ #define STM32_PLLSAIR_POST STM32_SAIR_DIV2
+
+ RCC->PLLSAICFGR = (STM32_PLLSAIN_VALUE << 6) | (STM32_PLLSAIR_VALUE << 28) | (STM32_PLLSAIQ_VALUE << 24);
+ RCC->DCKCFGR = (RCC->DCKCFGR & ~RCC_DCKCFGR_PLLSAIDIVR) | STM32_PLLSAIR_POST;
+ RCC->CR |= RCC_CR_PLLSAION;
+#endif
+
+ __HAL_RCC_DSI_CLK_ENABLE();
+
+ DSI_PLLInitTypeDef dsiPllInit;
+ DSI_CmdCfgTypeDef dsiCmdMode;
+ DSI_LPCmdTypeDef dsiAPBCmd;
+ /* Filling the DSI intialization struct. */
+ dsiHandle.Instance = DSI; // There is only one DSI interface
+ dsiHandle.Init.AutomaticClockLaneControl = DSI_AUTO_CLK_LANE_CTRL_ENABLE; // Automatic clock lane control: powers down the clock lane when not in use
+ /* Highest speed = 500MHz. */
+ uint16_t laneByteClk_kHz = 62500; /* 500 MHz / 8 = 62.5 MHz = 62500 kHz */
+ /* TXEscapeCkdiv = f(LaneByteClk)/15.62 = 4 -> 500MHz/4 = 25MHz datasheet says around 20MHz */
+ dsiHandle.Init.TXEscapeCkdiv = laneByteClk_kHz/15620; // Low power clock relative to the laneByteClock
+ dsiHandle.Init.NumberOfLanes = DSI_TWO_DATA_LANES; // Two data lines for the fastest transfer speed
+
+ /* Fill in the command mode struct. */
+ dsiCmdMode.VirtualChannelID = 0; // The first virtual channel
+
+ /* Select the appropriate color coding. */
+#ifdef GDISP_PIXELFORMAT_RGB565
+ dsiCmdMode.ColorCoding = DSI_RGB565;
+#else
+ dsiCmdMode.ColorCoding = DSI_RGB888;
+#endif
+
+ dsiCmdMode.CommandSize = driverCfg.width; // Amount of pixels sent at once -> one line at a time
+ dsiCmdMode.TearingEffectSource = DSI_TE_EXTERNAL; // Use pin PJ2
+ dsiCmdMode.TearingEffectPolarity = DSI_TE_RISING_EDGE;
+ dsiCmdMode.HSPolarity = DSI_HSYNC_ACTIVE_HIGH;
+ dsiCmdMode.VSPolarity = DSI_VSYNC_ACTIVE_HIGH;
+ dsiCmdMode.DEPolarity = DSI_DATA_ENABLE_ACTIVE_HIGH;
+ dsiCmdMode.VSyncPol = DSI_VSYNC_FALLING;
+ dsiCmdMode.AutomaticRefresh = DSI_AR_ENABLE; // Use the automatic refresh mode
+ dsiCmdMode.TEAcknowledgeRequest = DSI_TE_ACKNOWLEDGE_DISABLE; // Not needed when using TE through GPIO
+
+ /* GPIO configuration. */
+ GPIO_InitTypeDef gpioInit;
+ /* PH7 LCD_RESET */
+ __HAL_RCC_GPIOH_CLK_ENABLE();
+ gpioInit.Pin = GPIO_PIN_7;
+ gpioInit.Mode = GPIO_MODE_OUTPUT_OD;
+ gpioInit.Pull = GPIO_NOPULL;
+ gpioInit.Speed = GPIO_SPEED_HIGH;
+ HAL_GPIO_Init(GPIOH, &gpioInit);
+
+ /* PJ2 DSIHOST_TE */
+ __HAL_RCC_GPIOJ_CLK_ENABLE();
+ gpioInit.Pin = GPIO_PIN_2;
+ gpioInit.Mode = GPIO_MODE_AF_PP;
+ gpioInit.Alternate = GPIO_AF13_DSI;
+ HAL_GPIO_Init(GPIOJ, &gpioInit);
+
+ /* PA3 LCD_BL_CTRL This pin is not physically connected. */
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ gpioInit.Pin = GPIO_PIN_3;
+ gpioInit.Mode = GPIO_MODE_OUTPUT_OD;
+ HAL_GPIO_Init(GPIOA, &gpioInit);
+
+ /* Fvco = f(CLKin/IDF) * 2 * NDIV; fPHI = Fvco/(2*ODF) */
+#if !defined(USE_STM32469I_DISCO_REVA)
+ /* fPHI = CLKin*62.5; Fvco = CLKin*125 */
+ dsiPllInit.PLLNDIV = 125;
+ dsiPllInit.PLLIDF = DSI_PLL_IN_DIV2;
+#else
+ /* fPHI = CLKin*20; Fvco = CLKin*40 */
+ dsiPllInit.PLLNDIV = 100;
+ dsiPllInit.PLLIDF = DSI_PLL_IN_DIV5;
+#endif
+ dsiPllInit.PLLODF = DSI_PLL_OUT_DIV1;
+
+ /* Initialize the DSI peripheral. */
+ HAL_DSI_Init(&dsiHandle, &dsiPllInit);
+
+ DSI_PHY_TimerTypeDef PhyTimings;
+ /* Configure DSI PHY HS2LP and LP2HS timings. Datasheet says 95ns max */
+ PhyTimings.ClockLaneHS2LPTime = 35;
+ PhyTimings.ClockLaneLP2HSTime = 35;
+ PhyTimings.DataLaneHS2LPTime = 35;
+ PhyTimings.DataLaneLP2HSTime = 35;
+ PhyTimings.DataLaneMaxReadTime = 0;
+ PhyTimings.StopWaitTime = 10;
+ HAL_DSI_ConfigPhyTimer(&dsiHandle, &PhyTimings);
+
+ /* Configure adapted command mode. */
+ HAL_DSI_ConfigAdaptedCommandMode(&dsiHandle, &dsiCmdMode);
+
+ /* Hardware reset LCD */
+ reset_lcd(g);
+
+ /* Initialize the SDRAM */
+ BSP_SDRAM_Init();
+}
+
+static GFXINLINE void set_backlight(GDisplay* g, uint8_t percent)
+{
+ (void)g;
+ (void)percent;
+}
+
+/**
+ * @brief Perform a hardware reset on the LCD.
+ *
+ * @param g: Display parameter structure.
+ */
+static GFXINLINE void reset_lcd(GDisplay* g)
+{
+ (void)g;
+ /* Hardware display reset. */
+ HAL_GPIO_WritePin(GPIOH, GPIO_PIN_7, GPIO_PIN_RESET);
+ gfxSleepMilliseconds(20);
+ HAL_GPIO_WritePin(GPIOH, GPIO_PIN_7, GPIO_PIN_SET);
+ gfxSleepMilliseconds(10);
+ /* Turn on backlight. */
+ HAL_GPIO_WritePin(GPIOA, GPIO_PIN_3, GPIO_PIN_RESET);
+}
+
+/**
+ * @brief Extra initialization that is performed after the LTDC intialization.
+ *
+ * @param g: Display paramter structure.
+ */
+static GFXINLINE void post_init_board(GDisplay* g)
+{
+ (void)g;
+ DSI_LPCmdTypeDef dsiAPBCmd;
+
+ /* Enable the DSI host and wrapper after the LTDC initialization
+ To avoid any synchronization issue, the DSI shall be started after enabling the LTDC */
+ HAL_DSI_Start(&dsiHandle);
+
+ /* The configuration commands for the LCD have to be send through the dsiAPBCmd
+ * interface as the adapted command mode only supports DCS, WMS and WMC commands. */
+ dsiAPBCmd.LPGenShortWriteNoP = DSI_LP_GSW0P_ENABLE; // Put everything in low power mode
+ dsiAPBCmd.LPGenShortWriteOneP = DSI_LP_GSW1P_ENABLE;
+ dsiAPBCmd.LPGenShortWriteTwoP = DSI_LP_GSW2P_ENABLE;
+ dsiAPBCmd.LPGenShortReadNoP = DSI_LP_GSR0P_ENABLE;
+ dsiAPBCmd.LPGenShortReadOneP = DSI_LP_GSR1P_ENABLE;
+ dsiAPBCmd.LPGenShortReadTwoP = DSI_LP_GSR2P_ENABLE;
+ dsiAPBCmd.LPGenLongWrite = DSI_LP_GLW_ENABLE;
+ dsiAPBCmd.LPDcsShortWriteNoP = DSI_LP_DSW0P_ENABLE;
+ dsiAPBCmd.LPDcsShortWriteOneP = DSI_LP_DSW1P_ENABLE;
+ dsiAPBCmd.LPDcsShortReadNoP = DSI_LP_DSR0P_ENABLE;
+ dsiAPBCmd.LPDcsLongWrite = DSI_LP_DLW_ENABLE;
+ HAL_DSI_ConfigCommand(&dsiHandle, &dsiAPBCmd);
+
+ /* Configure the LCD. */
+#ifdef GDISP_PIXELFORMAT_RGB565
+ OTM8009A_Init(OTM8009A_FORMAT_RBG565, 1);
+#else
+ OTM8009A_Init(OTM8009A_FORMAT_RGB888, 1);
+#endif
+
+ /* Enable the tearing effect line. */
+ HAL_DSI_ShortWrite(&dsiHandle, 0, DSI_DCS_SHORT_PKT_WRITE_P1, DSI_SET_TEAR_ON, 0); // Only V-Blanking info
+
+ /* Disable the APB command mode again to go into adapted command mode. (going into high speed mode) */
+ dsiAPBCmd.LPGenShortWriteNoP = DSI_LP_GSW0P_DISABLE;
+ dsiAPBCmd.LPGenShortWriteOneP = DSI_LP_GSW1P_DISABLE;
+ dsiAPBCmd.LPGenShortWriteTwoP = DSI_LP_GSW2P_DISABLE;
+ dsiAPBCmd.LPGenShortReadNoP = DSI_LP_GSR0P_DISABLE;
+ dsiAPBCmd.LPGenShortReadOneP = DSI_LP_GSR1P_DISABLE;
+ dsiAPBCmd.LPGenShortReadTwoP = DSI_LP_GSR2P_DISABLE;
+ dsiAPBCmd.LPGenLongWrite = DSI_LP_GLW_DISABLE;
+ dsiAPBCmd.LPDcsShortWriteNoP = DSI_LP_DSW0P_DISABLE;
+ dsiAPBCmd.LPDcsShortWriteOneP = DSI_LP_DSW1P_DISABLE;
+ dsiAPBCmd.LPDcsShortReadNoP = DSI_LP_DSR0P_DISABLE;
+ dsiAPBCmd.LPDcsLongWrite = DSI_LP_DLW_DISABLE;
+ HAL_DSI_ConfigCommand(&dsiHandle, &dsiAPBCmd);
+
+ HAL_DSI_Refresh(&dsiHandle);
+}
+
+/**
+ * @brief DCS or Generic short/long write command
+ * @param NbrParams: Number of parameters. It indicates the write command mode:
+ * If inferior to 2, a long write command is performed else short.
+ * @param pParams: Pointer to parameter values table.
+ * @retval HAL status
+ */
+void DSI_IO_WriteCmd(uint32_t NbrParams, uint8_t *pParams)
+{
+ if(NbrParams <= 1)
+ {
+ HAL_DSI_ShortWrite(&dsiHandle, 0, DSI_DCS_SHORT_PKT_WRITE_P1, pParams[0], pParams[1]);
+ }
+ else
+ {
+ HAL_DSI_LongWrite(&dsiHandle, 0, DSI_DCS_LONG_PKT_WRITE, NbrParams, pParams[NbrParams], pParams);
+ }
+}
+
+/**
+ * @brief Delay function for the OTM8009A driver.
+ *
+ * @param Delay: The requested delay in ms.
+ */
+void OTM8009A_IO_Delay(uint32_t Delay)
+{
+ gfxSleepMilliseconds(Delay);
+}
+
+#endif /* _GDISP_LLD_BOARD_H */
diff --git a/boards/base/STM32F469i-Discovery/CubeHAL/ft6x06.h b/boards/base/STM32F469i-Discovery/CubeHAL/ft6x06.h
new file mode 100644
index 00000000..63545c4b
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/CubeHAL/ft6x06.h
@@ -0,0 +1,88 @@
+/*
+ * This file is subject to the terms of the GFX License. If a copy of
+ * the license was not distributed with this file, you can obtain one at:
+ *
+ * http://ugfx.org/license.html
+ */
+
+#ifndef _FT6x06_H
+#define _FT6x06_H
+
+// Slave address
+#define FT6x06_ADDR 0x70//(0x70 >> 1)
+
+// Maximum timeout
+#define FT6x06_TIMEOUT 0x3000
+
+#define FT6x06_DEVICE_MODE 0x00
+#define FT6x06_GESTURE_ID 0x01
+#define FT6x06_TOUCH_POINTS 0x02
+
+#define FT6x06_TOUCH1_EV_FLAG 0x03
+#define FT6x06_TOUCH1_XH 0x03
+#define FT6x06_TOUCH1_XL 0x04
+#define FT6x06_TOUCH1_YH 0x05
+#define FT6x06_TOUCH1_YL 0x06
+#define FT6x06_P1_WEIGHT 0x07
+#define FT6x06_P1_AREA 0x08
+
+#define FT6x06_TOUCH2_EV_FLAG 0x09
+#define FT6x06_TOUCH2_XH 0x09
+#define FT6x06_TOUCH2_XL 0x0A
+#define FT6x06_TOUCH2_YH 0x0B
+#define FT6x06_TOUCH2_YL 0x0C
+#define FT6x06_P2_WEIGHT 0x0D
+#define FT6x06_P2_AREA 0x0E
+
+#define FT6x06_TOUCH3_EV_FLAG 0x0F
+#define FT6x06_TOUCH3_XH 0x0F
+#define FT6x06_TOUCH3_XL 0x10
+#define FT6x06_TOUCH3_YH 0x11
+#define FT6x06_TOUCH3_YL 0x12
+#define FT6x06_P3_WEIGHT 0x13
+#define FT6x06_P3_AREA 0x14
+
+#define FT6x06_TOUCH4_EV_FLAG 0x15
+#define FT6x06_TOUCH4_XH 0x15
+#define FT6x06_TOUCH4_XL 0x16
+#define FT6x06_TOUCH4_YH 0x17
+#define FT6x06_TOUCH4_YL 0x18
+#define FT6x06_P4_WEIGHT 0x19
+#define FT6x06_P4_AREA 0x1A
+
+#define FT6x06_TOUCH5_EV_FLAG 0x1B
+#define FT6x06_TOUCH5_XH 0x1B
+#define FT6x06_TOUCH5_XL 0x1C
+#define FT6x06_TOUCH5_YH 0x1D
+#define FT6x06_TOUCH5_YL 0x1E
+#define FT6x06_P5_WEIGHT 0x1F
+#define FT6x06_P5_AREA 0x20
+
+#define FT6x06_ID_G_THGROUP 0x80
+#define FT6x06_ID_G_THPEAK 0x81
+#define FT6x06_ID_G_THCAL 0x82
+#define FT6x06_ID_G_THWATER 0x83
+#define FT6x06_ID_G_THTEMP 0x84
+#define FT6x06_ID_G_THDIFF 0x85
+#define FT6x06_ID_G_CTRL 0x86
+#define FT6x06_ID_G_TIME_ENTER_MONITOR 0x87
+#define FT6x06_ID_G_PERIODACTIVE 0x88
+#define FT6x06_ID_G_PERIODMONITOR 0x89
+#define FT6x06_RADIAN_VALUE 0x91
+#define FT6x06_OFFSET_LEFT_RIGHT 0x92
+#define FT6x06_OFFSET_UP_DOWN 0x93
+//#define FT6x06_OFFSET_LEFT_RIGHT 0x94
+#define FT6x06_DISTANCE_U_D 0x95
+#define FT6x06_DISTANCE_ZOOM 0x96
+#define FT6x06_ID_G_AUTO_CLB_MODE 0xA0
+#define FT6x06_ID_G_LIB_VERSION_H 0xA1
+#define FT6x06_ID_G_LIB_VERSION_L 0xA2
+#define FT6x06_ID_G_CIPHER 0xA3
+#define FT6x06_ID_G_MODE 0xA4
+#define FT6x06_ID_G_PMODE 0xA5
+#define FT6x06_ID_G_FIRMID 0xA6
+#define FT6x06_ID_G_STATE 0xA7
+#define FT6x06_ID_G_ID 0xA8
+#define FT6x06_ID_G_ERR 0xA9
+
+#endif /* _FT6x06_H */
diff --git a/boards/base/STM32F469i-Discovery/CubeHAL/gmouse_lld_FT6x06_board.h b/boards/base/STM32F469i-Discovery/CubeHAL/gmouse_lld_FT6x06_board.h
new file mode 100644
index 00000000..04f72a72
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/CubeHAL/gmouse_lld_FT6x06_board.h
@@ -0,0 +1,110 @@
+/*
+ * This file is subject to the terms of the GFX License. If a copy of
+ * the license was not distributed with this file, you can obtain one at:
+ *
+ * http://ugfx.org/license.html
+ */
+
+#ifndef _GINPUT_LLD_MOUSE_BOARD_H
+#define _GINPUT_LLD_MOUSE_BOARD_H
+
+#include "ft6x06.h"
+#include "stm32f4xx.h"
+#include "stm32f4xx_hal.h"
+
+// Resolution and Accuracy Settings
+#define GMOUSE_FT6x06_PEN_CALIBRATE_ERROR 40
+#define GMOUSE_FT6x06_PEN_CLICK_ERROR 16
+#define GMOUSE_FT6x06_PEN_MOVE_ERROR 14
+#define GMOUSE_FT6x06_FINGER_CALIBRATE_ERROR 50
+#define GMOUSE_FT6x06_FINGER_CLICK_ERROR 28
+#define GMOUSE_FT6x06_FINGER_MOVE_ERROR 24
+
+// How much extra data to allocate at the end of the GMouse structure for the board's use
+#define GMOUSE_FT6x06_BOARD_DATA_SIZE 0
+
+/* The FT6x06 I2C slave address */
+#define FT6x06_SLAVE_ADDR 0x54
+
+I2C_HandleTypeDef i2cHandle;
+/* Maximum speed (400kHz) */
+#define CLOCKSPEED 400000;
+
+static bool_t init_board(GMouse* m, unsigned instance) {
+ (void)m;
+ (void)instance;
+
+ GPIO_InitTypeDef gpioInit;
+ /* I2C1_SCL PB8 */
+ __HAL_RCC_GPIOB_CLK_ENABLE(); // Enable GPIOB clock
+ gpioInit.Pin = GPIO_PIN_8;
+ gpioInit.Mode = GPIO_MODE_AF_OD; // I2C -> Open-drain
+ gpioInit.Pull = GPIO_NOPULL; // Open-drain -> no pull
+ gpioInit.Speed = GPIO_SPEED_FREQ_HIGH; // High speed
+ gpioInit.Alternate = GPIO_AF4_I2C1; // Alternate function 4
+ HAL_GPIO_Init(GPIOB, &gpioInit);
+
+ /* I2C1_SDA PB9 */
+ gpioInit.Pin = GPIO_PIN_9;
+ HAL_GPIO_Init(GPIOB, &gpioInit);
+
+ /* LCD_INT PJ5 */
+ __HAL_RCC_GPIOJ_CLK_ENABLE();
+ gpioInit.Pin = GPIO_PIN_5;
+ gpioInit.Mode = GPIO_MODE_INPUT; // Input mode
+ gpioInit.Pull = GPIO_PULLUP; // Pull-up
+ HAL_GPIO_Init(GPIOJ, &gpioInit);
+
+ /* I2C1 intialization */
+ i2cHandle.Instance = I2C1;
+ i2cHandle.Init.ClockSpeed = CLOCKSPEED;
+ i2cHandle.Init.DutyCycle = I2C_DUTYCYCLE_2; // Normal duty cycle
+ i2cHandle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; // No dual adressing needed
+ i2cHandle.Init.OwnAddress1 = 0x00;
+ i2cHandle.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
+ i2cHandle.Init.OwnAddress2 = 0x00;
+ i2cHandle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; // All not needed so disabled
+ i2cHandle.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
+
+ __HAL_RCC_I2C1_CLK_ENABLE();
+
+ if(HAL_I2C_Init(&i2cHandle) == HAL_OK)
+ return TRUE;
+
+ return FALSE;
+}
+
+static GFXINLINE void aquire_bus(GMouse* m) {
+ (void)m;
+}
+
+static GFXINLINE void release_bus(GMouse* m) {
+ (void)m;
+}
+
+static void write_reg(GMouse* m, uint8_t reg, uint8_t val) {
+ (void)m;
+
+ HAL_I2C_Mem_Write(&i2cHandle, FT6x06_SLAVE_ADDR, (uint16_t)reg, I2C_MEMADD_SIZE_8BIT, &val, 1, 1000);
+}
+
+static uint8_t read_byte(GMouse* m, uint8_t reg) {
+ (void)m;
+ uint8_t result;
+
+ HAL_I2C_Mem_Read(&i2cHandle, FT6x06_SLAVE_ADDR, (uint16_t)reg, I2C_MEMADD_SIZE_8BIT, &result, 1, 1000);
+
+ return result;
+}
+
+static uint16_t read_word(GMouse* m, uint8_t reg) {
+ (void)m;
+ uint8_t result[2];
+
+ HAL_I2C_Mem_Read(&i2cHandle, FT6x06_SLAVE_ADDR, (uint16_t)reg, I2C_MEMADD_SIZE_8BIT, result, 2, 1000);
+
+ return (result[0]<<8 | result[1]);
+
+}
+
+#endif /* _GINPUT_LLD_MOUSE_BOARD_H */
diff --git a/boards/base/STM32F469i-Discovery/STM32_FLASH.ld b/boards/base/STM32F469i-Discovery/STM32_FLASH.ld
new file mode 100644
index 00000000..c1137c2f
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/STM32_FLASH.ld
@@ -0,0 +1,189 @@
+/*
+*****************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Abstract : Linker script for STM32F469NIHx Device with
+** 2048KByte FLASH, 320KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+** (c)Copyright Ac6.
+** You may use this file as-is or modify it according to the needs of your
+** project. Distribution of this file (unmodified or modified) is not
+** permitted. Ac6 permit registered System Workbench for MCU users the
+** rights to distribute the assembled, compiled & linked contents of this
+** file as part of an application binary file, provided that it is built
+** using the System Workbench for MCU toolchain.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20050000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200;; /* required amount of heap */
+_Min_Stack_Size = 0x400;; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 2048K
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 320K
+CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+ _siccmram = LOADADDR(.ccmram);
+
+ /* CCM-RAM section
+ *
+ * IMPORTANT NOTE!
+ * If initialized variables will be placed in this section,
+ * the startup code needs to be modified to copy the init-values.
+ */
+ .ccmram :
+ {
+ . = ALIGN(4);
+ _sccmram = .; /* create a global symbol at ccmram start */
+ *(.ccmram)
+ *(.ccmram*)
+
+ . = ALIGN(4);
+ _eccmram = .; /* create a global symbol at ccmram end */
+ } >CCMRAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(4);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(4);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/boards/base/STM32F469i-Discovery/board.mk b/boards/base/STM32F469i-Discovery/board.mk
new file mode 100644
index 00000000..ab704c17
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/board.mk
@@ -0,0 +1,33 @@
+GFXINC += $(GFXLIB)/boards/base/STM32F469i-Discovery \
+ $(GFXLIB)/boards/base/STM32F469i-Discovery/CubeHAL \
+ $(STMHAL)/Inc
+
+GFXSRC += $(GFXLIB)/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.c
+
+ifeq ($(OPT_OS),raw32)
+ GFXDEFS += STM32F469xx
+ GFXSRC += $(STMHAL)/Src/stm32f4xx_hal.c \
+ $(STMHAL)/Src/stm32f4xx_hal_cortex.c \
+ $(STMHAL)/Src/stm32f4xx_hal_rcc.c \
+ $(STMHAL)/Src/stm32f4xx_hal_rcc_ex.h \
+ $(STMHAL)/Src/stm32f4xx_hal_gpio.c \
+ $(STMHAL)/Src/stm32f4xx_hal_pwr.c \
+ $(STMHAL)/Src/stm32f4xx_hal_pwr_ex.c \
+ $(STMHAL)/Src/stm32f4xx_hal_dma.c \
+ $(STMHAL)/Src/stm32f4xx_hal_i2c.c \
+ $(STMHAL)/Src/stm32f4xx_hal_sdram.c \
+ $(STMHAL)/Src/stm32f4xx_hal_dsi.c \
+ $(STMHAL)/Src/stm32f4xx_ll_fmc.c \
+ $(GFXLIB)/boards/base/STM32F469i-Discovery/otm8009a.c
+ GFXSRC += $(GFXLIB)/boards/base/STM32F469i-Discovery/startup_stm32f469xx.s \
+ $(GFXLIB)/boards/base/STM32F469i-Discovery/stm32f469i_raw32_ugfx.c \
+ $(GFXLIB)/boards/base/STM32F469i-Discovery/stm32f469i_raw32_system.c \
+ $(GFXLIB)/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.c
+ GFXDEFS += GFX_OS_PRE_INIT_FUNCTION=Raw32OSInit GFX_OS_INIT_NO_WARNING=TRUE
+ GFXINC += $(CMSIS)/Device/ST/STM32F4xx/Include \
+ $(CMSIS)/Include
+ LDSCRIPT = $(GFXLIB)/boards/base/STM32F469i-Discovery/STM32_FLASH.ld
+endif
+
+include $(GFXLIB)/drivers/gdisp/STM32LTDC/driver.mk
+include $(GFXLIB)/drivers/ginput/touch/FT6x06/driver.mk
diff --git a/boards/base/STM32F469i-Discovery/board_STM32LTDC.h b/boards/base/STM32F469i-Discovery/board_STM32LTDC.h
deleted file mode 100644
index cd87d89e..00000000
--- a/boards/base/STM32F469i-Discovery/board_STM32LTDC.h
+++ /dev/null
@@ -1,292 +0,0 @@
-/*
- * This file is subject to the terms of the GFX License. If a copy of
- * the license was not distributed with this file, you can obtain one at:
- *
- * http://ugfx.org/license.html
- */
-
-#ifndef _GDISP_LLD_BOARD_H
-#define _GDISP_LLD_BOARD_H
-
-// Avoid naming collisions with CubeHAL
-#undef Red
-#undef Green
-#undef Blue
-
-// Don't allow the driver to init the LTDC clock. We will do it here
-#define LTDC_NO_CLOCK_INIT TRUE
-
-//#include "stm32f4xx_hal.h"
-//#include "stm32f4xx_hal_sdram.h"
-//#include "stm32f4xx_hal_rcc.h"
-//#include "stm32f4xx_hal_gpio.h"
-//#include "stm32f4xx_hal_ltdc.h"
-#include "stm32469i_discovery_lcd.h"
-
- LTDC_HandleTypeDef hltdc_eval;
- static DSI_VidCfgTypeDef hdsivideo_handle;
- DSI_HandleTypeDef hdsi_eval;
-
-#define ALLOW_2ND_LAYER FALSE // Do we really have the RAM bandwidth for this?
-
-// Panel parameters
-// This panel is a KoD KM-040TMP-02-0621 DSI LCD Display.
-
-static const ltdcConfig driverCfg = {
- 800, 480, // Width, Height (pixels)
- 120, 12, // Horizontal, Vertical sync (pixels)
- 120, 12, // Horizontal, Vertical back porch (pixels)
- 120, 12, // Horizontal, Vertical front porch (pixels)
- 0, // Sync flags
- 0x000000, // Clear color (RGB888)
-
- { // Background layer config
- (LLDCOLOR_TYPE *)SDRAM_DEVICE_ADDR, // Frame buffer address
- 800, 480, // Width, Height (pixels)
- 800 * LTDC_PIXELBYTES, // Line pitch (bytes)
- LTDC_PIXELFORMAT, // Pixel format
- 0, 0, // Start pixel position (x, y)
- 800, 480, // Size of virtual layer (cx, cy)
- 0x00000000, // Default color (ARGB8888)
- 0x000000, // Color key (RGB888)
- LTDC_BLEND_FIX1_FIX2, // Blending factors
- 0, // Palette (RGB888, can be NULL)
- 0, // Palette length
- 0xFF, // Constant alpha factor
- LTDC_LEF_ENABLE // Layer configuration flags
- },
-
-#if ALLOW_2ND_LAYER
- { // Foreground layer config (if turned on)
- (LLDCOLOR_TYPE *)(SDRAM_DEVICE_ADDR+(800 * 480 * LTDC_PIXELBYTES)), // Frame buffer address
- 800, 480, // Width, Height (pixels)
- 800 * LTDC_PIXELBYTES, // Line pitch (bytes)
- LTDC_PIXELFORMAT, // Pixel format
- 0, 0, // Start pixel position (x, y)
- 800, 480, // Size of virtual layer (cx, cy)
- 0x00000000, // Default color (ARGB8888)
- 0x000000, // Color key (RGB888)
- LTDC_BLEND_MOD1_MOD2, // Blending factors
- 0, // Palette (RGB888, can be NULL)
- 0, // Palette length
- 0xFF, // Constant alpha factor
- LTDC_LEF_ENABLE // Layer configuration flags
- }
-#else
- LTDC_UNUSED_LAYER_CONFIG
-#endif
-};
-
-/* Display timing */
-#define KoD_FREQUENCY_DIVIDER 7
-
-static GFXINLINE void init_board(GDisplay *g) {
- (void) g;
-
- DSI_PLLInitTypeDef dsiPllInit;
- DSI_PHY_TimerTypeDef PhyTimings;
-// static RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
- uint32_t LcdClock = 30000;//27429; /*!< LcdClk = 27429 kHz */
-
- /**
- * @brief Default Active LTDC Layer in which drawing is made is LTDC Layer Background
- */
-// static uint32_t ActiveLayer = LTDC_ACTIVE_LAYER_BACKGROUND;
-
- /**
- * @brief Current Drawing Layer properties variable
- */
-// static LCD_DrawPropTypeDef DrawProp[LTDC_MAX_LAYER_NUMBER];
-
- uint32_t laneByteClk_kHz = 0;
- uint32_t VSA; /*!< Vertical start active time in units of lines */
- uint32_t VBP; /*!< Vertical Back Porch time in units of lines */
- uint32_t VFP; /*!< Vertical Front Porch time in units of lines */
- uint32_t VACT; /*!< Vertical Active time in units of lines = imageSize Y in pixels to display */
- uint32_t HSA; /*!< Horizontal start active time in units of lcdClk */
- uint32_t HBP; /*!< Horizontal Back Porch time in units of lcdClk */
- uint32_t HFP; /*!< Horizontal Front Porch time in units of lcdClk */
- uint32_t HACT; /*!< Horizontal Active time in units of lcdClk = imageSize X in pixels to display */
-
-
- /* Toggle Hardware Reset of the DSI LCD using
- * its XRES signal (active low) */
- BSP_LCD_Reset();
-
- /* Call first MSP Initialize only in case of first initialization
- * This will set IP blocks LTDC, DSI and DMA2D
- * - out of reset
- * - clocked
- * - NVIC IRQ related to IP blocks enabled
- */
- BSP_LCD_MspInit();
-
- /*************************DSI Initialization***********************************/
-
- /* Base address of DSI Host/Wrapper registers to be set before calling De-Init */
- hdsi_eval.Instance = DSI;
-
- HAL_DSI_DeInit(&(hdsi_eval));
-
- #if !defined(USE_STM32469I_DISCO_REVA)
- dsiPllInit.PLLNDIV = 125;
- dsiPllInit.PLLIDF = DSI_PLL_IN_DIV2;
- dsiPllInit.PLLODF = DSI_PLL_OUT_DIV1;
- #else
- dsiPllInit.PLLNDIV = 100;
- dsiPllInit.PLLIDF = DSI_PLL_IN_DIV5;
- dsiPllInit.PLLODF = DSI_PLL_OUT_DIV1;
- #endif
- laneByteClk_kHz = 62500; /* 500 MHz / 8 = 62.5 MHz = 62500 kHz */
-
- /* Set number of Lanes */
- hdsi_eval.Init.NumberOfLanes = DSI_TWO_DATA_LANES;
-
- /* TXEscapeCkdiv = f(LaneByteClk)/15.62 = 4 */
- hdsi_eval.Init.TXEscapeCkdiv = laneByteClk_kHz/15620;
-
- HAL_DSI_Init(&(hdsi_eval), &(dsiPllInit));
-
- /* Timing parameters for all Video modes
- * Set Timing parameters of LTDC depending on its chosen orientation
- */
-
- /* lcd_orientation == LCD_ORIENTATION_LANDSCAPE */
- uint32_t lcd_x_size = OTM8009A_800X480_WIDTH; /* 800 */
- uint32_t lcd_y_size = OTM8009A_800X480_HEIGHT; /* 480 */
-
- HACT = lcd_x_size;
- VACT = lcd_y_size;
-
- /* The following values are same for portrait and landscape orientations */
- VSA = 12;//OTM8009A_480X800_VSYNC; /* 12 */
- VBP = 12;//OTM8009A_480X800_VBP; /* 12 */
- VFP = 12;//OTM8009A_480X800_VFP; /* 12 */
- HSA = 120;//OTM8009A_480X800_HSYNC; /* 63 */
- HBP = 120;//OTM8009A_480X800_HBP; /* 120 */
- HFP = 120;//OTM8009A_480X800_HFP; /* 120 */
-
- hdsivideo_handle.VirtualChannelID = LCD_OTM8009A_ID;
- hdsivideo_handle.ColorCoding = LCD_DSI_PIXEL_DATA_FMT_RBG888;
- hdsivideo_handle.VSPolarity = DSI_VSYNC_ACTIVE_HIGH;
- hdsivideo_handle.HSPolarity = DSI_HSYNC_ACTIVE_HIGH;
- hdsivideo_handle.DEPolarity = DSI_DATA_ENABLE_ACTIVE_HIGH;
- hdsivideo_handle.Mode = DSI_VID_MODE_BURST; /* Mode Video burst ie : one LgP per line */
- hdsivideo_handle.NullPacketSize = 0xFFF;
- hdsivideo_handle.NumberOfChunks = 0;
- hdsivideo_handle.PacketSize = HACT; /* Value depending on display orientation choice portrait/landscape */
- hdsivideo_handle.HorizontalSyncActive = (HSA * laneByteClk_kHz) / LcdClock;
- hdsivideo_handle.HorizontalBackPorch = (HBP * laneByteClk_kHz) / LcdClock;
- hdsivideo_handle.HorizontalLine = ((HACT + HSA + HBP + HFP) * laneByteClk_kHz) / LcdClock; /* Value depending on display orientation choice portrait/landscape */
- hdsivideo_handle.VerticalSyncActive = VSA;
- hdsivideo_handle.VerticalBackPorch = VBP;
- hdsivideo_handle.VerticalFrontPorch = VFP;
- hdsivideo_handle.VerticalActive = VACT; /* Value depending on display orientation choice portrait/landscape */
-
- /* Enable or disable sending LP command while streaming is active in video mode */
- hdsivideo_handle.LPCommandEnable = DSI_LP_COMMAND_ENABLE; /* Enable sending commands in mode LP (Low Power) */
-
- /* Largest packet size possible to transmit in LP mode in VSA, VBP, VFP regions */
- /* Only useful when sending LP packets is allowed while streaming is active in video mode */
- hdsivideo_handle.LPLargestPacketSize = 16;
-
- /* Largest packet size possible to transmit in LP mode in HFP region during VACT period */
- /* Only useful when sending LP packets is allowed while streaming is active in video mode */
- hdsivideo_handle.LPVACTLargestPacketSize = 0;
-
- /* Specify for each region of the video frame, if the transmission of command in LP mode is allowed in this region */
- /* while streaming is active in video mode */
- hdsivideo_handle.LPHorizontalFrontPorchEnable = DSI_LP_HFP_ENABLE; /* Allow sending LP commands during HFP period */
- hdsivideo_handle.LPHorizontalBackPorchEnable = DSI_LP_HBP_ENABLE; /* Allow sending LP commands during HBP period */
- hdsivideo_handle.LPVerticalActiveEnable = DSI_LP_VACT_ENABLE; /* Allow sending LP commands during VACT period */
- hdsivideo_handle.LPVerticalFrontPorchEnable = DSI_LP_VFP_ENABLE; /* Allow sending LP commands during VFP period */
- hdsivideo_handle.LPVerticalBackPorchEnable = DSI_LP_VBP_ENABLE; /* Allow sending LP commands during VBP period */
- hdsivideo_handle.LPVerticalSyncActiveEnable = DSI_LP_VSYNC_ENABLE; /* Allow sending LP commands during VSync = VSA period */
-
- /* Configure DSI Video mode timings with settings set above */
- HAL_DSI_ConfigVideoMode(&(hdsi_eval), &(hdsivideo_handle));
-
- /* Configure DSI PHY HS2LP and LP2HS timings */
- PhyTimings.ClockLaneHS2LPTime = 35;
- PhyTimings.ClockLaneLP2HSTime = 35;
- PhyTimings.DataLaneHS2LPTime = 35;
- PhyTimings.DataLaneLP2HSTime = 35;
- PhyTimings.DataLaneMaxReadTime = 0;
- PhyTimings.StopWaitTime = 10;
- HAL_DSI_ConfigPhyTimer(&hdsi_eval, &PhyTimings);
-
- /*************************End DSI Initialization*******************************/
-
- /************************LTDC Initialization***********************************/
-
- // KoD LCD clock configuration
- // PLLSAI_VCO Input = HSE_VALUE/PLL_M = 1 Mhz
- // PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN = 384 Mhz
- // PLLLCDCLK = PLLSAI_VCO Output/PLLSAIR = 384/7 = 54.857 Mhz
- // LTDC clock frequency = PLLLCDCLK / LTDC_PLLSAI_DIVR_2 = 54.857/2 = 27.429Mhz
- #define STM32_SAISRC_NOCLOCK (0 << 23) /**< No clock. */
- #define STM32_SAISRC_PLL (1 << 23) /**< SAI_CKIN is PLL. */
- #define STM32_SAIR_DIV2 (0 << 16) /**< R divided by 2. */
- #define STM32_SAIR_DIV4 (1 << 16) /**< R divided by 4. */
- #define STM32_SAIR_DIV8 (2 << 16) /**< R divided by 8. */
- #define STM32_SAIR_DIV16 (3 << 16) /**< R divided by 16. */
-
- #define STM32_PLLSAIN_VALUE 384
- #define STM32_PLLSAIQ_VALUE 4
- #define STM32_PLLSAIR_VALUE KoD_FREQUENCY_DIVIDER
- #define STM32_PLLSAIR_POST STM32_SAIR_DIV2
-
- RCC->PLLSAICFGR = (STM32_PLLSAIN_VALUE << 6) | (STM32_PLLSAIR_VALUE << 28) | (STM32_PLLSAIQ_VALUE << 24);
- RCC->DCKCFGR = (RCC->DCKCFGR & ~RCC_DCKCFGR_PLLSAIDIVR) | STM32_PLLSAIR_POST;
- RCC->CR |= RCC_CR_PLLSAION;
-
-// PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LTDC;
-// PeriphClkInitStruct.PLLSAI.PLLSAIN = 384;
-// PeriphClkInitStruct.PLLSAI.PLLSAIR = 7;
-// PeriphClkInitStruct.PLLSAIDivR = RCC_PLLSAIDIVR_2;
-// HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
-
- /* Get LTDC Configuration from DSI Configuration */
-// HAL_LTDC_StructInitFromVideoConfig(&(hltdc_eval), &(hdsivideo_handle));
-
- /* Initialize the LTDC */
-// HAL_LTDC_Init(&hltdc_eval);
-
- /* Enable the DSI host and wrapper : but LTDC is not started yet at this stage */
- HAL_DSI_Start(&(hdsi_eval));
-
- #if !defined(DATA_IN_ExtSDRAM)
- /* Initialize the SDRAM */
- BSP_SDRAM_Init();
- #endif /* DATA_IN_ExtSDRAM */
-
-}
-
-static GFXINLINE void post_init_board(GDisplay* g)
-{
- (void)g;
-
- if (g->controllerdisplay)
- return;
-
- /* Initialize the font */
- BSP_LCD_SetFont(&LCD_DEFAULT_FONT);
-
- /************************End LTDC Initialization*******************************/
-
-
- /***********************OTM8009A Initialization********************************/
-
- /* Initialize the OTM8009A LCD Display IC Driver (KoD LCD IC Driver)
- * depending on configuration set in 'hdsivideo_handle'.
- */
- OTM8009A_Init(OTM8009A_FORMAT_RGB888, OTM8009A_ORIENTATION_LANDSCAPE);
-}
-
-static GFXINLINE void set_backlight(GDisplay* g, uint8_t percent)
-{
- (void)g;
- (void)percent;
-}
-
-#endif /* _GDISP_LLD_BOARD_H */
diff --git a/boards/base/STM32F469i-Discovery/gmouse_lld_FT6x06_board.h b/boards/base/STM32F469i-Discovery/gmouse_lld_FT6x06_board.h
deleted file mode 100644
index ec07d5d0..00000000
--- a/boards/base/STM32F469i-Discovery/gmouse_lld_FT6x06_board.h
+++ /dev/null
@@ -1,85 +0,0 @@
-/*
- * This file is subject to the terms of the GFX License. If a copy of
- * the license was not distributed with this file, you can obtain one at:
- *
- * http://ugfx.org/license.html
- */
-
-#ifndef _GINPUT_LLD_MOUSE_BOARD_H
-#define _GINPUT_LLD_MOUSE_BOARD_H
-
-#include "tm_stm32_i2c.h"
-#include "stm32469i_discovery_ts.h"
-#include "ft6x06.h"
-
-// Resolution and Accuracy Settings
-#define GMOUSE_FT6x06_PEN_CALIBRATE_ERROR 8
-#define GMOUSE_FT6x06_PEN_CLICK_ERROR 6
-#define GMOUSE_FT6x06_PEN_MOVE_ERROR 4
-#define GMOUSE_FT6x06_FINGER_CALIBRATE_ERROR 14
-#define GMOUSE_FT6x06_FINGER_CLICK_ERROR 18
-#define GMOUSE_FT6x06_FINGER_MOVE_ERROR 14
-
-// How much extra data to allocate at the end of the GMouse structure for the board's use
-#define GMOUSE_FT6x06_BOARD_DATA_SIZE 0
-
-// Set this to TRUE if you want self-calibration.
-// NOTE: This is not as accurate as real calibration.
-// It requires the orientation of the touch panel to match the display.
-// It requires the active area of the touch panel to exactly match the display size.
-//#define GMOUSE_FT6x06_SELF_CALIBRATE TRUE
-
-#define FT6x06_SLAVE_ADDR 0x54
-
-static bool_t init_board(GMouse* m, unsigned driverinstance) {
- (void)m;
-
- TS_StateTypeDef ts_state;
-
- return TS_OK == BSP_TS_Init(BSP_LCD_GetXSize(), BSP_LCD_GetYSize());
-}
-
-#define aquire_bus(m)
-#define release_bus(m);
-
-static void write_reg(GMouse* m, uint8_t reg, uint8_t val) {
- (void)m;
-
- //TM_I2C_Write(I2C1, FT6x06_SLAVE_ADDR, reg, val);
-}
-
-static uint8_t read_byte(GMouse* m, uint8_t reg) {
- (void)m;
-
- /*uint8_t data;
- TM_I2C_Read(I2C1, FT6x06_SLAVE_ADDR, reg, &data);
- return data;*/
- TS_StateTypeDef ts_state;
- if(reg == FT6x06_TOUCH_POINTS){
- if (TS_OK != BSP_TS_GetState(&ts_state))
- {
- return FALSE;
- }
- return ts_state.touchDetected;
- }
-}
-
-static uint16_t read_word(GMouse* m, uint8_t reg) {
- (void)m;
-
- /*uint8_t data[2];
- TM_I2C_ReadMulti(I2C1, FT6x06_SLAVE_ADDR, reg, data, 2);
- return (data[1]<<8 | data[0]);*/
-
- TS_StateTypeDef ts_state;
- if (TS_OK == BSP_TS_GetState(&ts_state))
- {
- if(reg == FT6x06_TOUCH1_XH){
- return (coord_t)ts_state.touchX[0];
- }else if(reg == FT6x06_TOUCH1_YH){
- return (coord_t)ts_state.touchY[0];
- }
- }
-}
-
-#endif /* _GINPUT_LLD_MOUSE_BOARD_H */
diff --git a/boards/base/STM32F469i-Discovery/otm8009a.c b/boards/base/STM32F469i-Discovery/otm8009a.c
new file mode 100644
index 00000000..d408efe6
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/otm8009a.c
@@ -0,0 +1,454 @@
+/**
+ ******************************************************************************
+ * @file otm8009a.c
+ * @author MCD Application Team
+ * @version V1.0.2
+ * @date 27-January-2017
+ * @brief This file provides the LCD Driver for KoD KM-040TMP-02-0621 (WVGA)
+ * DSI LCD Display OTM8009A.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "otm8009a.h"
+
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @addtogroup Components
+ * @{
+ */
+
+/** @defgroup OTM8009A OTM8009A
+ * @brief This file provides a set of functions needed to drive the
+ * otm8009a IC display driver.
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup OTM8009A_Private_Constants OTM8009A Private Constants
+ * @{
+ */
+
+/*
+ * @brief Constant tables of register settings used to transmit DSI
+ * command packets as power up initialization sequence of the KoD LCD (OTM8009A LCD Driver)
+ */
+const uint8_t lcdRegData1[] = {0x80,0x09,0x01,0xFF};
+const uint8_t lcdRegData2[] = {0x80,0x09,0xFF};
+const uint8_t lcdRegData3[] = {0x00,0x09,0x0F,0x0E,0x07,0x10,0x0B,0x0A,0x04,0x07,0x0B,0x08,0x0F,0x10,0x0A,0x01,0xE1};
+const uint8_t lcdRegData4[] = {0x00,0x09,0x0F,0x0E,0x07,0x10,0x0B,0x0A,0x04,0x07,0x0B,0x08,0x0F,0x10,0x0A,0x01,0xE2};
+const uint8_t lcdRegData5[] = {0x79,0x79,0xD8};
+const uint8_t lcdRegData6[] = {0x00,0x01,0xB3};
+const uint8_t lcdRegData7[] = {0x85,0x01,0x00,0x84,0x01,0x00,0xCE};
+const uint8_t lcdRegData8[] = {0x18,0x04,0x03,0x39,0x00,0x00,0x00,0x18,0x03,0x03,0x3A,0x00,0x00,0x00,0xCE};
+const uint8_t lcdRegData9[] = {0x18,0x02,0x03,0x3B,0x00,0x00,0x00,0x18,0x01,0x03,0x3C,0x00,0x00,0x00,0xCE};
+const uint8_t lcdRegData10[] = {0x01,0x01,0x20,0x20,0x00,0x00,0x01,0x02,0x00,0x00,0xCF};
+const uint8_t lcdRegData11[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData12[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData13[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData14[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData15[] = {0x00,0x04,0x04,0x04,0x04,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData16[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x04,0x04,0x04,0x04,0x04,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData17[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCB};
+const uint8_t lcdRegData18[] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xCB};
+const uint8_t lcdRegData19[] = {0x00,0x26,0x09,0x0B,0x01,0x25,0x00,0x00,0x00,0x00,0xCC};
+const uint8_t lcdRegData20[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x26,0x0A,0x0C,0x02,0xCC};
+const uint8_t lcdRegData21[] = {0x25,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCC};
+const uint8_t lcdRegData22[] = {0x00,0x25,0x0C,0x0A,0x02,0x26,0x00,0x00,0x00,0x00,0xCC};
+const uint8_t lcdRegData23[] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x25,0x0B,0x09,0x01,0xCC};
+const uint8_t lcdRegData24[] = {0x26,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xCC};
+const uint8_t lcdRegData25[] = {0xFF,0xFF,0xFF,0xFF};
+/*
+ * CASET value (Column Address Set) : X direction LCD GRAM boundaries
+ * depending on LCD orientation mode and PASET value (Page Address Set) : Y direction
+ * LCD GRAM boundaries depending on LCD orientation mode
+ * XS[15:0] = 0x000 = 0, XE[15:0] = 0x31F = 799 for landscape mode : apply to CASET
+ * YS[15:0] = 0x000 = 0, YE[15:0] = 0x31F = 799 for portrait mode : : apply to PASET
+ */
+const uint8_t lcdRegData27[] = {0x00, 0x00, 0x03, 0x1F, OTM8009A_CMD_CASET};
+/*
+ * XS[15:0] = 0x000 = 0, XE[15:0] = 0x1DF = 479 for portrait mode : apply to CASET
+ * YS[15:0] = 0x000 = 0, YE[15:0] = 0x1DF = 479 for landscape mode : apply to PASET
+ */
+const uint8_t lcdRegData28[] = {0x00, 0x00, 0x01, 0xDF, OTM8009A_CMD_PASET};
+
+
+const uint8_t ShortRegData1[] = {OTM8009A_CMD_NOP, 0x00};
+const uint8_t ShortRegData2[] = {OTM8009A_CMD_NOP, 0x80};
+const uint8_t ShortRegData3[] = {0xC4, 0x30};
+const uint8_t ShortRegData4[] = {OTM8009A_CMD_NOP, 0x8A};
+const uint8_t ShortRegData5[] = {0xC4, 0x40};
+const uint8_t ShortRegData6[] = {OTM8009A_CMD_NOP, 0xB1};
+const uint8_t ShortRegData7[] = {0xC5, 0xA9};
+const uint8_t ShortRegData8[] = {OTM8009A_CMD_NOP, 0x91};
+const uint8_t ShortRegData9[] = {0xC5, 0x34};
+const uint8_t ShortRegData10[] = {OTM8009A_CMD_NOP, 0xB4};
+const uint8_t ShortRegData11[] = {0xC0, 0x50};
+const uint8_t ShortRegData12[] = {0xD9, 0x4E};
+const uint8_t ShortRegData13[] = {OTM8009A_CMD_NOP, 0x81};
+const uint8_t ShortRegData14[] = {0xC1, 0x66};
+const uint8_t ShortRegData15[] = {OTM8009A_CMD_NOP, 0xA1};
+const uint8_t ShortRegData16[] = {0xC1, 0x08};
+const uint8_t ShortRegData17[] = {OTM8009A_CMD_NOP, 0x92};
+const uint8_t ShortRegData18[] = {0xC5, 0x01};
+const uint8_t ShortRegData19[] = {OTM8009A_CMD_NOP, 0x95};
+const uint8_t ShortRegData20[] = {OTM8009A_CMD_NOP, 0x94};
+const uint8_t ShortRegData21[] = {0xC5, 0x33};
+const uint8_t ShortRegData22[] = {OTM8009A_CMD_NOP, 0xA3};
+const uint8_t ShortRegData23[] = {0xC0, 0x1B};
+const uint8_t ShortRegData24[] = {OTM8009A_CMD_NOP, 0x82};
+const uint8_t ShortRegData25[] = {0xC5, 0x83};
+const uint8_t ShortRegData26[] = {0xC4, 0x83};
+const uint8_t ShortRegData27[] = {0xC1, 0x0E};
+const uint8_t ShortRegData28[] = {OTM8009A_CMD_NOP, 0xA6};
+const uint8_t ShortRegData29[] = {OTM8009A_CMD_NOP, 0xA0};
+const uint8_t ShortRegData30[] = {OTM8009A_CMD_NOP, 0xB0};
+const uint8_t ShortRegData31[] = {OTM8009A_CMD_NOP, 0xC0};
+const uint8_t ShortRegData32[] = {OTM8009A_CMD_NOP, 0xD0};
+const uint8_t ShortRegData33[] = {OTM8009A_CMD_NOP, 0x90};
+const uint8_t ShortRegData34[] = {OTM8009A_CMD_NOP, 0xE0};
+const uint8_t ShortRegData35[] = {OTM8009A_CMD_NOP, 0xF0};
+const uint8_t ShortRegData36[] = {OTM8009A_CMD_SLPOUT, 0x00};
+const uint8_t ShortRegData37[] = {OTM8009A_CMD_COLMOD, OTM8009A_COLMOD_RGB565};
+const uint8_t ShortRegData38[] = {OTM8009A_CMD_COLMOD, OTM8009A_COLMOD_RGB888};
+const uint8_t ShortRegData39[] = {OTM8009A_CMD_MADCTR, OTM8009A_MADCTR_MODE_LANDSCAPE};
+const uint8_t ShortRegData40[] = {OTM8009A_CMD_WRDISBV, 0x7F};
+const uint8_t ShortRegData41[] = {OTM8009A_CMD_WRCTRLD, 0x2C};
+const uint8_t ShortRegData42[] = {OTM8009A_CMD_WRCABC, 0x02};
+const uint8_t ShortRegData43[] = {OTM8009A_CMD_WRCABCMB, 0xFF};
+const uint8_t ShortRegData44[] = {OTM8009A_CMD_DISPON, 0x00};
+const uint8_t ShortRegData45[] = {OTM8009A_CMD_RAMWR, 0x00};
+const uint8_t ShortRegData46[] = {0xCF, 0x00};
+const uint8_t ShortRegData47[] = {0xC5, 0x66};
+const uint8_t ShortRegData48[] = {OTM8009A_CMD_NOP, 0xB6};
+const uint8_t ShortRegData49[] = {0xF5, 0x06};
+const uint8_t ShortRegData50[] = {OTM8009A_CMD_NOP, 0xB1};
+const uint8_t ShortRegData51[] = {0xC6, 0x06};
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/** @defgroup OTM8009A_Exported_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Exported functions ---------------------------------------------------------*/
+/** @defgroup OTM8009A_Exported_Functions OTM8009A Exported Functions
+ * @{
+ */
+
+/**
+ * @brief DSI IO write short/long command.
+ * @note : Can be surcharged by application code implementation of the function.
+ */
+__weak void DSI_IO_WriteCmd(uint32_t NbrParams, uint8_t *pParams)
+{
+ /* NOTE : This function Should not be modified, when it is needed,
+ the DSI_IO_WriteCmd could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Initializes the LCD KoD display part by communication in DSI mode in Video Mode
+ * with IC Display Driver OTM8009A (see IC Driver specification for more information).
+ * @param hdsi_eval : pointer on DSI configuration structure
+ * @param hdsivideo_handle : pointer on DSI video mode configuration structure
+ * @retval Status
+ */
+uint8_t OTM8009A_Init(uint32_t ColorCoding, uint32_t orientation)
+{
+ /* Enable CMD2 to access vendor specific commands */
+ /* Enter in command 2 mode and set EXTC to enable address shift function (0x00) */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+ DSI_IO_WriteCmd( 3, (uint8_t *)lcdRegData1);
+
+ /* Enter ORISE Command 2 */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData2); /* Shift address to 0x80 */
+ DSI_IO_WriteCmd( 2, (uint8_t *)lcdRegData2);
+
+ /////////////////////////////////////////////////////////////////////
+ /* SD_PCH_CTRL - 0xC480h - 129th parameter - Default 0x00 */
+ /* Set SD_PT */
+ /* -> Source output level during porch and non-display area to GND */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData2);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData3);
+ OTM8009A_IO_Delay(10);
+ /* Not documented */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData4);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData5);
+ OTM8009A_IO_Delay(10);
+ /////////////////////////////////////////////////////////////////////
+
+ /* PWR_CTRL4 - 0xC4B0h - 178th parameter - Default 0xA8 */
+ /* Set gvdd_en_test */
+ /* -> enable GVDD test mode !!! */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData6);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData7);
+
+ /* PWR_CTRL2 - 0xC590h - 146th parameter - Default 0x79 */
+ /* Set pump 4 vgh voltage */
+ /* -> from 15.0v down to 13.0v */
+ /* Set pump 5 vgh voltage */
+ /* -> from -12.0v downto -9.0v */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData8);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData9);
+
+ /* P_DRV_M - 0xC0B4h - 181th parameter - Default 0x00 */
+ /* -> Column inversion */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData10);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData11);
+
+ /* VCOMDC - 0xD900h - 1st parameter - Default 0x39h */
+ /* VCOM Voltage settings */
+ /* -> from -1.0000v downto -1.2625v */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData12);
+
+ /* Oscillator adjustment for Idle/Normal mode (LPDT only) set to 65Hz (default is 60Hz) */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData13);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData14);
+
+ /* Video mode internal */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData15);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData16);
+
+ /* PWR_CTRL2 - 0xC590h - 147h parameter - Default 0x00 */
+ /* Set pump 4&5 x6 */
+ /* -> ONLY VALID when PUMP4_EN_ASDM_HV = "0" */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData17);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData18);
+
+ /* PWR_CTRL2 - 0xC590h - 150th parameter - Default 0x33h */
+ /* Change pump4 clock ratio */
+ /* -> from 1 line to 1/2 line */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData19);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData9);
+
+ /* GVDD/NGVDD settings */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+ DSI_IO_WriteCmd( 2, (uint8_t *)lcdRegData5);
+
+ /* PWR_CTRL2 - 0xC590h - 149th parameter - Default 0x33h */
+ /* Rewrite the default value ! */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData20);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData21);
+
+ /* Panel display timing Setting 3 */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData22);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData23);
+
+ /* Power control 1 */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData24);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData25);
+
+ /* Source driver precharge */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData13);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData26);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData15);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData27);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData28);
+ DSI_IO_WriteCmd( 2, (uint8_t *)lcdRegData6);
+
+ /* GOAVST */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData2);
+ DSI_IO_WriteCmd( 6, (uint8_t *)lcdRegData7);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData29);
+ DSI_IO_WriteCmd( 14, (uint8_t *)lcdRegData8);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData30);
+ DSI_IO_WriteCmd( 14, (uint8_t *)lcdRegData9);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData31);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData10);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData32);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData46);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData2);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData11);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData33);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData12);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData29);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData13);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData30);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData14);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData31);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData15);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData32);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData16);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData34);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData17);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData35);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData18);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData2);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData19);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData33);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData20);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData29);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData21);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData30);
+ DSI_IO_WriteCmd( 10, (uint8_t *)lcdRegData22);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData31);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData23);
+
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData32);
+ DSI_IO_WriteCmd( 15, (uint8_t *)lcdRegData24);
+
+ /////////////////////////////////////////////////////////////////////////////
+ /* PWR_CTRL1 - 0xc580h - 130th parameter - default 0x00 */
+ /* Pump 1 min and max DM */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData13);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData47);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData48);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData49);
+ /////////////////////////////////////////////////////////////////////////////
+
+ /* CABC LEDPWM frequency adjusted to 19,5kHz */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData50);
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData51);
+
+ /* Exit CMD2 mode */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+ DSI_IO_WriteCmd( 3, (uint8_t *)lcdRegData25);
+
+ /*************************************************************************** */
+ /* Standard DCS Initialization TO KEEP CAN BE DONE IN HSDT */
+ /*************************************************************************** */
+
+ /* NOP - goes back to DCS std command ? */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+
+ /* Gamma correction 2.2+ table (HSDT possible) */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+ DSI_IO_WriteCmd( 16, (uint8_t *)lcdRegData3);
+
+ /* Gamma correction 2.2- table (HSDT possible) */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+ DSI_IO_WriteCmd( 16, (uint8_t *)lcdRegData4);
+
+ /* Send Sleep Out command to display : no parameter */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData36);
+
+ /* Wait for sleep out exit */
+ OTM8009A_IO_Delay(120);
+
+ switch(ColorCoding)
+ {
+ case OTM8009A_FORMAT_RBG565 :
+ /* Set Pixel color format to RGB565 */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData37);
+ break;
+ case OTM8009A_FORMAT_RGB888 :
+ /* Set Pixel color format to RGB888 */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData38);
+ break;
+ default :
+ break;
+ }
+
+ /* Send command to configure display in landscape orientation mode. By default
+ the orientation mode is portrait */
+ if(orientation == OTM8009A_ORIENTATION_LANDSCAPE)
+ {
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData39);
+ DSI_IO_WriteCmd( 4, (uint8_t *)lcdRegData27);
+ DSI_IO_WriteCmd( 4, (uint8_t *)lcdRegData28);
+ }
+
+ /** CABC : Content Adaptive Backlight Control section start >> */
+ /* Note : defaut is 0 (lowest Brightness), 0xFF is highest Brightness, try 0x7F : intermediate value */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData40);
+
+ /* defaut is 0, try 0x2C - Brightness Control Block, Display Dimming & BackLight on */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData41);
+
+ /* defaut is 0, try 0x02 - image Content based Adaptive Brightness [Still Picture] */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData42);
+
+ /* defaut is 0 (lowest Brightness), 0xFF is highest Brightness */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData43);
+
+ /** CABC : Content Adaptive Backlight Control section end << */
+
+ /* Send Command Display On */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData44);
+
+ /* NOP command */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData1);
+
+ /* Send Command GRAM memory write (no parameters) : this initiates frame write via other DSI commands sent by */
+ /* DSI host from LTDC incoming pixels in video mode */
+ DSI_IO_WriteCmd(0, (uint8_t *)ShortRegData45);
+
+ return 0;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/otm8009a.h b/boards/base/STM32F469i-Discovery/otm8009a.h
new file mode 100644
index 00000000..417d9b9b
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/otm8009a.h
@@ -0,0 +1,224 @@
+/**
+ ******************************************************************************
+ * @file otm8009a.h
+ * @author MCD Application Team
+ * @version V1.0.2
+ * @date 27-January-2017
+ * @brief This file contains all the constants parameters for the OTM8009A
+ * which is the LCD Driver for KoD KM-040TMP-02-0621 (WVGA)
+ * DSI LCD Display.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __OTM8009A_H
+#define __OTM8009A_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include <stdint.h>
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @addtogroup Components
+ * @{
+ */
+
+/** @addtogroup otm8009a
+ * @{
+ */
+
+/** @addtogroup OTM8009A_Exported_Variables
+ * @{
+ */
+
+#if defined ( __GNUC__ )
+#ifndef __weak
+#define __weak __attribute__((weak))
+#endif /* __weak */
+#endif /* __GNUC__ */
+
+/**
+ * @brief LCD_OrientationTypeDef
+ * Possible values of Display Orientation
+ */
+#define OTM8009A_ORIENTATION_PORTRAIT ((uint32_t)0x00) /* Portrait orientation choice of LCD screen */
+#define OTM8009A_ORIENTATION_LANDSCAPE ((uint32_t)0x01) /* Landscape orientation choice of LCD screen */
+
+/**
+ * @brief Possible values of
+ * pixel data format (ie color coding) transmitted on DSI Data lane in DSI packets
+ */
+#define OTM8009A_FORMAT_RGB888 ((uint32_t)0x00) /* Pixel format chosen is RGB888 : 24 bpp */
+#define OTM8009A_FORMAT_RBG565 ((uint32_t)0x02) /* Pixel format chosen is RGB565 : 16 bpp */
+
+/**
+ * @brief otm8009a_480x800 Size
+ */
+
+/* Width and Height in Portrait mode */
+#define OTM8009A_480X800_WIDTH ((uint16_t)480) /* LCD PIXEL WIDTH */
+#define OTM8009A_480X800_HEIGHT ((uint16_t)800) /* LCD PIXEL HEIGHT */
+
+/* Width and Height in Landscape mode */
+#define OTM8009A_800X480_WIDTH ((uint16_t)800) /* LCD PIXEL WIDTH */
+#define OTM8009A_800X480_HEIGHT ((uint16_t)480) /* LCD PIXEL HEIGHT */
+
+/**
+ * @brief OTM8009A_480X800 Timing parameters for Portrait orientation mode
+ */
+#define OTM8009A_480X800_HSYNC ((uint16_t)2) /* Horizontal synchronization */
+#define OTM8009A_480X800_HBP ((uint16_t)34) /* Horizontal back porch */
+#define OTM8009A_480X800_HFP ((uint16_t)34) /* Horizontal front porch */
+#define OTM8009A_480X800_VSYNC ((uint16_t)1) /* Vertical synchronization */
+#define OTM8009A_480X800_VBP ((uint16_t)15) /* Vertical back porch */
+#define OTM8009A_480X800_VFP ((uint16_t)16) /* Vertical front porch */
+
+/**
+ * @brief OTM8009A_800X480 Timing parameters for Landscape orientation mode
+ * Same values as for Portrait mode in fact.
+ */
+#define OTM8009A_800X480_HSYNC OTM8009A_480X800_VSYNC /* Horizontal synchronization */
+#define OTM8009A_800X480_HBP OTM8009A_480X800_VBP /* Horizontal back porch */
+#define OTM8009A_800X480_HFP OTM8009A_480X800_VFP /* Horizontal front porch */
+#define OTM8009A_800X480_VSYNC OTM8009A_480X800_HSYNC /* Vertical synchronization */
+#define OTM8009A_800X480_VBP OTM8009A_480X800_HBP /* Vertical back porch */
+#define OTM8009A_800X480_VFP OTM8009A_480X800_HFP /* Vertical front porch */
+
+
+/* List of OTM8009A used commands */
+/* Detailed in OTM8009A Data Sheet 'DATA_SHEET_OTM8009A_V0 92.pdf' */
+/* Version of 14 June 2012 */
+#define OTM8009A_CMD_NOP 0x00 /* NOP command */
+#define OTM8009A_CMD_SWRESET 0x01 /* Sw reset command */
+#define OTM8009A_CMD_RDDMADCTL 0x0B /* Read Display MADCTR command : read memory display access ctrl */
+#define OTM8009A_CMD_RDDCOLMOD 0x0C /* Read Display pixel format */
+#define OTM8009A_CMD_SLPIN 0x10 /* Sleep In command */
+#define OTM8009A_CMD_SLPOUT 0x11 /* Sleep Out command */
+#define OTM8009A_CMD_PTLON 0x12 /* Partial mode On command */
+
+#define OTM8009A_CMD_DISPOFF 0x28 /* Display Off command */
+#define OTM8009A_CMD_DISPON 0x29 /* Display On command */
+
+#define OTM8009A_CMD_CASET 0x2A /* Column address set command */
+#define OTM8009A_CMD_PASET 0x2B /* Page address set command */
+
+#define OTM8009A_CMD_RAMWR 0x2C /* Memory (GRAM) write command */
+#define OTM8009A_CMD_RAMRD 0x2E /* Memory (GRAM) read command */
+
+#define OTM8009A_CMD_PLTAR 0x30 /* Partial area command (4 parameters) */
+
+#define OTM8009A_CMD_TEOFF 0x34 /* Tearing Effect Line Off command : command with no parameter */
+
+#define OTM8009A_CMD_TEEON 0x35 /* Tearing Effect Line On command : command with 1 parameter 'TELOM' */
+
+/* Parameter TELOM : Tearing Effect Line Output Mode : possible values */
+#define OTM8009A_TEEON_TELOM_VBLANKING_INFO_ONLY 0x00
+#define OTM8009A_TEEON_TELOM_VBLANKING_AND_HBLANKING_INFO 0x01
+
+#define OTM8009A_CMD_MADCTR 0x36 /* Memory Access write control command */
+
+/* Possible used values of MADCTR */
+#define OTM8009A_MADCTR_MODE_PORTRAIT 0x00
+#define OTM8009A_MADCTR_MODE_LANDSCAPE 0x60 /* MY = 0, MX = 1, MV = 1, ML = 0, RGB = 0 */
+
+#define OTM8009A_CMD_IDMOFF 0x38 /* Idle mode Off command */
+#define OTM8009A_CMD_IDMON 0x39 /* Idle mode On command */
+
+#define OTM8009A_CMD_COLMOD 0x3A /* Interface Pixel format command */
+
+/* Possible values of COLMOD parameter corresponding to used pixel formats */
+#define OTM8009A_COLMOD_RGB565 0x55
+#define OTM8009A_COLMOD_RGB888 0x77
+
+#define OTM8009A_CMD_RAMWRC 0x3C /* Memory write continue command */
+#define OTM8009A_CMD_RAMRDC 0x3E /* Memory read continue command */
+
+#define OTM8009A_CMD_WRTESCN 0x44 /* Write Tearing Effect Scan line command */
+#define OTM8009A_CMD_RDSCNL 0x45 /* Read Tearing Effect Scan line command */
+
+/* CABC Management : ie : Content Adaptive Back light Control in IC OTM8009a */
+#define OTM8009A_CMD_WRDISBV 0x51 /* Write Display Brightness command */
+#define OTM8009A_CMD_WRCTRLD 0x53 /* Write CTRL Display command */
+#define OTM8009A_CMD_WRCABC 0x55 /* Write Content Adaptive Brightness command */
+#define OTM8009A_CMD_WRCABCMB 0x5E /* Write CABC Minimum Brightness command */
+
+/**
+ * @brief OTM8009A_480X800 frequency divider
+ */
+#define OTM8009A_480X800_FREQUENCY_DIVIDER 2 /* LCD Frequency divider */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+
+/** @defgroup OTM8009A_Exported_Macros OTM8009A Exported Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup OTM8009A_Exported_Functions
+ * @{
+ */
+void DSI_IO_WriteCmd(uint32_t NbrParams, uint8_t *pParams);
+uint8_t OTM8009A_Init(uint32_t ColorCoding, uint32_t orientation);
+void OTM8009A_IO_Delay(uint32_t Delay);
+/**
+ * @}
+ */
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __OTM8009A_480X800_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/startup_stm32f469xx.s b/boards/base/STM32F469i-Discovery/startup_stm32f469xx.s
new file mode 100644
index 00000000..8dded6a0
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/startup_stm32f469xx.s
@@ -0,0 +1,589 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32f469xx.s
+ * @author MCD Application Team
+ * @version V1.1.0
+ * @date 17-February-2017
+ * @brief STM32F469xx Devices vector table for GCC based toolchains.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
+
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+ bx lr
+
+.global WeakCInit
+WeakCInit:
+ mov pc, lr
+
+ .weak _init
+ .thumb_set _init,WeakCInit
+
+.global WeakCExit
+WeakCExit:
+ b WeakCExit
+
+ .weak exit
+ .thumb_set exit,WeakCExit
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ * @param None
+ * @retval None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+*******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+ g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+
+ /* External Interrupts */
+ .word WWDG_IRQHandler /* Window WatchDog */
+ .word PVD_IRQHandler /* PVD through EXTI Line detection */
+ .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */
+ .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */
+ .word FLASH_IRQHandler /* FLASH */
+ .word RCC_IRQHandler /* RCC */
+ .word EXTI0_IRQHandler /* EXTI Line0 */
+ .word EXTI1_IRQHandler /* EXTI Line1 */
+ .word EXTI2_IRQHandler /* EXTI Line2 */
+ .word EXTI3_IRQHandler /* EXTI Line3 */
+ .word EXTI4_IRQHandler /* EXTI Line4 */
+ .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */
+ .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */
+ .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */
+ .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */
+ .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */
+ .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */
+ .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */
+ .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */
+ .word CAN1_TX_IRQHandler /* CAN1 TX */
+ .word CAN1_RX0_IRQHandler /* CAN1 RX0 */
+ .word CAN1_RX1_IRQHandler /* CAN1 RX1 */
+ .word CAN1_SCE_IRQHandler /* CAN1 SCE */
+ .word EXTI9_5_IRQHandler /* External Line[9:5]s */
+ .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */
+ .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */
+ .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */
+ .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
+ .word TIM2_IRQHandler /* TIM2 */
+ .word TIM3_IRQHandler /* TIM3 */
+ .word TIM4_IRQHandler /* TIM4 */
+ .word I2C1_EV_IRQHandler /* I2C1 Event */
+ .word I2C1_ER_IRQHandler /* I2C1 Error */
+ .word I2C2_EV_IRQHandler /* I2C2 Event */
+ .word I2C2_ER_IRQHandler /* I2C2 Error */
+ .word SPI1_IRQHandler /* SPI1 */
+ .word SPI2_IRQHandler /* SPI2 */
+ .word USART1_IRQHandler /* USART1 */
+ .word USART2_IRQHandler /* USART2 */
+ .word USART3_IRQHandler /* USART3 */
+ .word EXTI15_10_IRQHandler /* External Line[15:10]s */
+ .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */
+ .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */
+ .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */
+ .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */
+ .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */
+ .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */
+ .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */
+ .word FMC_IRQHandler /* FMC */
+ .word SDIO_IRQHandler /* SDIO */
+ .word TIM5_IRQHandler /* TIM5 */
+ .word SPI3_IRQHandler /* SPI3 */
+ .word UART4_IRQHandler /* UART4 */
+ .word UART5_IRQHandler /* UART5 */
+ .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */
+ .word TIM7_IRQHandler /* TIM7 */
+ .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */
+ .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */
+ .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */
+ .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */
+ .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */
+ .word ETH_IRQHandler /* Ethernet */
+ .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */
+ .word CAN2_TX_IRQHandler /* CAN2 TX */
+ .word CAN2_RX0_IRQHandler /* CAN2 RX0 */
+ .word CAN2_RX1_IRQHandler /* CAN2 RX1 */
+ .word CAN2_SCE_IRQHandler /* CAN2 SCE */
+ .word OTG_FS_IRQHandler /* USB OTG FS */
+ .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */
+ .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */
+ .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */
+ .word USART6_IRQHandler /* USART6 */
+ .word I2C3_EV_IRQHandler /* I2C3 event */
+ .word I2C3_ER_IRQHandler /* I2C3 error */
+ .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */
+ .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */
+ .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */
+ .word OTG_HS_IRQHandler /* USB OTG HS */
+ .word DCMI_IRQHandler /* DCMI */
+ .word 0 /* Reserved */
+ .word HASH_RNG_IRQHandler /* Hash and Rng */
+ .word FPU_IRQHandler /* FPU */
+ .word UART7_IRQHandler /* UART7 */
+ .word UART8_IRQHandler /* UART8 */
+ .word SPI4_IRQHandler /* SPI4 */
+ .word SPI5_IRQHandler /* SPI5 */
+ .word SPI6_IRQHandler /* SPI6 */
+ .word SAI1_IRQHandler /* SAI1 */
+ .word LTDC_IRQHandler /* LTDC */
+ .word LTDC_ER_IRQHandler /* LTDC error */
+ .word DMA2D_IRQHandler /* DMA2D */
+ .word QUADSPI_IRQHandler /* QUADSPI */
+ .word DSI_IRQHandler /* DSI */
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_IRQHandler
+ .thumb_set PVD_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream0_IRQHandler
+ .thumb_set DMA1_Stream0_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream1_IRQHandler
+ .thumb_set DMA1_Stream1_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream2_IRQHandler
+ .thumb_set DMA1_Stream2_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream3_IRQHandler
+ .thumb_set DMA1_Stream3_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream4_IRQHandler
+ .thumb_set DMA1_Stream4_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream5_IRQHandler
+ .thumb_set DMA1_Stream5_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream6_IRQHandler
+ .thumb_set DMA1_Stream6_IRQHandler,Default_Handler
+
+ .weak ADC_IRQHandler
+ .thumb_set ADC_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM9_IRQHandler
+ .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM10_IRQHandler
+ .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_TIM11_IRQHandler
+ .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM4_IRQHandler
+ .thumb_set TIM4_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak OTG_FS_WKUP_IRQHandler
+ .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+
+ .weak TIM8_BRK_TIM12_IRQHandler
+ .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler
+
+ .weak TIM8_UP_TIM13_IRQHandler
+ .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler
+
+ .weak TIM8_TRG_COM_TIM14_IRQHandler
+ .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler
+
+ .weak TIM8_CC_IRQHandler
+ .thumb_set TIM8_CC_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream7_IRQHandler
+ .thumb_set DMA1_Stream7_IRQHandler,Default_Handler
+
+ .weak FMC_IRQHandler
+ .thumb_set FMC_IRQHandler,Default_Handler
+
+ .weak SDIO_IRQHandler
+ .thumb_set SDIO_IRQHandler,Default_Handler
+
+ .weak TIM5_IRQHandler
+ .thumb_set TIM5_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak UART4_IRQHandler
+ .thumb_set UART4_IRQHandler,Default_Handler
+
+ .weak UART5_IRQHandler
+ .thumb_set UART5_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream0_IRQHandler
+ .thumb_set DMA2_Stream0_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream1_IRQHandler
+ .thumb_set DMA2_Stream1_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream2_IRQHandler
+ .thumb_set DMA2_Stream2_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream3_IRQHandler
+ .thumb_set DMA2_Stream3_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream4_IRQHandler
+ .thumb_set DMA2_Stream4_IRQHandler,Default_Handler
+
+ .weak ETH_IRQHandler
+ .thumb_set ETH_IRQHandler,Default_Handler
+
+ .weak ETH_WKUP_IRQHandler
+ .thumb_set ETH_WKUP_IRQHandler,Default_Handler
+
+ .weak CAN2_TX_IRQHandler
+ .thumb_set CAN2_TX_IRQHandler,Default_Handler
+
+ .weak CAN2_RX0_IRQHandler
+ .thumb_set CAN2_RX0_IRQHandler,Default_Handler
+
+ .weak CAN2_RX1_IRQHandler
+ .thumb_set CAN2_RX1_IRQHandler,Default_Handler
+
+ .weak CAN2_SCE_IRQHandler
+ .thumb_set CAN2_SCE_IRQHandler,Default_Handler
+
+ .weak OTG_FS_IRQHandler
+ .thumb_set OTG_FS_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream5_IRQHandler
+ .thumb_set DMA2_Stream5_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream6_IRQHandler
+ .thumb_set DMA2_Stream6_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream7_IRQHandler
+ .thumb_set DMA2_Stream7_IRQHandler,Default_Handler
+
+ .weak USART6_IRQHandler
+ .thumb_set USART6_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak OTG_HS_EP1_OUT_IRQHandler
+ .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler
+
+ .weak OTG_HS_EP1_IN_IRQHandler
+ .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler
+
+ .weak OTG_HS_WKUP_IRQHandler
+ .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler
+
+ .weak OTG_HS_IRQHandler
+ .thumb_set OTG_HS_IRQHandler,Default_Handler
+
+ .weak DCMI_IRQHandler
+ .thumb_set DCMI_IRQHandler,Default_Handler
+
+ .weak HASH_RNG_IRQHandler
+ .thumb_set HASH_RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak UART7_IRQHandler
+ .thumb_set UART7_IRQHandler,Default_Handler
+
+ .weak UART8_IRQHandler
+ .thumb_set UART8_IRQHandler,Default_Handler
+
+ .weak SPI4_IRQHandler
+ .thumb_set SPI4_IRQHandler,Default_Handler
+
+ .weak SPI5_IRQHandler
+ .thumb_set SPI5_IRQHandler,Default_Handler
+
+ .weak SPI6_IRQHandler
+ .thumb_set SPI6_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak LTDC_IRQHandler
+ .thumb_set LTDC_IRQHandler,Default_Handler
+
+ .weak LTDC_ER_IRQHandler
+ .thumb_set LTDC_ER_IRQHandler,Default_Handler
+
+ .weak DMA2D_IRQHandler
+ .thumb_set DMA2D_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak DSI_IRQHandler
+ .thumb_set DSI_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
+
+
+
+
+
+
diff --git a/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.c b/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.c
new file mode 100644
index 00000000..8068db36
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.c
@@ -0,0 +1,529 @@
+/**
+ ******************************************************************************
+ * @file stm32469i_discovery_sdram.c
+ * @author MCD Application Team
+ * @version V2.0.0
+ * @date 27-January-2017
+ * @brief This file includes the SDRAM driver for the MT48LC4M32B2B5-7 memory
+ * device mounted on STM32469I-Discovery board.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/* File Info : -----------------------------------------------------------------
+ User NOTES
+1. How To use this driver:
+--------------------------
+ - This driver is used to drive the MT48LC4M32B2B5-7 SDRAM external memory mounted
+ on STM32469I-Discovery board.
+ - This driver does not need a specific component driver for the SDRAM device
+ to be included with.
+
+2. Driver description:
+---------------------
+ + Initialization steps:
+ o Initialize the SDRAM external memory using the BSP_SDRAM_Init() function. This
+ function includes the MSP layer hardware resources initialization and the
+ FMC controller configuration to interface with the external SDRAM memory.
+ o It contains the SDRAM initialization sequence to program the SDRAM external
+ device using the function BSP_SDRAM_Initialization_sequence(). Note that this
+ sequence is standard for all SDRAM devices, but can include some differences
+ from a device to another. If it is the case, the right sequence should be
+ implemented separately.
+
+ + SDRAM read/write operations
+ o SDRAM external memory can be accessed with read/write operations once it is
+ initialized.
+ Read/write operation can be performed with AHB access using the functions
+ BSP_SDRAM_ReadData()/BSP_SDRAM_WriteData(), or by DMA transfer using the functions
+ BSP_SDRAM_ReadData_DMA()/BSP_SDRAM_WriteData_DMA().
+ o The AHB access is performed with 32-bit width transaction, the DMA transfer
+ configuration is fixed at single (no burst) word transfer (see the
+ BSP_SDRAM_MspInit() weak function).
+ o User can implement his own functions for read/write access with his desired
+ configurations.
+ o If interrupt mode is used for DMA transfer, the function BSP_SDRAM_DMA_IRQHandler()
+ is called in IRQ handler file, to serve the generated interrupt once the DMA
+ transfer is complete.
+ o You can send a command to the SDRAM device in runtime using the function
+ BSP_SDRAM_Sendcmd(), and giving the desired command as parameter chosen between
+ the predefined commands of the "FMC_SDRAM_CommandTypeDef" structure.
+
+------------------------------------------------------------------------------*/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f469i_discovery_sdram.h"
+
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @addtogroup STM32469I_Discovery
+ * @{
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM STM32469I Discovery SDRAM
+ * @{
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Private_Types_Definitions STM32469I Discovery SDRAM Private TypesDef
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Private_Defines STM32469I Discovery SDRAM Private Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Private_Macros STM32469I Discovery SDRAM Private Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Private_Variables STM32469I Discovery SDRAM Private Variables
+ * @{
+ */
+static SDRAM_HandleTypeDef sdramHandle;
+static FMC_SDRAM_TimingTypeDef Timing;
+static FMC_SDRAM_CommandTypeDef Command;
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Private_Function_Prototypes STM32469I Discovery SDRAM Private Prototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Private_Functions STM32469I Discovery SDRAM Private Functions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I_Discovery_SDRAM_Exported_Functions STM32469I Discovery SDRAM Exported Functions
+ * @{
+ */
+
+/**
+ * @brief Initializes the SDRAM device.
+ * @retval SDRAM status
+ */
+uint8_t BSP_SDRAM_Init(void)
+{
+ static uint8_t sdramstatus = SDRAM_ERROR;
+
+ /* SDRAM device configuration */
+ sdramHandle.Instance = FMC_SDRAM_DEVICE;
+
+ /* Timing configuration for 90 MHz as SD clock frequency (System clock is up to 180 MHz) */
+ Timing.LoadToActiveDelay = 2;
+ Timing.ExitSelfRefreshDelay = 7;
+ Timing.SelfRefreshTime = 4;
+ Timing.RowCycleDelay = 7;
+ Timing.WriteRecoveryTime = 2;
+ Timing.RPDelay = 2;
+ Timing.RCDDelay = 2;
+
+ sdramHandle.Init.SDBank = FMC_SDRAM_BANK1;
+ sdramHandle.Init.ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_8;
+ sdramHandle.Init.RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_12;
+ sdramHandle.Init.MemoryDataWidth = SDRAM_MEMORY_WIDTH;
+ sdramHandle.Init.InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4;
+ sdramHandle.Init.CASLatency = FMC_SDRAM_CAS_LATENCY_3;
+ sdramHandle.Init.WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE;
+ sdramHandle.Init.SDClockPeriod = SDCLOCK_PERIOD;
+ sdramHandle.Init.ReadBurst = FMC_SDRAM_RBURST_ENABLE;
+ sdramHandle.Init.ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0;
+
+ /* SDRAM controller initialization */
+ /* __weak function can be surcharged by the application code */
+ BSP_SDRAM_MspInit(&sdramHandle, (void *)NULL);
+ if(HAL_SDRAM_Init(&sdramHandle, &Timing) != HAL_OK)
+ {
+ sdramstatus = SDRAM_ERROR;
+ }
+ else
+ {
+ sdramstatus = SDRAM_OK;
+ }
+
+ /* SDRAM initialization sequence */
+ BSP_SDRAM_Initialization_sequence(REFRESH_COUNT);
+
+ return sdramstatus;
+}
+
+/**
+ * @brief DeInitializes the SDRAM device.
+ * @retval SDRAM status : SDRAM_OK or SDRAM_ERROR.
+ */
+uint8_t BSP_SDRAM_DeInit(void)
+{
+ static uint8_t sdramstatus = SDRAM_ERROR;
+
+ /* SDRAM device configuration */
+ sdramHandle.Instance = FMC_SDRAM_DEVICE;
+
+ if(HAL_SDRAM_DeInit(&sdramHandle) == HAL_OK)
+ {
+ sdramstatus = SDRAM_OK;
+
+ /* SDRAM controller De-initialization */
+ BSP_SDRAM_MspDeInit(&sdramHandle, (void *)NULL);
+ }
+
+ return sdramstatus;
+}
+
+
+/**
+ * @brief Programs the SDRAM device.
+ * @param RefreshCount: SDRAM refresh counter value
+ */
+void BSP_SDRAM_Initialization_sequence(uint32_t RefreshCount)
+{
+ __IO uint32_t tmpmrd = 0;
+
+ /* Step 1: Configure a clock configuration enable command */
+ Command.CommandMode = FMC_SDRAM_CMD_CLK_ENABLE;
+ Command.CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command.AutoRefreshNumber = 1;
+ Command.ModeRegisterDefinition = 0;
+
+ /* Send the command */
+ HAL_SDRAM_SendCommand(&sdramHandle, &Command, SDRAM_TIMEOUT);
+
+ /* Step 2: Insert 100 us minimum delay */
+ /* Inserted delay is equal to 1 ms due to systick time base unit (ms) */
+ HAL_Delay(1);
+
+ /* Step 3: Configure a PALL (precharge all) command */
+ Command.CommandMode = FMC_SDRAM_CMD_PALL;
+ Command.CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command.AutoRefreshNumber = 1;
+ Command.ModeRegisterDefinition = 0;
+
+ /* Send the command */
+ HAL_SDRAM_SendCommand(&sdramHandle, &Command, SDRAM_TIMEOUT);
+
+ /* Step 4: Configure an Auto Refresh command */
+ Command.CommandMode = FMC_SDRAM_CMD_AUTOREFRESH_MODE;
+ Command.CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command.AutoRefreshNumber = 8;
+ Command.ModeRegisterDefinition = 0;
+
+ /* Send the command */
+ HAL_SDRAM_SendCommand(&sdramHandle, &Command, SDRAM_TIMEOUT);
+
+ /* Step 5: Program the external memory mode register */
+ tmpmrd = (uint32_t)SDRAM_MODEREG_BURST_LENGTH_1 |\
+ SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL |\
+ SDRAM_MODEREG_CAS_LATENCY_3 |\
+ SDRAM_MODEREG_OPERATING_MODE_STANDARD |\
+ SDRAM_MODEREG_WRITEBURST_MODE_SINGLE;
+
+ Command.CommandMode = FMC_SDRAM_CMD_LOAD_MODE;
+ Command.CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command.AutoRefreshNumber = 1;
+ Command.ModeRegisterDefinition = tmpmrd;
+
+ /* Send the command */
+ HAL_SDRAM_SendCommand(&sdramHandle, &Command, SDRAM_TIMEOUT);
+
+ /* Step 6: Set the refresh rate counter */
+ /* Set the device refresh rate */
+ HAL_SDRAM_ProgramRefreshRate(&sdramHandle, RefreshCount);
+}
+
+/**
+ * @brief Reads an mount of data from the SDRAM memory in polling mode.
+ * @param uwStartAddress: Read start address
+ * @param pData: Pointer to data to be read
+ * @param uwDataSize: Size of read data from the memory
+ * @retval SDRAM status : SDRAM_OK or SDRAM_ERROR.
+ */
+uint8_t BSP_SDRAM_ReadData(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize)
+{
+ if(HAL_SDRAM_Read_32b(&sdramHandle, (uint32_t *)uwStartAddress, pData, uwDataSize) != HAL_OK)
+ {
+ return SDRAM_ERROR;
+ }
+ else
+ {
+ return SDRAM_OK;
+ }
+}
+
+/**
+ * @brief Reads an mount of data from the SDRAM memory in DMA mode.
+ * @param uwStartAddress: Read start address
+ * @param pData: Pointer to data to be read
+ * @param uwDataSize: Size of read data from the memory
+ * @retval SDRAM status : SDRAM_OK or SDRAM_ERROR.
+ */
+uint8_t BSP_SDRAM_ReadData_DMA(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize)
+{
+ if(HAL_SDRAM_Read_DMA(&sdramHandle, (uint32_t *)uwStartAddress, pData, uwDataSize) != HAL_OK)
+ {
+ return SDRAM_ERROR;
+ }
+ else
+ {
+ return SDRAM_OK;
+ }
+}
+
+/**
+ * @brief Writes an mount of data to the SDRAM memory in polling mode.
+ * @param uwStartAddress: Write start address
+ * @param pData: Pointer to data to be written
+ * @param uwDataSize: Size of written data from the memory
+ * @retval SDRAM status : SDRAM_OK or SDRAM_ERROR.
+ */
+uint8_t BSP_SDRAM_WriteData(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize)
+{
+ if(HAL_SDRAM_Write_32b(&sdramHandle, (uint32_t *)uwStartAddress, pData, uwDataSize) != HAL_OK)
+ {
+ return SDRAM_ERROR;
+ }
+ else
+ {
+ return SDRAM_OK;
+ }
+}
+
+/**
+ * @brief Writes an mount of data to the SDRAM memory in DMA mode.
+ * @param uwStartAddress: Write start address
+ * @param pData: Pointer to data to be written
+ * @param uwDataSize: Size of written data from the memory
+ * @retval SDRAM status : SDRAM_OK or SDRAM_ERROR.
+ */
+uint8_t BSP_SDRAM_WriteData_DMA(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize)
+{
+ if(HAL_SDRAM_Write_DMA(&sdramHandle, (uint32_t *)uwStartAddress, pData, uwDataSize) != HAL_OK)
+ {
+ return SDRAM_ERROR;
+ }
+ else
+ {
+ return SDRAM_OK;
+ }
+}
+
+/**
+ * @brief Sends command to the SDRAM bank.
+ * @param SdramCmd: Pointer to SDRAM command structure
+ * @retval HAL status : SDRAM_OK or SDRAM_ERROR.
+ */
+uint8_t BSP_SDRAM_Sendcmd(FMC_SDRAM_CommandTypeDef *SdramCmd)
+{
+ if(HAL_SDRAM_SendCommand(&sdramHandle, SdramCmd, SDRAM_TIMEOUT) != HAL_OK)
+ {
+ return SDRAM_ERROR;
+ }
+ else
+ {
+ return SDRAM_OK;
+ }
+}
+
+/**
+ * @brief Handles SDRAM DMA transfer interrupt request.
+ */
+void BSP_SDRAM_DMA_IRQHandler(void)
+{
+ HAL_DMA_IRQHandler(sdramHandle.hdma);
+}
+
+/**
+ * @brief Initializes SDRAM MSP.
+ * @note This function can be surcharged by application code.
+ * @param hsdram: pointer on SDRAM handle
+ * @param Params: pointer on additional configuration parameters, can be NULL.
+ */
+__weak void BSP_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram, void *Params)
+{
+ static DMA_HandleTypeDef dma_handle;
+ GPIO_InitTypeDef gpio_init_structure;
+
+ if(hsdram != (SDRAM_HandleTypeDef *)NULL)
+ {
+ /* Enable FMC clock */
+ __HAL_RCC_FMC_CLK_ENABLE();
+
+ /* Enable chosen DMAx clock */
+ __DMAx_CLK_ENABLE();
+
+ /* Enable GPIOs clock */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOD_CLK_ENABLE();
+ __HAL_RCC_GPIOE_CLK_ENABLE();
+ __HAL_RCC_GPIOF_CLK_ENABLE();
+ __HAL_RCC_GPIOG_CLK_ENABLE();
+ __HAL_RCC_GPIOH_CLK_ENABLE();
+ __HAL_RCC_GPIOI_CLK_ENABLE();
+
+ /* Common GPIO configuration */
+ gpio_init_structure.Mode = GPIO_MODE_AF_PP;
+ gpio_init_structure.Pull = GPIO_PULLUP;
+ gpio_init_structure.Speed = GPIO_SPEED_FAST;
+ gpio_init_structure.Alternate = GPIO_AF12_FMC;
+
+ /* GPIOC configuration : PC0 is SDNWE */
+ gpio_init_structure.Pin = GPIO_PIN_0;
+ HAL_GPIO_Init(GPIOC, &gpio_init_structure);
+
+ /* GPIOD configuration */
+ gpio_init_structure.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_8| GPIO_PIN_9 | GPIO_PIN_10 |\
+ GPIO_PIN_14 | GPIO_PIN_15;
+
+
+ HAL_GPIO_Init(GPIOD, &gpio_init_structure);
+
+ /* GPIOE configuration */
+ gpio_init_structure.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_7| GPIO_PIN_8 | GPIO_PIN_9 |\
+ GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_14 |\
+ GPIO_PIN_15;
+
+ HAL_GPIO_Init(GPIOE, &gpio_init_structure);
+
+ /* GPIOF configuration */
+ gpio_init_structure.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2| GPIO_PIN_3 | GPIO_PIN_4 |\
+ GPIO_PIN_5 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_14 |\
+ GPIO_PIN_15;
+
+ HAL_GPIO_Init(GPIOF, &gpio_init_structure);
+
+ /* GPIOG configuration */
+ gpio_init_structure.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_4| GPIO_PIN_5 | GPIO_PIN_8 |\
+ GPIO_PIN_15;
+ HAL_GPIO_Init(GPIOG, &gpio_init_structure);
+
+ /* GPIOH configuration */
+ gpio_init_structure.Pin = GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_8 | GPIO_PIN_9 |\
+ GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_14 |\
+ GPIO_PIN_15;
+ HAL_GPIO_Init(GPIOH, &gpio_init_structure);
+
+ /* GPIOI configuration */
+ gpio_init_structure.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_4 |\
+ GPIO_PIN_5 | GPIO_PIN_6 | GPIO_PIN_7 | GPIO_PIN_9 | GPIO_PIN_10;
+ HAL_GPIO_Init(GPIOI, &gpio_init_structure);
+
+ /* Configure common DMA parameters */
+ dma_handle.Init.Channel = SDRAM_DMAx_CHANNEL;
+ dma_handle.Init.Direction = DMA_MEMORY_TO_MEMORY;
+ dma_handle.Init.PeriphInc = DMA_PINC_ENABLE;
+ dma_handle.Init.MemInc = DMA_MINC_ENABLE;
+ dma_handle.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
+ dma_handle.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
+ dma_handle.Init.Mode = DMA_NORMAL;
+ dma_handle.Init.Priority = DMA_PRIORITY_HIGH;
+ dma_handle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+ dma_handle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
+ dma_handle.Init.MemBurst = DMA_MBURST_SINGLE;
+ dma_handle.Init.PeriphBurst = DMA_PBURST_SINGLE;
+
+ dma_handle.Instance = SDRAM_DMAx_STREAM;
+
+ /* Associate the DMA handle */
+ __HAL_LINKDMA(hsdram, hdma, dma_handle);
+
+ /* Deinitialize the stream for new transfer */
+ HAL_DMA_DeInit(&dma_handle);
+
+ /* Configure the DMA stream */
+ HAL_DMA_Init(&dma_handle);
+
+ /* NVIC configuration for DMA transfer complete interrupt */
+ HAL_NVIC_SetPriority(SDRAM_DMAx_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(SDRAM_DMAx_IRQn);
+
+ } /* of if(hsdram != (SDRAM_HandleTypeDef *)NULL) */
+}
+
+/**
+ * @brief DeInitializes SDRAM MSP.
+ * @note This function can be surcharged by application code.
+ * @param hsdram: pointer on SDRAM handle
+ * @param Params: pointer on additional configuration parameters, can be NULL.
+ */
+__weak void BSP_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram, void *Params)
+{
+ static DMA_HandleTypeDef dma_handle;
+
+ if(hsdram != (SDRAM_HandleTypeDef *)NULL)
+ {
+ /* Disable NVIC configuration for DMA interrupt */
+ HAL_NVIC_DisableIRQ(SDRAM_DMAx_IRQn);
+
+ /* Deinitialize the stream for new transfer */
+ dma_handle.Instance = SDRAM_DMAx_STREAM;
+ HAL_DMA_DeInit(&dma_handle);
+
+ /* DeInit GPIO pins can be done in the application
+ (by surcharging this __weak function) */
+
+ /* GPIO pins clock, FMC clock and DMA clock can be shut down in the application
+ by surcharging this __weak function */
+
+ } /* of if(hsdram != (SDRAM_HandleTypeDef *)NULL) */
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.h b/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.h
new file mode 100644
index 00000000..6068644f
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/stm32f469i_discovery_sdram.h
@@ -0,0 +1,169 @@
+/**
+ ******************************************************************************
+ * @file stm32469i_discovery_sdram.h
+ * @author MCD Application Team
+ * @version V2.0.0
+ * @date 27-January-2017
+ * @brief This file contains the common defines and functions prototypes for
+ * the stm32469i_discovery_sdram.c driver.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32469I_DISCOVERY_SDRAM_H
+#define __STM32469I_DISCOVERY_SDRAM_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_hal.h"
+
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @addtogroup STM32469I_Discovery
+ * @{
+ */
+
+/** @addtogroup STM32469I-Discovery_SDRAM
+ * @{
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Exported_Types STM32469I Discovery SDRAM Exported Types
+ * @{
+ */
+
+/**
+ * @brief SDRAM status structure definition
+ */
+#define SDRAM_OK ((uint8_t)0x00)
+#define SDRAM_ERROR ((uint8_t)0x01)
+
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Exported_Constants STM32469I Discovery SDRAM Exported Constants
+ * @{
+ */
+#define SDRAM_DEVICE_ADDR ((uint32_t)0xC0000000)
+
+ /* SDRAM device size in Bytes */
+ #define SDRAM_DEVICE_SIZE ((uint32_t)0x1000000)
+
+#define SDRAM_MEMORY_WIDTH FMC_SDRAM_MEM_BUS_WIDTH_32
+#define SDCLOCK_PERIOD FMC_SDRAM_CLOCK_PERIOD_2
+
+/* SDRAM refresh counter (90 MHz SD clock) */
+#define REFRESH_COUNT ((uint32_t)0x0569)
+#define SDRAM_TIMEOUT ((uint32_t)0xFFFF)
+
+/* DMA definitions for SDRAM DMA transfer */
+#define __DMAx_CLK_ENABLE __HAL_RCC_DMA2_CLK_ENABLE
+#define __DMAx_CLK_DISABLE __HAL_RCC_DMA2_CLK_DISABLE
+#define SDRAM_DMAx_CHANNEL DMA_CHANNEL_0
+#define SDRAM_DMAx_STREAM DMA2_Stream0
+#define SDRAM_DMAx_IRQn DMA2_Stream0_IRQn
+#define SDRAM_DMAx_IRQHandler DMA2_Stream0_IRQHandler
+
+
+/**
+ * @brief FMC SDRAM Mode definition register defines
+ */
+#define SDRAM_MODEREG_BURST_LENGTH_1 ((uint16_t)0x0000)
+#define SDRAM_MODEREG_BURST_LENGTH_2 ((uint16_t)0x0001)
+#define SDRAM_MODEREG_BURST_LENGTH_4 ((uint16_t)0x0002)
+#define SDRAM_MODEREG_BURST_LENGTH_8 ((uint16_t)0x0004)
+#define SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL ((uint16_t)0x0000)
+#define SDRAM_MODEREG_BURST_TYPE_INTERLEAVED ((uint16_t)0x0008)
+#define SDRAM_MODEREG_CAS_LATENCY_2 ((uint16_t)0x0020)
+#define SDRAM_MODEREG_CAS_LATENCY_3 ((uint16_t)0x0030)
+#define SDRAM_MODEREG_OPERATING_MODE_STANDARD ((uint16_t)0x0000)
+#define SDRAM_MODEREG_WRITEBURST_MODE_PROGRAMMED ((uint16_t)0x0000)
+#define SDRAM_MODEREG_WRITEBURST_MODE_SINGLE ((uint16_t)0x0200)
+/**
+ * @}
+ */
+
+/** @defgroup STM32469I-Discovery_SDRAM_Exported_Macro STM32469I Discovery SDRAM Exported Macro
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @addtogroup STM32469I_Discovery_SDRAM_Exported_Functions
+ * @{
+ */
+uint8_t BSP_SDRAM_Init(void);
+uint8_t BSP_SDRAM_DeInit(void);
+void BSP_SDRAM_Initialization_sequence(uint32_t RefreshCount);
+uint8_t BSP_SDRAM_ReadData(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize);
+uint8_t BSP_SDRAM_ReadData_DMA(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize);
+uint8_t BSP_SDRAM_WriteData(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize);
+uint8_t BSP_SDRAM_WriteData_DMA(uint32_t uwStartAddress, uint32_t *pData, uint32_t uwDataSize);
+uint8_t BSP_SDRAM_Sendcmd(FMC_SDRAM_CommandTypeDef *SdramCmd);
+void BSP_SDRAM_DMA_IRQHandler(void);
+
+/* These function can be modified in case the current settings (e.g. DMA stream)
+ need to be changed for specific application needs */
+void BSP_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram, void *Params);
+void BSP_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram, void *Params);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32469I_DISCOVERY_SDRAM_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.c b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.c
new file mode 100644
index 00000000..0b6fdf84
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.c
@@ -0,0 +1,176 @@
+/**
+ ******************************************************************************
+ * @file Templates_LL/Src/stm32f4xx_it.c
+ * @author MCD Application Team
+ * @version V1.0.0
+ * @date 17-February-2017
+ * @brief Main Interrupt Service Routines.
+ * This file provides template for all exceptions handler and
+ * peripherals interrupt service routine.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f469i_raw32_it.h"
+
+/** @addtogroup STM32F4xx_LL_Examples
+ * @{
+ */
+
+/** @addtogroup Templates_LL
+ * @{
+ */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/******************************************************************************/
+/* Cortex-M4 Processor Exceptions Handlers */
+/******************************************************************************/
+
+/**
+ * @brief This function handles NMI exception.
+ * @param None
+ * @retval None
+ */
+void NMI_Handler(void)
+{
+}
+
+/**
+ * @brief This function handles Hard Fault exception.
+ * @param None
+ * @retval None
+ */
+void HardFault_Handler(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/**
+ * @brief This function handles Memory Manage exception.
+ * @param None
+ * @retval None
+ */
+void MemManage_Handler(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/**
+ * @brief This function handles Bus Fault exception.
+ * @param None
+ * @retval None
+ */
+void BusFault_Handler(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/**
+ * @brief This function handles Usage Fault exception.
+ * @param None
+ * @retval None
+ */
+void UsageFault_Handler(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/**
+ * @brief This function handles SVCall exception.
+ * @param None
+ * @retval None
+ */
+void SVC_Handler(void)
+{
+}
+
+/**
+ * @brief This function handles Debug Monitor exception.
+ * @param None
+ * @retval None
+ */
+void DebugMon_Handler(void)
+{
+}
+
+/**
+ * @brief This function handles PendSVC exception.
+ * @param None
+ * @retval None
+ */
+void PendSV_Handler(void)
+{
+}
+
+/**
+ * @brief This function handles SysTick Handler.
+ * @param None
+ * @retval None
+ */
+void SysTick_Handler(void)
+{
+ HAL_IncTick();
+}
+
+/******************************************************************************/
+/* STM32F4xx Peripherals Interrupt Handlers */
+/* Add here the Interrupt Handler for the used peripheral(s) (GPIO), for the */
+/* available peripheral interrupt handler's name please refer to the startup */
+/* file (startup_stm32f4xx.s). */
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.h b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.h
new file mode 100644
index 00000000..4ff24ba1
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_it.h
@@ -0,0 +1,69 @@
+/**
+ ******************************************************************************
+ * @file Templates_LL/Inc/stm32f4xx_it.h
+ * @author MCD Application Team
+ * @version V1.0.0
+ * @date 17-February-2017
+ * @brief This file contains the headers of the interrupt handlers.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_IT_H
+#define __STM32F4xx_IT_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMI_Handler(void);
+void HardFault_Handler(void);
+void MemManage_Handler(void);
+void BusFault_Handler(void);
+void UsageFault_Handler(void);
+void SVC_Handler(void);
+void DebugMon_Handler(void);
+void PendSV_Handler(void);
+void SysTick_Handler(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_IT_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/stm32f469i_raw32_system.c b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_system.c
new file mode 100644
index 00000000..bfeaf3b4
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_system.c
@@ -0,0 +1,450 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.c
+ * @author MCD Application Team
+ * @version V1.0.0
+ * @date 17-February-2017
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+ *
+ * This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2017 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Includes
+ * @{
+ */
+
+
+#include "stm32f4xx.h"
+
+#if !defined (HSE_VALUE)
+#if defined(USE_STM32469I_DISCO_REVA)
+ #define HSE_VALUE ((uint32_t)25000000) /*!< Default value of the External oscillator in Hz */
+#else
+ #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */
+#endif /* USE_STM32469I_DISCO_REVA */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SDRAM mounted
+ on DK as data memory */
+/* #define DATA_IN_ExtSDRAM */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+ * @{
+ */
+ /* This variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+uint32_t SystemCoreClock = 16000000;
+const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+#if defined (DATA_IN_ExtSDRAM)
+ static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the FPU setting, vector table location and External memory
+ * configuration.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x24003010;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#if defined (DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSDRAM */
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (its value
+ * depends on the application requirements), user has to ensure that HSE_VALUE
+ * is same as the real frequency of the crystal used. Otherwise, this function
+ * may have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL used as system clock source */
+
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_P
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+
+ pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+ SystemCoreClock = pllvco/pllp;
+ break;
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+
+#if defined (DATA_IN_ExtSDRAM)
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external memories (SRAM/SDRAM)
+ * This SRAM/SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register __IO uint32_t index;
+
+ /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH, and GPIOI interface
+ clock */
+ RCC->AHB1ENR |= 0x000001FC;
+
+ /* Connect PCx pins to FMC Alternate function */
+ GPIOC->AFR[0] = 0x0000000C;
+ GPIOC->AFR[1] = 0x00000000;
+ /* Configure PCx pins in Alternate function mode */
+ GPIOC->MODER = 0x00000002;
+ /* Configure PCx pins speed to 100 MHz */
+ GPIOC->OSPEEDR = 0x00000003;
+ /* Configure PCx pins Output type to push-pull */
+ GPIOC->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PCx pins */
+ GPIOC->PUPDR = 0x00000000;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xA02A000A;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xF03F000F;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xFFFFC00F;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00CCCCCC;
+ GPIOF->AFR[1] = 0xCCCCC000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA800AAA;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xFFC00FFF;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00CC00CC;
+ GPIOG->AFR[1] = 0xC000000C;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x80020A0A;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0xC0030F0F;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0x0000CC00;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAA00A0;
+ /* Configure PHx pins speed to 100 MHz */
+ GPIOH->OSPEEDR = 0xFFFF00F0;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x00000000;
+
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0x0028AAAA;
+ /* Configure PIx pins speed to 100 MHz */
+ GPIOI->OSPEEDR = 0x003CFFFF;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00000000;
+
+ /* FMC Configuration */
+ /* Enable the FMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+ /* Configure and enable SDRAM bank2 */
+ FMC_Bank5_6->SDCR[0] = 0x000019E4;
+ FMC_Bank5_6->SDTR[0] = 0x01115351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000011;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x00000012;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Auto refresh command */
+ FMC_Bank5_6->SDCMR = 0x000000F3;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* MRD register program */
+ FMC_Bank5_6->SDCMR = 0x00046014;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x0000056A<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[0];
+ FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/boards/base/STM32F469i-Discovery/stm32f469i_raw32_ugfx.c b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_ugfx.c
new file mode 100644
index 00000000..7619b074
--- /dev/null
+++ b/boards/base/STM32F469i-Discovery/stm32f469i_raw32_ugfx.c
@@ -0,0 +1,110 @@
+#include "../../../gfx.h"
+#undef Red
+#undef Green
+#undef Blue
+#include "stm32f4xx.h"
+#include "stm32f4xx_hal.h"
+
+#if !GFX_USE_OS_CHIBIOS
+ systemticks_t gfxSystemTicks(void)
+ {
+ return HAL_GetTick();
+ }
+
+ systemticks_t gfxMillisecondsToTicks(delaytime_t ms)
+ {
+ return ms;
+ }
+#endif
+
+static void SystemClock_Config(void);
+
+void Raw32OSInit(void) {
+
+ /* STM32F4xx HAL library initialization:
+ - Configure the Flash prefetch, instruction and Data caches
+ - Systick timer is configured by default as source of time base, but user
+ can eventually implement his proper time base source (a general purpose
+ timer for example or other time source), keeping in mind that Time base
+ duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and
+ handled in milliseconds basis.
+ - Set NVIC Group Priority to 4
+ - Low Level Initialization: global MSP (MCU Support Package) initialization
+ */
+ HAL_Init();
+
+ /* Configure the system clock to 216 MHz */
+ SystemClock_Config();
+}
+
+/**
+ * @brief System Clock Configuration
+ * The system Clock is configured as follow :
+ * System Clock source = PLL (HSE)
+ * SYSCLK(Hz) = 180000000
+ * HCLK(Hz) = 180000000
+ * AHB Prescaler = 1
+ * APB1 Prescaler = 4
+ * APB2 Prescaler = 2
+ * HSE Frequency(Hz) = 8000000
+ * PLL_M = 8
+ * PLL_N = 360
+ * PLL_P = 2
+ * PLL_Q = 7
+ * PLL_R = 6
+ * VDD(V) = 3.3
+ * Main regulator output voltage = Scale1 mode
+ * Flash Latency(WS) = 5
+ * @param None
+ * @retval None
+ */
+static void SystemClock_Config(void)
+{
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+
+ /* Enable Power Control clock */
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ /* Enable HSE Oscillator and activate PLL with HSE as source */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+#if defined(USE_STM32469I_DISCO_REVA)
+ RCC_OscInitStruct.PLL.PLLM = 25;
+#else
+ RCC_OscInitStruct.PLL.PLLM = 8;
+#endif /* USE_STM32469I_DISCO_REVA */
+ RCC_OscInitStruct.PLL.PLLN = 360;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
+ RCC_OscInitStruct.PLL.PLLQ = 7;
+ RCC_OscInitStruct.PLL.PLLR = 6;
+
+ if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ while(1);
+ }
+ /* Enable the OverDrive to reach the 180 Mhz Frequency */
+ if(HAL_PWREx_EnableOverDrive() != HAL_OK)
+ {
+ while(1);
+ }
+
+ /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
+ clocks dividers */
+ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
+ if(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK)
+ {
+ while(1);
+ }
+}