summaryrefslogtreecommitdiff
path: root/nuttx/configs/hymini-stm32v/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/hymini-stm32v/src')
-rw-r--r--nuttx/configs/hymini-stm32v/src/Makefile102
-rw-r--r--nuttx/configs/hymini-stm32v/src/README.txt1
-rw-r--r--nuttx/configs/hymini-stm32v/src/hymini_stm32v-internal.h153
-rw-r--r--nuttx/configs/hymini-stm32v/src/ssd1289.c989
-rw-r--r--nuttx/configs/hymini-stm32v/src/ssd1289.h55
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_boot.c103
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_buttons.c159
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_leds.c241
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_nsh.c182
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_spi.c179
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_ts.c163
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_usbdev.c117
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_usbstrg.c164
13 files changed, 2608 insertions, 0 deletions
diff --git a/nuttx/configs/hymini-stm32v/src/Makefile b/nuttx/configs/hymini-stm32v/src/Makefile
new file mode 100644
index 000000000..d79260748
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/Makefile
@@ -0,0 +1,102 @@
+############################################################################
+# configs/hymini-stm32v/src/Makefile
+#
+# Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+# Laurent Latil <laurent@latil.nom.fr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = up_boot.c up_leds.c up_buttons.c up_spi.c up_usbdev.c
+
+ifeq ($(CONFIG_NX_LCDDRIVER),y)
+CSRCS += ssd1289.c
+endif
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += up_nsh.c
+endif
+
+ifeq ($(CONFIG_INPUT),y)
+CSRCS += up_ts.c
+endif
+
+ifeq ($(CONFIG_USBSTRG),y)
+CSRCS += up_usbstrg.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f libboard$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/configs/hymini-stm32v/src/README.txt b/nuttx/configs/hymini-stm32v/src/README.txt
new file mode 100644
index 000000000..d7c4f97cc
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/README.txt
@@ -0,0 +1 @@
+This directory contains drivers unique to the HY-MiniSTM32V development board.
diff --git a/nuttx/configs/hymini-stm32v/src/hymini_stm32v-internal.h b/nuttx/configs/hymini-stm32v/src/hymini_stm32v-internal.h
new file mode 100644
index 000000000..718220454
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/hymini_stm32v-internal.h
@@ -0,0 +1,153 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/hymini_stm32v-internal.h
+ * arch/arm/src/board/hymini_stm32v-internal.h
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIGS_HYMINI_STM32V_INTERNAL_H
+#define __CONFIGS_HYMINI_STM32V_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* How many SPI modules does this chip support? The LM3S6918 supports 2 SPI
+ * modules (others may support more -- in such case, the following must be
+ * expanded).
+ */
+
+#if STM32_NSPI < 1
+# undef CONFIG_STM32_SPI1
+# undef CONFIG_STM32_SPI2
+#elif STM32_NSPI < 2
+# undef CONFIG_STM32_SPI2
+#endif
+
+/* GPIOs **************************************************************/
+/* LEDs */
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+
+/* BUTTONS -- NOTE that some have EXTI interrupts configured */
+
+#define MIN_IRQBUTTON BUTTON_KEYA
+#define MAX_IRQBUTTON BUTTON_KEYB
+#define NUM_IRQBUTTONS NUM_BUTTONS
+
+/* Button A is externally pulled up */
+#define GPIO_BTN_KEYA (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_PORTC|GPIO_PIN13)
+
+/* Button B is externally pulled dw */
+#define GPIO_BTN_KEYB (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_PORTB|GPIO_PIN2)
+
+/* SPI touch screen (ADS7843) chip select: PA.4 */
+
+#define GPIO_TS_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+
+/* Touch screen (ADS7843) IRQ pin: PB.6 */
+#define GPIO_TS_IRQ (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|\
+ GPIO_PORTB|GPIO_PIN6)
+
+/* USB Soft Connect Pullup: PB.7 */
+#define GPIO_USB_PULLUP (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN7)
+
+/* SD card detect pin: PD.3 */
+#define GPIO_SD_CD (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_PORTD|GPIO_PIN3)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the Hy-Mini STM32v board.
+ *
+ ************************************************************************************/
+
+extern void weak_function stm32_spiinitialize(void);
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the Hy-Mini STM32v board.
+ *
+ ************************************************************************************/
+
+extern void weak_function stm32_usbinitialize(void);
+
+#if defined(CONFIG_INPUT_ADS7843E)
+
+/************************************************************************************
+ * Name: Touchscreen initialization
+ *
+ ************************************************************************************/
+
+extern int arch_tcinitialize(int minor);
+
+extern void arch_tcuninitialize(void);
+
+#endif /* CONFIG_INPUT_ADS7843E */
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_HYMINI_STM32V_INTERNAL_H */
+
diff --git a/nuttx/configs/hymini-stm32v/src/ssd1289.c b/nuttx/configs/hymini-stm32v/src/ssd1289.c
new file mode 100644
index 000000000..0ebf82274
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/ssd1289.c
@@ -0,0 +1,989 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/ssd1289.c
+ * arch/arm/src/board/ssd1289.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "stm32.h"
+#include "stm32_internal.h"
+#include "hymini_stm32v-internal.h"
+
+#include "ssd1289.h"
+
+/* Color depth and format */
+#define LCD_BPP 16
+#define LCD_COLORFMT FB_FMT_RGB16_565
+
+/* Display Resolution */
+#if defined(CONFIG_LCD_LANDSCAPE)
+# define LCD_XRES 320
+# define LCD_YRES 240
+#else
+# define LCD_XRES 240
+# define LCD_YRES 320
+#endif
+
+#define LCD_BL_TIMER_PERIOD 8999
+
+
+/* Debug ******************************************************************************/
+#ifdef CONFIG_DEBUG_LCD
+# define lcddbg(format, arg...) vdbg(format, ##arg)
+#else
+# define lcddbg(x...)
+#endif
+
+/* LCD is connected to the FSMC_Bank1_NOR/SRAM1 and NE1 is used as ship select signal */
+/* RS <==> A16 */
+#define LCD_REG (*((volatile unsigned short *) 0x60000000)) /* RS = 0 */
+#define LCD_RAM (*((volatile unsigned short *) 0x60020000)) /* RS = 1 */
+
+const uint16_t fsmc_gpios[] =
+{ /* A16... A24 */
+ GPIO_NPS_A16, GPIO_NPS_A17, GPIO_NPS_A18, GPIO_NPS_A19, GPIO_NPS_A20,
+ GPIO_NPS_A21, GPIO_NPS_A22, GPIO_NPS_A23,
+
+ /* D0... D15 */GPIO_NPS_D0, GPIO_NPS_D1, GPIO_NPS_D2, GPIO_NPS_D3,
+ GPIO_NPS_D4, GPIO_NPS_D5, GPIO_NPS_D6, GPIO_NPS_D7, GPIO_NPS_D8, GPIO_NPS_D9,
+ GPIO_NPS_D10, GPIO_NPS_D11, GPIO_NPS_D12, GPIO_NPS_D13, GPIO_NPS_D14,
+ GPIO_NPS_D15,
+
+ /* NOE, NWE */GPIO_NPS_NOE, GPIO_NPS_NWE,
+
+ /* NE1 */GPIO_NPS_NE1 };
+
+#define NGPIOS (sizeof(fsmc_gpios)/sizeof(uint16_t))
+
+/** This should be put elsewhere */
+#ifdef __CC_ARM /* ARM Compiler */
+#define lcd_inline static __inline
+#elif defined (__ICCARM__) /* for IAR Compiler */
+#define lcd_inline inline
+#elif defined (__GNUC__) /* GNU GCC Compiler */
+#define lcd_inline static __inline
+#else
+#define lcd_inline static
+#endif
+
+/* Low Level methods */
+void lcd_clear(uint16_t color);
+
+/* LCD Data Transfer Methods */
+int lcd_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+ size_t npixels);
+int lcd_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels);
+
+/* LCD Configuration */
+static int lcd_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo);
+static int lcd_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+ FAR struct lcd_planeinfo_s *pinfo);
+
+/* LCD RGB Mapping */
+#ifdef CONFIG_FB_CMAP
+# error "RGB color mapping not supported by this driver"
+#endif
+
+/* Cursor Controls */
+#ifdef CONFIG_FB_HWCURSOR
+# error "Cursor control not supported by this driver"
+#endif
+
+/* LCD Specific Controls */
+static int lcd_getpower(struct lcd_dev_s *dev);
+static int lcd_setpower(struct lcd_dev_s *dev, int power);
+static int lcd_getcontrast(struct lcd_dev_s *dev);
+static int lcd_setcontrast(struct lcd_dev_s *dev, unsigned int contrast);
+
+/* Initialization (LCD ctrl / backlight) */
+static inline void lcd_initialize(void);
+
+#ifdef CONFIG_LCD_BACKLIGHT
+static void lcd_backlight(void);
+#else
+# define lcd_backlight()
+#endif
+
+/**************************************************************************************
+ * Private Data
+ **************************************************************************************/
+
+/* This is working memory allocated by the LCD driver for each LCD device
+ * and for each color plane. This memory will hold one raster line of data.
+ * The size of the allocated run buffer must therefore be at least
+ * (bpp * xres / 8). Actual alignment of the buffer must conform to the
+ * bitwidth of the underlying pixel type.
+ *
+ * If there are multiple planes, they may share the same working buffer
+ * because different planes will not be operate on concurrently. However,
+ * if there are multiple LCD devices, they must each have unique run buffers.
+ */
+
+static uint16_t g_runbuffer[LCD_XRES];
+
+/* This structure describes the overall LCD video controller */
+
+static const struct fb_videoinfo_s g_videoinfo =
+{ .fmt = LCD_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */
+ .xres = LCD_XRES, /* Horizontal resolution in pixel columns */
+ .yres = LCD_YRES, /* Vertical resolution in pixel rows */
+ .nplanes = 1, /* Number of color planes supported */
+};
+
+/* This is the standard, NuttX Plane information object */
+
+static const struct lcd_planeinfo_s g_planeinfo =
+{ .putrun = lcd_putrun, /* Put a run into LCD memory */
+ .getrun = lcd_getrun, /* Get a run from LCD memory */
+ .buffer = (uint8_t*) g_runbuffer, /* Run scratch buffer */
+ .bpp = LCD_BPP, /* Bits-per-pixel */
+};
+
+/* This is the standard, NuttX LCD driver object */
+
+static struct ssd1289_dev_s g_lcddev =
+{ .dev =
+ {
+ /* LCD Configuration */
+
+ .getvideoinfo = lcd_getvideoinfo,
+ .getplaneinfo = lcd_getplaneinfo,
+
+/* LCD RGB Mapping -- Not supported */
+/* Cursor Controls -- Not supported */
+
+/* LCD Specific Controls */
+ .getpower = lcd_getpower,
+ .setpower = lcd_setpower,
+ .getcontrast = lcd_getcontrast,
+ .setcontrast = lcd_setcontrast,
+ },
+ .power=0
+};
+
+/************************************************************************************
+ * Name: stm32_extmemgpios
+ *
+ * Description:
+ * Initialize GPIOs for NOR or SRAM
+ *
+ ************************************************************************************/
+
+static inline void stm32_extmemgpios(const uint16_t *gpios, int ngpios)
+{
+ int i;
+
+ /* Configure GPIOs */
+ for (i = 0; i < ngpios; i++)
+ {
+ stm32_configgpio(gpios[i]);
+ }
+}
+
+/************************************************************************************
+ * Name: stm32_enablefsmc
+ *
+ * Description:
+ * enable clocking to the FSMC module
+ *
+ ************************************************************************************/
+
+#ifndef CONFIG_STM32_FSMC
+# error CONFIG_STM32_FSMC is required for LCD support
+#endif
+
+static void stm32_enablefsmc(void)
+{
+ uint32_t regval;
+
+ /* Enable AHB clocking to the FSMC */
+
+ regval = getreg32( STM32_RCC_AHBENR);
+ regval |= RCC_AHBENR_FSMCEN;
+ putreg32(regval, STM32_RCC_AHBENR);
+}
+
+/************************************************************************************
+ * Name: stm32_disablefsmc
+ *
+ * Description:
+ * enable clocking to the FSMC module
+ *
+ ************************************************************************************/
+
+static void stm32_disablefsmc(void)
+{
+ uint32_t regval;
+
+ /* Enable AHB clocking to the FSMC */
+
+ regval = getreg32( STM32_RCC_AHBENR);
+ regval &= ~RCC_AHBENR_FSMCEN;
+ putreg32(regval, STM32_RCC_AHBENR);
+}
+
+/************************************************************************************
+ * Name: stm32_selectlcd
+ *
+ * Description:
+ * Initialize to the LCD
+ *
+ ************************************************************************************/
+
+static void stm32_selectlcd(void)
+{
+ /* Configure new GPIO state */
+ stm32_extmemgpios(fsmc_gpios, NGPIOS);
+
+ /* Enable AHB clocking to the FSMC */
+ stm32_enablefsmc();
+
+ /* Bank1 NOR/SRAM control register configuration */
+ putreg32(FSMC_BCR_SRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN, STM32_FSMC_BCR1);
+
+ /* Bank1 NOR/SRAM timing register configuration */
+ putreg32(
+ FSMC_BTR_ADDSET(2)|FSMC_BTR_ADDHLD(0)|FSMC_BTR_DATAST(2)|FSMC_BTR_BUSTRUN(0)| FSMC_BTR_CLKDIV(0)|FSMC_BTR_DATLAT(0)|FSMC_BTR_ACCMODA,
+ STM32_FSMC_BTR1);
+
+ /* As ext mode is not active the write timing is ignored!! */
+ putreg32(0xffffffff, STM32_FSMC_BWTR1);
+
+ /* Enable the bank by setting the MBKEN bit */
+ putreg32(FSMC_BCR_MBKEN | FSMC_BCR_SRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN,
+ STM32_FSMC_BCR1);
+}
+
+/************************************************************************************
+ * Name: stm32_deselectlcd
+ *
+ * Description:
+ * Disable the LCD
+ *
+ ************************************************************************************/
+// FIXME: Check this code !!
+void stm32_deselectlcd(void)
+{
+ /* Restore registers to their power up settings */
+
+ putreg32(0xffffffff, STM32_FSMC_BCR4);
+
+ /* Bank1 NOR/SRAM timing register configuration */
+
+ putreg32(0x0fffffff, STM32_FSMC_BTR4);
+
+ /* Disable AHB clocking to the FSMC */
+
+ stm32_disablefsmc();
+}
+
+lcd_inline void write_cmd(unsigned short cmd)
+{
+ LCD_REG = cmd;
+}
+
+lcd_inline unsigned short read_data(void)
+{
+ return LCD_RAM;
+}
+
+lcd_inline void write_data(unsigned short data_code)
+{
+ LCD_RAM = data_code;
+}
+
+void write_reg(unsigned char reg_addr, unsigned short reg_val)
+{
+ write_cmd(reg_addr);
+ write_data(reg_val);
+}
+
+unsigned short read_reg(unsigned char reg_addr)
+{
+ unsigned short val;
+ write_cmd(reg_addr);
+ val = read_data();
+ return (val);
+}
+
+static inline void lcd_gramselect(void)
+{
+ write_cmd(0x22);
+}
+
+void lcd_setcursor(unsigned int x, unsigned int y)
+{
+#if defined(CONFIG_LCD_PORTRAIT) || defined (CONFIG_LCD_RPORTRAIT)
+# if defined (CONFIG_LCD_RPORTRAIT)
+ x = (LCD_XRES - 1) - x;
+ y = (LCD_YRES - 1) - y;
+# endif
+ write_reg(0x4e, x);
+ write_reg(0x4f, y);
+#endif
+
+#if defined(CONFIG_LCD_LANDSCAPE)
+ y = (LCD_YRES - 1) - y;
+
+ write_reg(0x4e, y);
+ write_reg(0x4f, x);
+#endif
+}
+
+/**************************************************************************************
+ * Name: lcd_putrun
+ *
+ * Description:
+ * This method can be used to write a partial raster line to the LCD:
+ *
+ * row - Starting row to write to (range: 0 <= row < yres)
+ * col - Starting column to write to (range: 0 <= col <= xres-npixels)
+ * buffer - The buffer containing the run to be written to the LCD
+ * npixels - The number of pixels to write to the LCD
+ * (range: 0 < npixels <= xres-col)
+ *
+ **************************************************************************************/
+
+int lcd_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+ size_t npixels)
+{
+ int i;
+ FAR const uint16_t *src = (FAR const uint16_t*) buffer;
+
+ /* Buffer must be provided and aligned to a 16-bit address boundary */
+ DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
+
+ /* Write the run to GRAM. */
+ lcd_setcursor(col, row);
+
+ lcd_gramselect();
+ for (i = 0; i < npixels; i++)
+ {
+ write_data(*src++);
+ }
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: lcd_getrun
+ *
+ * Description:
+ * This method can be used to read a partial raster line from the LCD:
+ *
+ * row - Starting row to read from (range: 0 <= row < yres)
+ * col - Starting column to read read (range: 0 <= col <= xres-npixels)
+ * buffer - The buffer in which to return the run read from the LCD
+ * npixels - The number of pixels to read from the LCD
+ * (range: 0 < npixels <= xres-col)
+ *
+ **************************************************************************************/
+
+int lcd_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels)
+{
+ FAR uint16_t *dest = (FAR uint16_t*) buffer;
+ int i;
+
+ /* Buffer must be provided and aligned to a 16-bit address boundary */
+ DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
+
+ /* Read the run from GRAM. */
+ lcd_setcursor(col, row);
+
+ lcd_gramselect();
+
+ /* dummy read */
+ (void)read_data();
+
+ for (i = 0; i < npixels; i++)
+ {
+ *dest++ = read_data();
+ }
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: lcd_getvideoinfo
+ *
+ * Description:
+ * Get information about the LCD video controller configuration.
+ *
+ **************************************************************************************/
+
+static int lcd_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo)
+{
+ DEBUGASSERT(dev && vinfo);gvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n",
+ g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes);
+ memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s));
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: lcd_getplaneinfo
+ *
+ * Description:
+ * Get information about the configuration of each LCD color plane.
+ *
+ **************************************************************************************/
+
+static int lcd_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+ FAR struct lcd_planeinfo_s *pinfo)
+{
+ DEBUGASSERT(dev && pinfo && planeno == 0);gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp);
+ memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s));
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: lcd_getpower
+ *
+ * Description:
+ * Get the LCD panel power status (0: full off - CONFIG_LCD_MAXPOWER: full on). On
+ * backlit LCDs, this setting may correspond to the backlight setting.
+ *
+ **************************************************************************************/
+
+static int lcd_getpower(struct lcd_dev_s *dev)
+{
+ gvdbg("power: %d\n", 0);
+ return g_lcddev.power;
+}
+
+/**************************************************************************************
+ * Name: lcd_setpower
+ *
+ * Description:
+ * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on).
+ * Used here to set pwm duty on timer used for backlight.
+ *
+ **************************************************************************************/
+
+static int lcd_setpower(struct lcd_dev_s *dev, int power)
+{
+ if (g_lcddev.power == power) {
+ return OK;
+ }
+
+ gvdbg("power: %d\n", power);
+ DEBUGASSERT(power <= CONFIG_LCD_MAXPOWER);
+
+ /* Set new power level */
+
+ if (power > 0)
+ {
+#ifdef CONFIG_LCD_BACKLIGHT
+ uint32_t duty;
+
+ /* Calculate the new backlight duty. It is a fraction of the timer
+ * period based on the ration of the current power setting to the
+ * maximum power setting.
+ */
+ duty = ((uint32_t)LCD_BL_TIMER_PERIOD * (uint32_t)power) / CONFIG_LCD_MAXPOWER;
+ if (duty >= LCD_BL_TIMER_PERIOD)
+ {
+ duty = LCD_BL_TIMER_PERIOD - 1;
+ }
+ gvdbg("PWM duty: %d\n", duty);
+ putreg16((uint16_t)duty, STM32_TIM3_CCR2);
+#endif
+ /* TODO turn the display on */
+ }
+ else
+ {
+ /* FIXME: Turn display off ? */
+ gvdbg("Force PWM to 0\n");
+ putreg16((uint16_t)0, STM32_TIM3_CCR2);
+ }
+ g_lcddev.power = power;
+ return OK;
+}
+
+
+/**************************************************************************************
+ * Name: lcd_getcontrast
+ *
+ * Description:
+ * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static int lcd_getcontrast(struct lcd_dev_s *dev)
+{
+ gvdbg("Not implemented\n");
+ return -ENOSYS;
+}
+
+/**************************************************************************************
+ * Name: lcd_setcontrast
+ *
+ * Description:
+ * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static int lcd_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
+{
+ gvdbg("Not implemented\n");
+ return -ENOSYS;
+}
+
+/**************************************************************************************
+ * Name: lcd_lcdinitialize
+ *
+ * Description:
+ * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+static inline void lcd_initialize(void)
+{
+ /* Display control (GON=1,DTE=0,D[1:0]=01)
+ D[1:0]=01 - Internal display is performed, display is off.
+ */
+ write_reg(0x07, 0x0021);
+
+ /* Oscillator (OSCEN=1) */
+ write_reg(0x00, 0x0001);
+
+ /* Display control (GON=1,DTE=0,D[1:0]=11)
+ D[1:0]=11 - Internal display is performed, display is on.
+ */
+ write_reg(0x07, 0x0023);
+
+ /* Wait 30ms */
+ up_mdelay(30);
+
+ /* Display control (GON=1,DTE=1,D[1:0]=11) */
+ write_reg(0x07, 0x0033);
+
+ /* Power control 1
+ DCT3 DCT2 DCT1 DCT0 BT2 BT1 BT0 - DC3 DC2 DC1 DC0 AP2 AP1 AP0 -
+ 1 0 1 0 1 0 0 0 1 0 1 0 0 1 0 0
+ DCT[3:0] - 1010: fosc/4 (step-up cycle of the step-up circuit for 8-color mode)
+ BT[2:0] - 100 (step-up factor of the step-up circuit)
+ DC[3:0] - 1010: fosc/4 (step-up cycle of the step-up circuit for 262k-color mode)
+ AP[2:0] - 010: Small to medium (amount of current from the stable-current source in internal operational amplifier circuit)
+ */
+ write_reg(0x03, 0xA8A4); /* or 0x0804 ?? */
+
+ /* Power Control 2
+ VRC[2:0] - 000: 5.1v (VCIX2 output voltage)
+ */
+ write_reg(0x0C, 0x0000);
+
+ /* Power Control 3
+ - - - - - - - - - - - - VRH3 VRH2 VRH1 VRH0
+ 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0
+ VRH[3:0] - 1000: Vref x 2.165 (Set amplitude magnification of VLCD63)
+ */
+ write_reg(0x0D, 0x0008); // or 0x080C ??
+
+ /* power control 4
+ - - VCOMG VDV4 VDV3 VDV2 VDV1 VDV0 - - - - - - - -
+ 0 0 1 0 1 0 0 1 0 0 0 0 0 0 0 0
+ VDV[4:0] - 01001: VLCD63 x 0.xx (Vcom amplitude)
+ VCOMG - 1 (enable output voltage of VcomL - VDV[4:0])
+ */
+ write_reg(0x0E, 0x2900);
+
+ /* Power Control 5
+ - - - - - - - - nOTP - VCM5 VCM4 VCM3 VCM2 VCM1 VCM0
+ 0 0 0 0 0 0 0 0 1 0 1 1 1 0 0 0
+ nOTP: 1 - setting of VCM[5:0] becomes valid and voltage of VcomH can be adjusted.
+ VCM[5-0] - 111000: VLCD63 x 0.xx (amplify the VcomH voltage 0.35 to 0.99 times the VLCD63 voltage)
+ */
+ write_reg(0x1E, 0x00B8);
+
+ /* Driver Output Control
+ - RL REV CAD BGR SM TB MUX8 MUX7 MUX6 MUX5 MUX4 MUX3 MUX2 MUX1 MUX0
+ 0 0 1 0 1 0 1 1 0 0 1 1 1 1 1 1
+ RL - 0 RL setting is ignored when display with RAM (Dmode[1:0] = 00).
+ REV - 1 Reverse source output level
+ CAD - 0 Cs on Common
+ BGR - 1 BGR (Selects the order from RGB to BGR in writing 18-bit pixel data in the GDDRAM)
+ SM - 0 (Gate scan sequence)
+ TB - 1 (output shift direction of the gate driver)
+ MUX[8:0] - 100111111 (319) (number of lines for the LCD driver)
+ */
+ write_reg(0x01, 0x2B3F);
+
+ /* LCD-Driving-Waveform Control
+ - - - FLD ENWS B/C EOR WSMD NW7 NW6 NW5 NW4 NW3 NW2 NW1 NW0
+ 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0
+ FLD - 0 ?
+ ENWS- 0 (disable WSYNC output pin -> HiZ)
+ B/C - 1 (When B/C = 1, a N-line inversion waveform is generated and alternates in a N-line equals to NW[7:0]+1)
+ EOR - 1
+ WSMD- 0
+ NW[7:0] - 0 Specify the number of lines that will alternate at the N-line inversion setting (if B/C = 1).
+ */
+ /* Set FLD ? */
+ write_reg(0x02, 0x0600);
+
+ /* Exit sleep mode */
+ write_reg(0x10, 0x0000);
+
+ /* Entry Mode
+ VSMode DFM1 DFM0 TRANS OEDef WMode DMode1 DMode0 TY1 TY0 ID1 ID0 AM LG2 LG1 LG0
+ 0 1 1 0 0 0 0 0 0 1 1 1 0 0 0 0
+ VSMode - 0 When VSMode = 1 at DMode[1:0] = “00”, the frame frequency will be dependent on VSYNC.
+ DFM[1:0] - 11 (65k color mode selected)
+ TRANS - 0 (if TRANS = 1, transparent display is allowed during DMode[1:0] = “1x”)
+ 0EDef - 0 (display window is defined by R4Eh and R4Fh)
+ WMode - 0 (Normal data bus)
+ DMode[1:0] - 00 (data display from RAM data)
+ TY[1:0] - 01 (type B. Used for 262k color mode only)
+ ID[1:0] - 11 (address counter auto incremented by 1, horizontal & vertical)
+ AM - 0 Horizontal (direction of the address counter update after data are written to the GDDRAM)
+ LG[2:0] - 000 (operation to perform according to GDRAM compare registers ?)
+ */
+#if defined(CONFIG_LCD_PORTRAIT)
+ write_reg(0x11, 0x6070);
+#elif defined(CONFIG_LCD_RPORTRAIT)
+ /* ID[1:0] - 00 (address counter auto decremented by 1, horizontal & vertical) */
+ write_reg(0x11, 0x6840);
+#elif defined(CONFIG_LCD_LANDSCAPE)
+ /* ID[1:0] - 10 (address counter auto decremented by 1, horizontal & vertical)
+ AM - 1 Vertical direction
+ */
+ write_reg(0x11, 0x6068);
+#else
+#error "LCD orientation not supported"
+#endif
+
+ /* Compare register (unused ?) */
+ write_reg(0x05, 0x0000);
+ write_reg(0x06, 0x0000);
+
+ /* Horizontal Porch
+ XL7 XL6 XL5 XL4 XL3 XL2 IB9 XL1 HBP7 HBP6 HBP5 HBP4 HBP3 HBP2 HBP1 HBP0
+ XL[7:0] - 0xEF (239) (Number of valid pixel per line is equal to XL[7:0] + 1)
+ HBP[7:0] - 0x1C (28) 30 dot clocks (delay period from falling edge of HSYNC signal to first valid data)
+ */
+ write_reg(0x16, 0xEF1C);
+
+ /* Vertical Porch */
+ write_reg(0x17, 0x0003);
+
+ /* Display control
+ - - - PT1 PT0 VLE2 VLE1 SPT - - GON DTE CM - D1 D0
+ 0 0 0 0 0 0 0 1 0 0 1 1 0 0 1 1
+ VLE[2:1]: 00 (When VLE1 = 1 or VLE2 = 1, vertical scroll performed in the 1st screen by taking data VL17-0 in R41h
+ register. When VLE1 = 1 and VLE2 = 1, a vertical scroll is performed in the 1st and 2nd screen by VL1[8:0] and VL2[8:0])
+ SPT: 1 (When SPT = “1”, the 2-division LCD drive is performed.
+ CM: 0 (8-color mode setting 0=disabled, 1=enabled)
+ D[1:0]: 11
+ */
+ write_reg(0x07, 0x0133);
+
+ /* Frame Cycle Control */
+ write_reg(0x0B, 0x0000);
+
+ /* Gate Scan Position */
+ /* write_reg(0x0F, 0x0000); // Default value */
+
+ /* Vertical Scroll Control */
+ write_reg(0x41, 0x0000);
+ write_reg(0x42, 0x0000);
+
+ /* 1st Screen driving position
+ driving start position for the first screen in a line unit. (0)
+ */
+ write_reg(0x48, 0x0000);
+ /* driving end position for the first screen in a line unit. (319) */
+ write_reg(0x49, 0x013F);
+
+ /* 2nd Screen driving position (unused) */
+ write_reg(0x4A, 0x0000);
+ write_reg(0x4B, 0x0000);
+
+ /* start/end positions of the window address in the horizontal direction */
+ write_reg(0x44, 0xEF00);
+
+ /* start/end positions of the window address in the vertical direction */
+ /* write_reg(0x45, 0x0000); // Default value
+ write_reg(0x46, 0x013F); // Default value
+ */
+
+ /* Gamma Control */
+ write_reg(0x0030, 0x0707);
+ write_reg(0x0031, 0x0204);
+ write_reg(0x0032, 0x0204);
+ write_reg(0x0033, 0x0502);
+ write_reg(0x0034, 0x0507);
+ write_reg(0x0035, 0x0204);
+ write_reg(0x0036, 0x0204);
+ write_reg(0x0037, 0x0502);
+ write_reg(0x003A, 0x0302);
+ write_reg(0x003B, 0x0302);
+
+ /* RAM write data mask (unused)
+ write_reg(0x23, 0x0000); // Default value
+ write_reg(0x24, 0x0000); // Default value
+ */
+
+ /* Setting R28h as 0x0006 is required before setting R25h and R29h registers.*/
+
+ write_reg(0x28, 0x0006);
+
+ /* Frame Frequency Control (R25h)
+ OSC3 OSC2 OSC1 OSC0 - - - - - - - - - - - -
+ 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0
+ OSC[3:0]: 1110 Corresponding frame freq: 80Hz
+ */
+ write_reg(0x25, 0xE000); /* (Default value = 8000h) */
+}
+
+/**************************************************************************************
+ * Name: lcd_backlight
+ *
+ * Description:
+ * The LCD backlight is driven from PB.5 which must be configured as TIM3
+ * CH2. TIM3 must then be configured to pwm output on PB.5; the duty
+ * of the clock determines the backlight level.
+ *
+ **************************************************************************************/
+
+#ifdef CONFIG_LCD_BACKLIGHT
+
+#ifndef CONFIG_STM32_TIM3_PARTIAL_REMAP
+# error CONFIG_STM32_TIM3_PARTIAL_REMAP must be set (to have TIM3 CH2 on pin B.5)
+#endif
+
+static void lcd_backlight(void)
+{
+ uint16_t ccmr;
+ uint16_t ccer;
+ uint16_t cr2;
+
+ /* Configure PB5 as TIM3 CH2 output */
+ stm32_configgpio(GPIO_TIM3_CH2OUT);
+
+ /* Enabled timer 3 clocking */
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM3EN);
+
+ /* Reset timer 3 */
+
+ modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_TIM3RST);
+ modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_TIM3RST, 0);
+
+ /* Reset the Counter Mode and set the clock division */
+ putreg16(0, STM32_TIM3_CR1);
+
+ /* Set the Autoreload value */
+ putreg16(LCD_BL_TIMER_PERIOD, STM32_TIM3_ARR);
+
+ /* Set the Prescaler value */
+
+ putreg16(0, STM32_TIM3_PSC);
+
+ /* Generate an update event to reload the Prescaler value immediatly */
+
+ putreg16(ATIM_EGR_UG, STM32_TIM3_EGR);
+
+ /* Disable the Channel 2 */
+
+ ccer = getreg16(STM32_TIM3_CCER);
+ ccer &= ~ATIM_CCER_CC2E;
+ putreg16(ccer, STM32_TIM3_CCER);
+
+ /* Get the TIM3 CR2 register value */
+ cr2 = getreg16(STM32_TIM3_CR2);
+
+ /* Select the Output Compare Mode Bits */
+
+ ccmr = getreg16(STM32_TIM3_CCMR1);
+ ccmr &= ATIM_CCMR1_OC2M_MASK;
+ ccmr |= (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT);
+
+ /* Set the capture compare register value (50% duty) */
+ // FIXME should be set to 0 (appl needs to call setpower to change it)
+ g_lcddev.power = (CONFIG_LCD_MAXPOWER + 1) / 2;
+ putreg16((LCD_BL_TIMER_PERIOD + 1) / 2, STM32_TIM3_CCR2);
+
+ /* Select the output polarity level == HIGH */
+ ccer &= !ATIM_CCER_CC2P;
+
+ /* Enable channel 2*/
+ ccer |= ATIM_CCER_CC2E;
+
+ /* Write the timer configuration */
+
+ putreg16(ccmr, STM32_TIM3_CCMR1);
+ putreg16(ccer, STM32_TIM3_CCER);
+
+ /* Set the auto preload enable bit */
+
+ modifyreg16(STM32_TIM3_CR1, 0, ATIM_CR1_ARPE);
+
+ /* Enable Backlight Timer !!!!*/
+ modifyreg16(STM32_TIM3_CR1, 0, ATIM_CR1_CEN);
+
+ /* Dump timer3 registers */
+ lcddbg("APB1ENR: %08x\n", getreg32(STM32_RCC_APB1ENR));
+ lcddbg("CR1: %04x\n", getreg32(STM32_TIM3_CR1));
+ lcddbg("CR2: %04x\n", getreg32(STM32_TIM3_CR2));
+ lcddbg("SMCR: %04x\n", getreg32(STM32_TIM3_SMCR));
+ lcddbg("DIER: %04x\n", getreg32(STM32_TIM3_DIER));
+ lcddbg("SR: %04x\n", getreg32(STM32_TIM3_SR));
+ lcddbg("EGR: %04x\n", getreg32(STM32_TIM3_EGR));
+ lcddbg("CCMR1: %04x\n", getreg32(STM32_TIM3_CCMR1));
+ lcddbg("CCMR2: %04x\n", getreg32(STM32_TIM3_CCMR2));
+ lcddbg("CCER: %04x\n", getreg32(STM32_TIM3_CCER));
+ lcddbg("CNT: %04x\n", getreg32(STM32_TIM3_CNT));
+ lcddbg("PSC: %04x\n", getreg32(STM32_TIM3_PSC));
+ lcddbg("ARR: %04x\n", getreg32(STM32_TIM3_ARR));
+ lcddbg("CCR1: %04x\n", getreg32(STM32_TIM3_CCR1));
+ lcddbg("CCR2: %04x\n", getreg32(STM32_TIM3_CCR2));
+ lcddbg("CCR3: %04x\n", getreg32(STM32_TIM3_CCR3));
+ lcddbg("CCR4: %04x\n", getreg32(STM32_TIM3_CCR4));
+ lcddbg("CCR4: %04x\n", getreg32(STM32_TIM3_CCR4));
+ lcddbg("CCR4: %04x\n", getreg32(STM32_TIM3_CCR4));
+ lcddbg("DMAR: %04x\n", getreg32(STM32_TIM3_DMAR));
+}
+#endif
+
+/**************************************************************************************
+ * Public Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: up_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD video hardware. The initial state of the LCD is fully
+ * initialized, display memory cleared, and the LCD ready to use, but with the power
+ * setting at 0 (full off).
+ *
+ **************************************************************************************/
+
+int up_lcdinitialize(void)
+{
+ unsigned short id;
+
+ gvdbg("Initializing\n");
+
+ /* Configure GPIO pins and configure the FSMC to support the LCD */
+ stm32_selectlcd();
+
+ /* Delay required here */
+
+ up_mdelay(50);
+
+ /* Check model id */
+
+ id=read_reg(0x0);
+ if (id != SSD1289_ID) {
+ /* Not a SSD1289 ? */
+ gdbg("up_lcdinitialize: LCD ctrl is not a SSD1289");
+ return ERROR;
+ }
+
+ /* Configure and enable LCD */
+
+ lcd_initialize();
+
+ /* Clear the display (setting it to the color 0=black) */
+
+ lcd_clear(0);
+
+ /* Configure the backlight */
+
+ lcd_backlight();
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: up_lcdgetdev
+ *
+ * Description:
+ * Return a a reference to the LCD object for the specified LCD. This allows support
+ * for multiple LCD devices.
+ *
+ **************************************************************************************/
+
+FAR struct lcd_dev_s *up_lcdgetdev(int lcddev)
+{
+ DEBUGASSERT(lcddev == 0);
+ return &g_lcddev.dev;
+}
+
+/**************************************************************************************
+ * Name: up_lcduninitialize
+ *
+ * Description:
+ * Un-initialize the LCD support
+ *
+ **************************************************************************************/
+
+void up_lcduninitialize(void)
+{
+ lcd_setpower(&g_lcddev.dev, 0);
+ stm32_deselectlcd();
+}
+
+/**************************************************************************************
+ * Name: lcd_clear
+ *
+ * Description:
+ * Fill the LCD ctrl memory with given color
+ *
+ **************************************************************************************/
+
+void lcd_clear(uint16_t color)
+{
+ uint32_t index;
+ lcd_setcursor(0, 0);
+ lcd_gramselect(); /* Prepare to write GRAM */
+ for (index = 0; index < LCD_XRES * LCD_YRES; index++)
+ {
+ write_data(color);
+ }
+}
diff --git a/nuttx/configs/hymini-stm32v/src/ssd1289.h b/nuttx/configs/hymini-stm32v/src/ssd1289.h
new file mode 100644
index 000000000..6f81361fe
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/ssd1289.h
@@ -0,0 +1,55 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/ssd1289.h
+ * arch/arm/src/board/ssd1289.h
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef SSD1289_H_
+#define SSD1289_H_
+
+#include <nuttx/lcd/lcd.h>
+
+/* LCD IDs */
+#define SSD1289_ID 0x8989
+
+struct ssd1289_dev_s
+{
+ /* Publicly visible device structure */
+ struct lcd_dev_s dev;
+
+ /* Private LCD-specific information follows */
+ uint8_t power; /* Current power setting */
+};
+
+#endif /* SSD1289_H_ */
diff --git a/nuttx/configs/hymini-stm32v/src/up_boot.c b/nuttx/configs/hymini-stm32v/src/up_boot.c
new file mode 100644
index 000000000..4b48e0b57
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_boot.c
@@ -0,0 +1,103 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/up_boot.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/spi.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "hymini_stm32v-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void)
+{
+ /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
+ * stm32_spiinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
+ if (stm32_spiinitialize)
+ {
+ stm32_spiinitialize();
+ }
+#endif
+
+ /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
+ * disabled, and 3) the weak function stm32_usbinitialize() has been brought
+ * into the build.
+ */
+
+#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
+ if (stm32_usbinitialize)
+ {
+ stm32_usbinitialize();
+ }
+#endif
+
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+}
diff --git a/nuttx/configs/hymini-stm32v/src/up_buttons.c b/nuttx/configs/hymini-stm32v/src/up_buttons.c
new file mode 100644
index 000000000..c3ea0b821
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_buttons.c
@@ -0,0 +1,159 @@
+/****************************************************************************
+ * configs/hymini-stm32v/src/up_buttons.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include <arch/board/board.h>
+#include "hymini_stm32v-internal.h"
+
+#ifdef CONFIG_ARCH_BUTTONS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Pin configuration for each HY-mini button. This array is indexed by
+ * the BUTTON_* definitions in board.h
+ */
+
+//static const uint16_t g_buttons[NUM_BUTTONS] =
+// {
+// GPIO_BTN_KEYA, GPIO_BTN_KEYB
+// };
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_buttoninit
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ ****************************************************************************/
+
+void up_buttoninit(void)
+ {
+ stm32_configgpio(GPIO_BTN_KEYA);
+ stm32_configgpio(GPIO_BTN_KEYB);
+ }
+
+/****************************************************************************
+ * Name: up_buttons
+ ****************************************************************************/
+
+uint8_t up_buttons(void)
+ {
+ uint8_t ret = 0;
+ bool pinValue;
+
+ /* Check that state of each key */
+
+ /* Pin is pulled up */
+ pinValue = stm32_gpioread(GPIO_BTN_KEYA);
+ if (!pinValue)
+ {
+ // Button pressed
+ ret = 1 << BUTTON_KEYA;
+ }
+
+ /* Pin is pulled down */
+ pinValue = stm32_gpioread(GPIO_BTN_KEYB);
+ if (pinValue)
+ {
+ // Button pressed
+ ret |= 1 << BUTTON_KEYB;
+ }
+ return ret;
+ }
+
+/************************************************************************************
+ * Button support.
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ * After up_buttoninit() has been called, up_buttons() may be called to
+ * collect the state of all buttons. up_buttons() returns an 8-bit bit set
+ * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT
+ * definitions in board.h for the meaning of each bit.
+ *
+ * up_irqbutton() may be called to register an interrupt handler that will
+ * be called when a button is depressed or released. The ID value is a
+ * button enumeration value that uniquely identifies a button resource. See the
+ * BUTTON_* definitions in board.h for the meaning of enumeration
+ * value. The previous interrupt handler address is returned (so that it may
+ * restored, if so desired).
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQBUTTONS
+xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
+ {
+ xcpt_t oldhandler = NULL;
+ uint32_t pinset = GPIO_BTN_KEYA;
+
+ if (id == 1)
+ {
+ pinset = GPIO_BTN_KEYB;
+ }
+ if (id < 2)
+ {
+ oldhandler = stm32_gpiosetevent(pinset, true, true, true, irqhandler);
+ }
+ return oldhandler;
+ }
+#endif
+#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/hymini-stm32v/src/up_leds.c b/nuttx/configs/hymini-stm32v/src/up_leds.c
new file mode 100644
index 000000000..3cd0d44bd
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_leds.c
@@ -0,0 +1,241 @@
+/****************************************************************************
+ * configs/hymini-stm32v/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "hymini_stm32v-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/* The following definitions map the encoded LED setting to GPIO settings */
+
+#define HYMINI_STM32_LED1 (1 << 0)
+#define HYMINI_STM32_LED2 (1 << 1)
+
+#define ON_SETBITS_SHIFT (0)
+#define ON_CLRBITS_SHIFT (4)
+#define OFF_SETBITS_SHIFT (8)
+#define OFF_CLRBITS_SHIFT (12)
+
+#define ON_BITS(v) ((v) & 0xff)
+#define OFF_BITS(v) (((v) >> 8) & 0x0ff)
+#define SETBITS(b) ((b) & 0x0f)
+#define CLRBITS(b) (((b) >> 4) & 0x0f)
+
+#define ON_SETBITS(v) (SETBITS(ON_BITS(v))
+#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v))
+#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v))
+#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v))
+
+/* On: !LED1 + !LED2 Off: - */
+#define LED_STARTED_ON_SETBITS ((0) << ON_SETBITS_SHIFT)
+#define LED_STARTED_ON_CLRBITS ((HYMINI_STM32_LED1|HYMINI_STM32_LED2) << ON_CLRBITS_SHIFT)
+#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT)
+#define LED_STARTED_OFF_CLRBITS (0 << OFF_CLRBITS_SHIFT)
+
+/* On: LED1+!LED2 Off: N/A */
+#define LED_HEAPALLOCATE_ON_SETBITS ((HYMINI_STM32_LED1) << ON_SETBITS_SHIFT)
+#define LED_HEAPALLOCATE_ON_CLRBITS ((HYMINI_STM32_LED2) << ON_CLRBITS_SHIFT)
+#define LED_HEAPALLOCATE_OFF_SETBITS (0)
+#define LED_HEAPALLOCATE_OFF_CLRBITS (0)
+
+/* On: LED2+!LED1 Off: N/A */
+#define LED_IRQSENABLED_ON_SETBITS ((HYMINI_STM32_LED2) << ON_SETBITS_SHIFT)
+#define LED_IRQSENABLED_ON_CLRBITS ((HYMINI_STM32_LED1) << ON_CLRBITS_SHIFT)
+#define LED_IRQSENABLED_OFF_SETBITS (0)
+#define LED_IRQSENABLED_OFF_CLRBITS (0)
+
+/* On: LED1+!LED2 Off: N/A */
+#define LED_STACKCREATED_ON_SETBITS ((HYMINI_STM32_LED1) << ON_SETBITS_SHIFT)
+#define LED_STACKCREATED_ON_CLRBITS ((HYMINI_STM32_LED2) << ON_CLRBITS_SHIFT)
+#define LED_STACKCREATED_OFF_SETBITS (0)
+#define LED_STACKCREATED_OFF_CLRBITS (0)
+
+/* On: !LED1 Off: LED1 */
+#define LED_INIRQ_ON_SETBITS ((0) << ON_SETBITS_SHIFT)
+#define LED_INIRQ_ON_CLRBITS ((HYMINI_STM32_LED1) << ON_CLRBITS_SHIFT)
+#define LED_INIRQ_OFF_SETBITS ((HYMINI_STM32_LED1) << OFF_SETBITS_SHIFT)
+#define LED_INIRQ_OFF_CLRBITS ((0) << OFF_CLRBITS_SHIFT)
+
+/* On: LED2 Off: !LED2 */
+#define LED_SIGNAL_ON_SETBITS ((HYMINI_STM32_LED2) << ON_SETBITS_SHIFT)
+#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_SIGNAL_OFF_CLRBITS ((HYMINI_STM32_LED2) << OFF_CLRBITS_SHIFT)
+
+/* On: LED1+LED2 Off: - */
+#define LED_ASSERTION_ON_SETBITS ((HYMINI_STM32_LED2|HYMINI_STM32_LED2) << ON_SETBITS_SHIFT)
+#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_ASSERTION_OFF_CLRBITS ((0) << OFF_CLRBITS_SHIFT)
+
+/* On: LED1 Off: LED2 */
+#define LED_PANIC_ON_SETBITS ((HYMINI_STM32_LED1) << ON_SETBITS_SHIFT)
+#define LED_PANIC_ON_CLRBITS ((HYMINI_STM32_LED2) << ON_CLRBITS_SHIFT)
+#define LED_PANIC_OFF_SETBITS ((HYMINI_STM32_LED2) << OFF_SETBITS_SHIFT)
+#define LED_PANIC_OFF_CLRBITS ((HYMINI_STM32_LED1) << OFF_CLRBITS_SHIFT)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const uint16_t g_ledbits[8] =
+{ (LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS | LED_STARTED_OFF_SETBITS
+ | LED_STARTED_OFF_CLRBITS),
+
+(LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS
+ | LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS),
+
+(LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS
+ | LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS),
+
+(LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS
+ | LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS),
+
+(LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS | LED_INIRQ_OFF_SETBITS
+ | LED_INIRQ_OFF_CLRBITS),
+
+(LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS | LED_SIGNAL_OFF_SETBITS
+ | LED_SIGNAL_OFF_CLRBITS),
+
+(LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS | LED_ASSERTION_OFF_SETBITS
+ | LED_ASSERTION_OFF_CLRBITS),
+
+(LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS | LED_PANIC_OFF_SETBITS
+ | LED_PANIC_OFF_CLRBITS) };
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static inline void led_clrbits(unsigned int clrbits)
+{
+ if ((clrbits & HYMINI_STM32_LED1) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+
+ if ((clrbits & HYMINI_STM32_LED2) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED2, false);
+ }
+}
+
+static inline void led_setbits(unsigned int setbits)
+{
+ if ((setbits & HYMINI_STM32_LED1) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+
+ if ((setbits & HYMINI_STM32_LED2) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
+
+static void led_setonoff(unsigned int bits)
+{
+ led_clrbits(CLRBITS(bits));
+ led_setbits(SETBITS(bits));
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ /* Configure LED1 & LED2 GPIOs for output */
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ led_setonoff(ON_BITS(g_ledbits[led]));
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ led_setonoff(OFF_BITS(g_ledbits[led]));
+}
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/hymini-stm32v/src/up_nsh.c b/nuttx/configs/hymini-stm32v/src/up_nsh.c
new file mode 100644
index 000000000..d7c4605ac
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_nsh.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * config/hymini-stm32v/src/up_nsh.c
+ * arch/arm/src/board/up_nsh.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#ifdef CONFIG_STM32_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+#endif
+
+#ifdef CONFIG_STM32_SDIO
+# include <nuttx/sdio.h>
+# include <nuttx/mmcsd.h>
+#endif
+
+#include "stm32_internal.h"
+#include "hymini_stm32v-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* For now, don't build in any SPI1 support -- NSH is not using it */
+
+#undef CONFIG_STM32_SPI1
+
+
+/* PORT and SLOT number probably depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_HYMINI_STM32V
+# define CONFIG_NSH_HAVEUSBDEV 1
+# define CONFIG_NSH_HAVEMMCSD 1
+# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0
+# error "Only one MMC/SD slot"
+# undef CONFIG_NSH_MMCSDSLOTNO
+# endif
+# ifndef CONFIG_NSH_MMCSDSLOTNO
+# define CONFIG_NSH_MMCSDSLOTNO 0
+# endif
+#else
+ /* Add configuration for new STM32 boards here */
+# error "Unrecognized STM32 board"
+# undef CONFIG_NSH_HAVEUSBDEV
+# undef CONFIG_NSH_HAVEMMCSD
+#endif
+
+/* Can't support USB features if USB is not enabled */
+
+#ifndef CONFIG_USBDEV
+# undef CONFIG_NSH_HAVEUSBDEV
+#endif
+
+/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
+ * is not enabled.
+ */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO)
+# undef CONFIG_NSH_HAVEMMCSD
+#endif
+
+#ifndef CONFIG_NSH_MMCSDMINOR
+# define CONFIG_NSH_MMCSDMINOR 0
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+#ifdef CONFIG_NSH_HAVEMMCSD
+ FAR struct sdio_dev_s *sdio;
+ int ret;
+
+ /* Card detect */
+ bool cd_status;
+#endif
+
+ /* Mount the SDIO-based MMC/SD block driver */
+
+#ifdef CONFIG_NSH_HAVEMMCSD
+ /* First, get an instance of the SDIO interface */
+
+ message("nsh_archinitialize: Initializing SDIO slot %d\n",
+ CONFIG_NSH_MMCSDSLOTNO);
+ sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
+ if (!sdio)
+ {
+ message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
+ CONFIG_NSH_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+
+ message("nsh_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n",
+ CONFIG_NSH_MMCSDMINOR);
+ ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
+ if (ret != OK)
+ {
+ message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ return ret;
+ }
+ message("nsh_archinitialize: Successfully bound SDIO to the MMC/SD driver\n");
+
+ /* Use SD card detect pin to check if a card is inserted */
+
+ cd_status = !stm32_gpioread(GPIO_SD_CD);
+ message("Card detect : %hhu", cd_status);
+
+ sdio_mediachange(sdio, cd_status);
+#endif
+ return OK;
+}
diff --git a/nuttx/configs/hymini-stm32v/src/up_spi.c b/nuttx/configs/hymini-stm32v/src/up_spi.c
new file mode 100644
index 000000000..631c70ce9
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_spi.c
@@ -0,0 +1,179 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/up_spi.c
+ * arch/arm/src/board/up_spi.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "hymini_stm32v-internal.h"
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#define SPI_DEBUG /* Define to enable debug */
+#define SPI_VERBOSE /* Define to enable verbose debug */
+
+#ifdef SPI_DEBUG
+# define spidbg lldbg
+# ifdef SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the HY-MiniSTM32 board.
+ *
+ ************************************************************************************/
+
+void stm32_spiinitialize(void)
+{
+ /* NOTE: Clocking for SPI1 and/or SPI2 was already provided in stm32_rcc.c.
+ * Configurations of SPI pins is performed in stm32_spi.c.
+ * Here, we only initialize chip select pins unique to the board
+ * architecture.
+ */
+
+#ifdef CONFIG_STM32_SPI1
+ /* Configure the SPI-based touch screen CS GPIO */
+ spivdbg("Configure GPIO for SPI1/CS\n");
+ stm32_configgpio(GPIO_TS_CS);
+#endif
+}
+
+/****************************************************************************
+ * Name: stm32_spi1/2/3select and stm32_spi1/2/3status
+ *
+ * Description:
+ * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be
+ * provided by board-specific logic. They are implementations of the select
+ * and status methods of the SPI interface defined by struct spi_ops_s (see
+ * include/nuttx/spi.h). All other methods (including up_spiinitialize())
+ * are provided by common STM32 logic. To use this common SPI logic on your
+ * board:
+ *
+ * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select
+ * pins.
+ * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your
+ * board-specific logic. These functions will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_SPI1
+void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ if (devid == SPIDEV_TOUCHSCREEN)
+ {
+ /* Set the GPIO low to select and high to de-select */
+
+ stm32_gpiowrite(GPIO_TS_CS, !selected);
+ }
+}
+
+uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+}
+
+uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+}
+
+uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
diff --git a/nuttx/configs/hymini-stm32v/src/up_ts.c b/nuttx/configs/hymini-stm32v/src/up_ts.c
new file mode 100644
index 000000000..6c4decf7c
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_ts.c
@@ -0,0 +1,163 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/up_ts.c
+ * arch/arm/src/board/up_ts.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Laurent Latil <laurent@latil.nom.fr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/spi.h>
+#include <nuttx/arch.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include "stm32.h"
+#include "stm32_internal.h"
+#include "hymini_stm32v-internal.h"
+
+#include <nuttx/input/ads7843e.h>
+
+#if !defined(CONFIG_STM32_SPI1)
+# error CONFIG_STM32_SPI1 must be defined to use the ADS7843 on this board
+#endif
+
+static int hymini_ts_irq_attach(FAR struct ads7843e_config_s *state, xcpt_t isr);
+static void hymini_ts_irq_enable(FAR struct ads7843e_config_s *state,
+ bool enable);
+static void hymini_ts_irq_clear(FAR struct ads7843e_config_s *state);
+static bool hymini_ts_busy(FAR struct ads7843e_config_s *state);
+static bool hymini_ts_pendown(FAR struct ads7843e_config_s *state);
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+static FAR struct ads7843e_config_s ts_cfg =
+{
+ .frequency = CONFIG_ADS7843E_FREQUENCY,
+
+ .attach = hymini_ts_irq_attach,
+ .enable=hymini_ts_irq_enable,
+ .clear=hymini_ts_irq_clear,
+ .busy = hymini_ts_busy,
+ .pendown=hymini_ts_pendown
+};
+
+static xcpt_t tc_isr;
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/* Attach the ADS7843E interrupt handler to the GPIO interrupt */
+static int hymini_ts_irq_attach(FAR struct ads7843e_config_s *state, xcpt_t isr)
+{
+ ivdbg("hymini_ts_irq_attach\n");
+
+ tc_isr = isr;
+ stm32_gpiosetevent(GPIO_TS_IRQ, true, true, true, isr);
+ return OK;
+}
+
+/* Enable or disable the GPIO interrupt */
+static void hymini_ts_irq_enable(FAR struct ads7843e_config_s *state,
+ bool enable)
+{
+ illvdbg("%d\n", enable);
+
+ stm32_gpiosetevent(GPIO_TS_IRQ, true, true, true, enable? tc_isr:NULL);
+}
+
+/* Acknowledge/clear any pending GPIO interrupt */
+static void hymini_ts_irq_clear(FAR struct ads7843e_config_s *state)
+{
+ // FIXME Nothing to do ?
+}
+
+/* As the busy line is not connected, we just wait a little bit here */
+static bool hymini_ts_busy(FAR struct ads7843e_config_s *state)
+{
+ up_mdelay(50);
+ return false;
+}
+
+/* Return the state of the pen down GPIO input */
+static bool hymini_ts_pendown(FAR struct ads7843e_config_s *state)
+{
+ bool pin_value = stm32_gpioread(GPIO_TS_IRQ);
+ return !pin_value;
+}
+
+/****************************************************************************
+ * Name: arch_tcinitialize()
+ *
+ * Description:
+ * Perform architecture-specific initialization of the touchscreen.
+ * This function must be called directly from application.
+ *
+ ****************************************************************************/
+
+int arch_tcinitialize(int minor)
+{
+ FAR struct spi_dev_s *dev;
+
+ idbg("arch_tcinitialize: minor %d\n", minor);
+
+ dev = up_spiinitialize(1);
+ if (!dev)
+ {
+ idbg("arch_tcinitialize: Failed to initialize SPI bus\n");
+ return -ENODEV;
+ }
+
+ /* Configure the PIO interrupt */
+
+ stm32_configgpio(GPIO_TS_IRQ);
+
+ return ads7843e_register(dev, &ts_cfg, minor);
+}
+
+/****************************************************************************
+ * Name: arch_tcuninitialize()
+ *
+ * Description:
+ * Perform architecture-specific un-initialization of the touchscreen
+ * hardware. This function must be called directly from application.
+ *
+ ****************************************************************************/
+
+void arch_tcuninitialize(void)
+{
+ /* FIXME What can/should we do here ? */
+}
diff --git a/nuttx/configs/hymini-stm32v/src/up_usbdev.c b/nuttx/configs/hymini-stm32v/src/up_usbdev.c
new file mode 100644
index 000000000..061ed9234
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_usbdev.c
@@ -0,0 +1,117 @@
+/************************************************************************************
+ * configs/hymini-stm32v/src/up_usbdev.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "stm32_internal.h"
+#include "hymini_stm32v-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the Hy-Mini STM32v board.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void)
+{
+ ulldbg("called\n");
+
+ /* USB Soft Connect Pullup */
+ stm32_configgpio(GPIO_USB_PULLUP);
+}
+
+/************************************************************************************
+ * Name: stm32_usbpullup
+ *
+ * Description:
+ * If USB is supported and the board supports a pullup via GPIO (for USB software
+ * connect and disconnect), then the board software must provide stm32_pullup.
+ * See include/nuttx/usb/usbdev.h for additional description of this method.
+ * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be
+ * NULL.
+ *
+ ************************************************************************************/
+
+int stm32_usbpullup(FAR struct usbdev_s *dev, bool enable)
+{
+ usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
+ stm32_gpiowrite(GPIO_USB_PULLUP, !enable);
+ return OK;
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+
diff --git a/nuttx/configs/hymini-stm32v/src/up_usbstrg.c b/nuttx/configs/hymini-stm32v/src/up_usbstrg.c
new file mode 100644
index 000000000..8a309c270
--- /dev/null
+++ b/nuttx/configs/hymini-stm32v/src/up_usbstrg.c
@@ -0,0 +1,164 @@
+/****************************************************************************
+ * configs/hymini-stm32v/src/up_usbstrg.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Configure and register the STM32 MMC/SD SDIO block driver.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/sdio.h>
+#include <nuttx/mmcsd.h>
+
+#include "stm32_internal.h"
+
+/* There is nothing to do here if SDIO support is not selected. */
+
+#ifdef CONFIG_STM32_SDIO
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_EXAMPLES_USBSTRG_DEVMINOR1
+# define CONFIG_EXAMPLES_USBSTRG_DEVMINOR1 0
+#endif
+
+/* SLOT number(s) could depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_HYMINI_STM32V
+# undef STM32_MMCSDSLOTNO
+# define STM32_MMCSDSLOTNO 0
+#else
+ /* Add configuration for new STM32 boards here */
+# error "Unrecognized STM32 board"
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# define msgflush()
+# else
+# define message(...) printf(__VA_ARGS__)
+# define msgflush() fflush(stdout)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# define msgflush()
+# else
+# define message printf
+# define msgflush() fflush(stdout)
+# endif
+#endif
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbstrg_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int usbstrg_archinitialize(void)
+{
+ /* If examples/usbstrg is built as an NSH command, then SD slot should
+ * already have been initialized in nsh_archinitialize() (see up_nsh.c). In
+ * this case, there is nothing further to be done here.
+ */
+
+#ifndef CONFIG_EXAMPLES_USBSTRG_BUILTIN
+ FAR struct sdio_dev_s *sdio;
+ int ret;
+
+ /* First, get an instance of the SDIO interface */
+
+ message("usbstrg_archinitialize: "
+ "Initializing SDIO slot %d\n",
+ STM32_MMCSDSLOTNO);
+
+ sdio = sdio_initialize(STM32_MMCSDSLOTNO);
+ if (!sdio)
+ {
+ message("usbstrg_archinitialize: Failed to initialize SDIO slot %d\n",
+ STM32_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+
+ message("usbstrg_archinitialize: "
+ "Bind SDIO to the MMC/SD driver, minor=%d\n",
+ CONFIG_EXAMPLES_USBSTRG_DEVMINOR1);
+
+ ret = mmcsd_slotinitialize(CONFIG_EXAMPLES_USBSTRG_DEVMINOR1, sdio);
+ if (ret != OK)
+ {
+ message("usbstrg_archinitialize: "
+ "Failed to bind SDIO to the MMC/SD driver: %d\n",
+ ret);
+ return ret;
+ }
+ message("usbstrg_archinitialize: "
+ "Successfully bound SDIO to the MMC/SD driver\n");
+
+ /* Then let's guess and say that there is a card in the slot. I need to check to
+ * see if the Hy-Mini STM32v board supports a GPIO to detect if there is a card in
+ * the slot.
+ */
+
+ sdio_mediachange(sdio, true);
+
+#endif /* CONFIG_EXAMPLES_USBSTRG_BUILTIN */
+
+ return OK;
+}
+
+#endif /* CONFIG_STM32_SDIO */