From d7561fc092955ee766d6d423071c2186efe0a695 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 26 Sep 2012 19:41:54 +0000 Subject: [PATCH] Shenzhou board has an SSD1289 LCD, not ILI93xx git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5194 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 + nuttx/Kconfig | 47 +++-- nuttx/configs/shenzhou/nxwm/defconfig | 6 + nuttx/configs/shenzhou/src/Makefile | 2 +- .../configs/shenzhou/src/shenzhou-internal.h | 11 +- .../shenzhou/src/{up_lcd.c => up_ili93xx.c} | 85 ++++++-- nuttx/configs/shenzhou/src/up_ssd1289.c | 190 +++++++++++++----- nuttx/configs/shenzhou/src/up_touchscreen.c | 2 +- nuttx/drivers/lcd/Kconfig | 28 +++ nuttx/drivers/lcd/ssd1289.c | 8 +- 10 files changed, 286 insertions(+), 96 deletions(-) rename nuttx/configs/shenzhou/src/{up_lcd.c => up_ili93xx.c} (96%) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 3c4f142d12..906b63d33f 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3413,3 +3413,6 @@ SPI3 and some do not (still not clear). * nuttx/configs/shenzhou: Various fixes to build new NxWM configuration. + * configs/shenzhou: Oops. The Shenzhou LCD is and SSD1289, + not an ILI93xx. + diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 86e8849bc8..7ac512607e 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -216,7 +216,7 @@ endmenu menu "Debug Options" config DEBUG - bool "Enable debug features" + bool "Enable Debug Features" default n ---help--- Enables built-in debug features. Selecting this option will (1) Enable @@ -227,94 +227,107 @@ config DEBUG if DEBUG config DEBUG_VERBOSE - bool "Enable debug verbose output" + bool "Enable Debug Verbose Output" default n ---help--- Enables verbose debug output (assuming debug output is enabled) config DEBUG_ENABLE - bool "Enable debug controls" + bool "Enable Debug Controls" default n ---help--- Support an interface to dynamically enable or disable debug output. config DEBUG_SCHED - bool "Enable scheduler debug output" + bool "Enable Scheduler Debug Output" default n ---help--- Enable OS debug output (disabled by default) config DEBUG_MM - bool "Enable memory manager debug output" + bool "Enable Memory Manager Debug Output" default n ---help--- Enable memory management debug output (disabled by default) config DEBUG_NET - bool "Enable network debug output" + bool "Enable Network Debug Output" default n + depends on NET ---help--- Enable network debug output (disabled by default) config DEBUG_USB - bool "Enable USB debug output" + bool "Enable USB Debug Output" default n + depends on USBDEV || USBHOST ---help--- Enable usb debug output (disabled by default) config DEBUG_FS - bool "Enable file system debug output" + bool "Enable File System Debug Output" default n ---help--- Enable file system debug output (disabled by default) config DEBUG_LIB - bool "Enable C library debug output" + bool "Enable C Library Debug Output" default n ---help--- Enable C library debug output (disabled by default) config DEBUG_BINFMT - bool "Enable binary loader debug output" + bool "Enable Binary Loader Debug Output" default n ---help--- Enable binary loader debug output (disabled by default) config DEBUG_GRAPHICS - bool "Enable graphics debug output" + bool "Enable Graphics Debug Output" default n ---help--- Enable NX graphics debug output (disabled by default) config DEBUG_LCD - bool "Enable low-leve LCD debug output" + bool "Enable Low-level LCD Debug Output" default n depends on LCD ---help--- Enable low level debug output from the LCD driver (disabled by default) -config DEBUG_I2C - bool "Enable I2C debug output" +config DEBUG_INPUT + bool "Enable Input Device Debug Output" default n + depends on INPUT + ---help--- + Enable low level debug output from the input device drivers such as + mice and touchscreens (disabled by default) + +config DEBUG_I2C + bool "Enable I2C Debug Output" + default n + depends on I2C ---help--- Enable I2C driver debug output (disabled by default) config DEBUG_SPI - bool "Enable SPI debug output" + bool "Enable SPI Debug Output" default n + depends on SPI ---help--- Enable I2C driver debug output (disabled by default) config DEBUG_WATCHDOG - bool "Enable watchdog timer debug output" + bool "Enable Watchdog Timer Debug Output" default n + depends on WATCHDOG ---help--- Enable watchdog timer debug output (disabled by default) endif config DEBUG_SYMBOLS - bool "Enable debug symbols" + bool "Enable Debug Symbols" default n ---help--- Build without optimization and with debug symbols (needed diff --git a/nuttx/configs/shenzhou/nxwm/defconfig b/nuttx/configs/shenzhou/nxwm/defconfig index 9889e887de..29c83730e7 100644 --- a/nuttx/configs/shenzhou/nxwm/defconfig +++ b/nuttx/configs/shenzhou/nxwm/defconfig @@ -197,6 +197,7 @@ CONFIG_STM32_PHYSR_100FD=0x8000 CONFIG_STM32_RMII=y CONFIG_STM32_RMII_MCO=y # CONFIG_STM32_RMII_EXTCLK is not set +# CONFIG_STM32_ETHMAC_REGDEBUG is not set # # USB Host Configuration @@ -350,6 +351,7 @@ CONFIG_SPI_EXCHANGE=y # CONFIG_SPI_CMDDATA is not set CONFIG_RTC=y # CONFIG_RTC_DATETIME is not set +# CONFIG_RTC_HIRES is not set # CONFIG_RTC_ALARM is not set # CONFIG_WATCHDOG is not set # CONFIG_ANALOG is not set @@ -364,6 +366,10 @@ CONFIG_LCD_MAXPOWER=1 # CONFIG_LCD_P14201 is not set # CONFIG_LCD_NOKIA6100 is not set # CONFIG_LCD_UG9664HSWAG01 is not set +CONFIG_LCD_SSD1289=y +CONFIG_SSD1289_PROFILE1=y +# CONFIG_SSD1289_PROFILE2 is not set +# CONFIG_SSD1289_PROFILE3 is not set CONFIG_LCD_LANDSCAPE=y # CONFIG_LCD_PORTRAIT is not set # CONFIG_LCD_RPORTRAIT is not set diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile index 04088110c8..1775f1fcec 100644 --- a/nuttx/configs/shenzhou/src/Makefile +++ b/nuttx/configs/shenzhou/src/Makefile @@ -89,7 +89,7 @@ endif ifeq ($(CONFIG_LCD_SSD1289),y) CSRCS += up_ssd1289.c else -CSRCS += up_lcd.c +CSRCS += up_ili93xx.c endif ifeq ($(CONFIG_INPUT_ADS7843E),y) diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h index 095cba4850..51ab105532 100644 --- a/nuttx/configs/shenzhou/src/shenzhou-internal.h +++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h @@ -295,22 +295,29 @@ (STM32_PERIPHBB_BASE + ((offs + STM32_GPIO_BRR_OFFSET) << 5) + ((pin) << 2)) #define LCD_BIT_SET(offs,pin) \ (STM32_PERIPHBB_BASE + ((offs + STM32_GPIO_BSRR_OFFSET) << 5) + ((pin) << 2)) +#define LCD_BIT_READ(offs,pin) \ + (STM32_PERIPHBB_BASE + ((offs + STM32_GPIO_ODR_OFFSET) << 5) + ((pin) << 2)) #define LCD_RS_CLEAR LCD_BIT_CLEAR(STM32_GPIOD_OFFSET, 13) /* GPIO_PORTD|GPIO_PIN13 */ #define LCD_RS_SET LCD_BIT_SET(STM32_GPIOD_OFFSET, 13) +#define LCD_RS_READ LCD_BIT_READ(STM32_GPIOD_OFFSET, 13) #define LCD_CS_CLEAR LCD_BIT_CLEAR(STM32_GPIOC_OFFSET, 8) /* GPIO_PORTC|GPIO_PIN8 */ #define LCD_CS_SET LCD_BIT_SET(STM32_GPIOC_OFFSET, 8) +#define LCD_CS_READ LCD_BIT_READ(STM32_GPIOC_OFFSET, 8) #define LCD_RD_CLEAR LCD_BIT_CLEAR(STM32_GPIOD_OFFSET, 15) /* GPIO_PORTD|GPIO_PIN15 */ #define LCD_RD_SET LCD_BIT_SET(STM32_GPIOD_OFFSET, 15) +#define LCD_RD_READ LCD_BIT_READ(STM32_GPIOD_OFFSET, 15) #define LCD_WR_CLEAR LCD_BIT_CLEAR(STM32_GPIOD_OFFSET, 14) /* GPIO_PORTD|GPIO_PIN14 */ #define LCD_WR_SET LCD_BIT_SET(STM32_GPIOD_OFFSET, 14) +#define LCD_WR_READ LCD_BIT_READ(STM32_GPIOD_OFFSET, 14) #define LCD_LE_CLEAR LCD_BIT_CLEAR(STM32_GPIOB_OFFSET, 2) /* GPIO_PORTB|GPIO_PIN2 */ #define LCD_LE_SET LCD_BIT_SET(STM32_GPIOB_OFFSET, 2) +#define LCD_LE_READ LCD_BIT_READ(STM32_GPIOB_OFFSET, 2) #define LCD_CRL STM32_GPIOE_CRL #define LCD_CRH STM32_GPIOE_CRH -#define LCD_INPUT 0x44444444 -#define LCD_OUTPUT 0x33333333 +#define LCD_INPUT 0x44444444 /* Floating input */ +#define LCD_OUTPUT 0x33333333 /* Push/pull output */ #define LCD_ODR STM32_GPIOE_ODR #define LCD_IDR STM32_GPIOE_IDR diff --git a/nuttx/configs/shenzhou/src/up_lcd.c b/nuttx/configs/shenzhou/src/up_ili93xx.c similarity index 96% rename from nuttx/configs/shenzhou/src/up_lcd.c rename to nuttx/configs/shenzhou/src/up_ili93xx.c index 1de2a7d4bc..ef2cee417c 100644 --- a/nuttx/configs/shenzhou/src/up_lcd.c +++ b/nuttx/configs/shenzhou/src/up_ili93xx.c @@ -1,6 +1,6 @@ /************************************************************************************ - * configs/shenzhou/src/up_lcd.c - * arch/arm/src/board/up_lcd.c + * configs/shenzhou/src/up_ili93xx.c + * arch/arm/src/board/up_ili93xx.c * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Authors: Gregory Nutt @@ -211,6 +211,7 @@ # undef CONFIG_DEBUG_VERBOSE # undef CONFIG_DEBUG_GRAPHICS # undef CONFIG_DEBUG_LCD +# undef CONFIG_LCD_REGDEBUG #endif #ifndef CONFIG_DEBUG_VERBOSE @@ -425,6 +426,12 @@ struct stm32_dev_s ************************************************************************************/ /* Low Level LCD access */ +#ifdef CONFIG_LCD_REGDEBUG +static void stm32_lcdshow(FAR struct stm32_lower_s *priv, FAR const char *msg); +#else +# define stm32_lcdshow(p,m) +#endif + static void stm32_writereg(FAR struct stm32_dev_s *priv, uint8_t regaddr, uint16_t regval); static uint16_t stm32_readreg(FAR struct stm32_dev_s *priv, uint8_t regaddr); @@ -485,7 +492,7 @@ static inline void stm32_lcd9919init(FAR struct stm32_dev_s *priv); #ifndef CONFIG_STM32_ILI1505_DISABLE static inline void stm32_lcd1505init(FAR struct stm32_dev_s *priv); #endif -static inline void stm32_lcdinitialize(FAR struct stm32_dev_s *priv); +static inline int stm32_lcdinitialize(FAR struct stm32_dev_s *priv); /************************************************************************************ * Private Data @@ -577,6 +584,33 @@ static struct stm32_dev_s g_lcddev = * Private Functions ************************************************************************************/ +/************************************************************************************ + * Name: stm32_lcdshow + * + * Description: + * Show the state of the interface + * + ************************************************************************************/ + +#ifdef CONFIG_LCD_REGDEBUG +static void stm32_lcdshow(FAR struct stm32_lower_s *priv, FAR const char *msg) +{ + dbg("%s:\n", msg); + dbg(" CRTL RS: %d CS: %d RD: %d WR: %d LE: %d\n", + getreg32(LCD_RS_READ), getreg32(LCD_CS_READ), getreg32(LCD_RD_READ), + getreg32(LCD_WR_READ), getreg32(LCD_LE_READ)); + dbg(" DATA CR: %08x %08x\n", getreg32(LCD_CRL), getreg32(LCD_CRH)); + if (priv->output) + { + dbg(" OUTPUT: %08x\n", getreg32(LCD_ODR)); + } + else + { + dbg(" INPUT: %08x\n", getreg32(LCD_IDR)); + } +} +#endif + /************************************************************************************ * Name: stm32_writereg * @@ -601,7 +635,7 @@ static void stm32_writereg(FAR struct stm32_dev_s *priv, uint8_t regaddr, uint16 /* Then write the 16-bit register value */ - putreg32(1, LCD_RS_CLEAR); + putreg32(1, LCD_RS_SET); putreg32(1, LCD_WR_CLEAR); putreg32((uint32_t)regval, LCD_ODR); putreg32(1, LCD_WR_SET); @@ -638,7 +672,7 @@ static uint16_t stm32_readreg(FAR struct stm32_dev_s *priv, uint8_t regaddr) /* Read the 16-bit register value */ - putreg32(1, LCD_RS_CLEAR); + putreg32(1, LCD_RS_SET); putreg32(1, LCD_RD_CLEAR); putreg32(1, LCD_RD_SET); regval = (uint16_t)getreg32(LCD_IDR); @@ -688,7 +722,7 @@ static inline void stm32_writegram(FAR struct stm32_dev_s *priv, uint16_t rgbval /* Write the value (GRAM register already selected) */ putreg32(1, LCD_CS_CLEAR); - putreg32(1, LCD_RS_CLEAR); + putreg32(1, LCD_RS_SET); putreg32(1, LCD_WR_CLEAR); putreg32((uint32_t)rgbval, LCD_ODR); putreg32(1, LCD_WR_SET); @@ -713,7 +747,8 @@ static inline uint16_t stm32_readgram(FAR struct stm32_dev_s *priv) /* Read the 16-bit value */ - putreg32(1, LCD_RS_CLEAR); + putreg32(1, LCD_CS_CLEAR); + putreg32(1, LCD_RS_SET); putreg32(1, LCD_RD_CLEAR); putreg32(1, LCD_RD_SET); regval = (uint16_t)getreg32(LCD_IDR); @@ -770,8 +805,16 @@ static uint16_t stm32_readnoshift(FAR struct stm32_dev_s *priv, FAR uint16_t *ac static void stm32_setcursor(FAR struct stm32_dev_s *priv, uint16_t col, uint16_t row) { - stm32_writereg(priv, LCD_REG_32, row); /* GRAM horizontal address */ - stm32_writereg(priv, LCD_REG_33, col); /* GRAM vertical address */ + if (priv->type = LCD_TYPE_ILI9919) + { + stm32_writereg(priv, LCD_REG_78, col); /* GRAM horizontal address */ + stm32_writereg(priv, LCD_REG_79, row); /* GRAM vertical address */ + } + else + { + stm32_writereg(priv, LCD_REG_32, row); /* GRAM vertical address */ + stm32_writereg(priv, LCD_REG_33, col); /* GRAM horizontal address */ + } } /************************************************************************************ @@ -1726,9 +1769,10 @@ static inline void stm32_lcd1505init(FAR struct stm32_dev_s *priv) * ************************************************************************************/ -static inline void stm32_lcdinitialize(FAR struct stm32_dev_s *priv) +static inline int stm32_lcdinitialize(FAR struct stm32_dev_s *priv) { uint16_t id; + int ret = OK; /* Check LCD ID */ @@ -1809,11 +1853,12 @@ static inline void stm32_lcdinitialize(FAR struct stm32_dev_s *priv) #endif { lcddbg("Unsupported LCD type\n"); + ret = -ENODEV; } lcddbg("LCD type: %d\n", priv->type); + return ret; } - /************************************************************************************ * Public Functions ************************************************************************************/ @@ -1831,6 +1876,7 @@ static inline void stm32_lcdinitialize(FAR struct stm32_dev_s *priv) int up_lcdinitialize(void) { FAR struct stm32_dev_s *priv = &g_lcddev; + int ret; int i; lcdvdbg("Initializing\n"); @@ -1851,16 +1897,19 @@ int up_lcdinitialize(void) /* Configure and enable LCD */ up_mdelay(50); - stm32_lcdinitialize(priv); + ret = stm32_lcdinitialize(priv); + if (ret == OK) + { + /* Clear the display (setting it to the color 0=black) */ - /* Clear the display (setting it to the color 0=black) */ + stm32_lcdclear(0); - stm32_lcdclear(0); + /* Turn the display off */ - /* Turn the display off */ + stm32_poweroff(priv); + } - stm32_poweroff(priv); - return OK; + return ret; } /************************************************************************************ @@ -1925,7 +1974,7 @@ void stm32_lcdclear(uint16_t color) /* Write the selected color into the entire GRAM memory */ putreg32(1, LCD_CS_CLEAR); - putreg32(1, LCD_RS_CLEAR); + putreg32(1, LCD_RS_SET); for (i = 0; i < STM32_XRES * STM32_YRES; i++) { putreg32(1, LCD_WR_CLEAR); diff --git a/nuttx/configs/shenzhou/src/up_ssd1289.c b/nuttx/configs/shenzhou/src/up_ssd1289.c index 2b48c78ca7..cf02b36d19 100644 --- a/nuttx/configs/shenzhou/src/up_ssd1289.c +++ b/nuttx/configs/shenzhou/src/up_ssd1289.c @@ -76,6 +76,7 @@ # undef CONFIG_DEBUG_VERBOSE # undef CONFIG_DEBUG_GRAPHICS # undef CONFIG_DEBUG_LCD +# undef CONFIG_LCD_REGDEBUG #endif #ifndef CONFIG_DEBUG_VERBOSE @@ -100,14 +101,29 @@ * Private Type Definition ************************************************************************************/ +/* This structure describes the state of this driver */ + +struct stm32_lower_s +{ + struct ssd1289_lcd_s dev; /* This is externally visible the driver state */ + FAR struct lcd_dev_s *drvr; /* The saved instance of the LCD driver */ + bool output; /* True: Configured for output */ +}; + /************************************************************************************** * Private Function Protototypes **************************************************************************************/ /* Helpers */ -static void stm32_wrdata(uint16_t data); +#ifdef CONFIG_LCD_REGDEBUG +static void stm32_lcdshow(FAR struct stm32_lower_s *priv, FAR const char *msg); +#else +# define stm32_lcdshow(p,m) +#endif + +static void stm32_wrdata(FAR struct stm32_lower_s *priv, uint16_t data); #ifndef CONFIG_SSD1289_WRONLY -static uint16_t stm32_rddata(void); +static inline uint16_t stm32_rddata(FAR struct stm32_lower_s *priv); #endif /* Low Level LCD access */ @@ -121,6 +137,11 @@ static uint16_t stm32_read(FAR struct ssd1289_lcd_s *dev); static void stm32_write(FAR struct ssd1289_lcd_s *dev, uint16_t data); static void stm32_backlight(FAR struct ssd1289_lcd_s *dev, int power); +/* Initialization */ + +static void stm32_lcdinput(FAR struct stm32_lower_s *priv); +static void stm32_lcdoutput(FAR struct stm32_lower_s *priv); + /************************************************************************************ * Private Data ************************************************************************************/ @@ -224,28 +245,55 @@ static const uint32_t g_lcdconfig[] = }; #define NLCD_CONFIG (sizeof(g_lcdconfig)/sizeof(uint32_t)) -/* This is the driver state structure (there is no retained state information) */ +/* Driver state structure (only supports one LCD) */ -static struct ssd1289_lcd_s g_ssd1289 = +static struct stm32_lower_s g_lcdlower = { - .select = stm32_select, - .deselect = stm32_deselect, - .index = stm32_index, + { + .select = stm32_select, + .deselect = stm32_deselect, + .index = stm32_index, #ifndef CONFIG_SSD1289_WRONLY - .read = stm32_read, + .read = stm32_read, #endif - .write = stm32_write, - .backlight = stm32_backlight + .write = stm32_write, + .backlight = stm32_backlight + }, + .drvr = NULL, + .output = false }; -/* The saved instance of the LCD driver */ - -static FAR struct lcd_dev_s *g_ssd1289drvr; - /************************************************************************************ * Private Functions ************************************************************************************/ +/************************************************************************************ + * Name: stm32_lcdshow + * + * Description: + * Show the state of the interface + * + ************************************************************************************/ + +#ifdef CONFIG_LCD_REGDEBUG +static void stm32_lcdshow(FAR struct stm32_lower_s *priv, FAR const char *msg) +{ + dbg("%s:\n", msg); + dbg(" CRTL RS: %d CS: %d RD: %d WR: %d LE: %d\n", + getreg32(LCD_RS_READ), getreg32(LCD_CS_READ), getreg32(LCD_RD_READ), + getreg32(LCD_WR_READ), getreg32(LCD_LE_READ)); + dbg(" DATA CR: %08x %08x\n", getreg32(LCD_CRL), getreg32(LCD_CRH)); + if (priv->output) + { + dbg(" OUTPUT: %08x\n", getreg32(LCD_ODR)); + } + else + { + dbg(" INPUT: %08x\n", getreg32(LCD_IDR)); + } +} +#endif + /************************************************************************************ * Name: stm32_wrdata * @@ -254,11 +302,11 @@ static FAR struct lcd_dev_s *g_ssd1289drvr; * ************************************************************************************/ -static void stm32_wrdata(uint16_t data) +static void stm32_wrdata(FAR struct stm32_lower_s *priv, uint16_t data) { /* Make sure D0-D15 are configured as outputs */ - stm32_lcdoutput(); + stm32_lcdoutput(priv); /* Latch the 16-bit LCD data and toggle the WR line */ @@ -276,18 +324,17 @@ static void stm32_wrdata(uint16_t data) ************************************************************************************/ #ifndef CONFIG_SSD1289_WRONLY -static uint16_t stm32_rddata(void); +static inline uint16_t stm32_rddata(FAR struct stm32_lower_s *priv) { /* Make sure D0-D15 are configured as inputs */ - stm32_lcdinput(); + stm32_lcdinput(priv); /* Toggle the RD line to latch the 16-bit LCD data */ -#warning "Requires pins configured as inputs" putreg32(1, LCD_RD_CLEAR); putreg32(1, LCD_RD_SET); - return (uin16_t)getreg32(LCD_IDR); + return (uint16_t)getreg32(LCD_IDR); } #endif @@ -322,7 +369,7 @@ static void stm32_deselect(FAR struct ssd1289_lcd_s *dev) } /************************************************************************************ - * Name: stm32_deselect + * Name: stm32_index * * Description: * Set the index register @@ -331,13 +378,15 @@ static void stm32_deselect(FAR struct ssd1289_lcd_s *dev) static void stm32_index(FAR struct ssd1289_lcd_s *dev, uint8_t index) { - /* Clear the RS signal */ + FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)dev; - putreg32(1, LCD_RS_CLR); + /* Clear the RS signal to select the index address */ + + putreg32(1, LCD_RS_CLEAR); /* And write the index */ - stm32_wrdata((uint16_t)index); + stm32_wrdata(priv, (uint16_t)index); } /************************************************************************************ @@ -351,13 +400,15 @@ static void stm32_index(FAR struct ssd1289_lcd_s *dev, uint8_t index) #ifndef CONFIG_SSD1289_WRONLY static uint16_t stm32_read(FAR struct ssd1289_lcd_s *dev) { - /* Set the RS signal */ + FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)dev; - putreg32(1, LCD_RS_CLR); + /* Set the RS signal to select the data address */ - /* And return the data */ + putreg32(1, LCD_RS_SET); - return stm32_rddata(); + /* Read and return the data */ + + return stm32_rddata(priv); } #endif @@ -371,13 +422,15 @@ static uint16_t stm32_read(FAR struct ssd1289_lcd_s *dev) static void stm32_write(FAR struct ssd1289_lcd_s *dev, uint16_t data) { - /* Set the RS signal */ + FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)dev; - putreg32(1, LCD_RS_CLR); + /* Set the RS signal to select the data address */ + + putreg32(1, LCD_RS_SET); /* And write the data */ - stm32_wrdata(data); + stm32_wrdata(priv, data); } /************************************************************************************ @@ -401,21 +454,31 @@ static void stm32_backlight(FAR struct ssd1289_lcd_s *dev, int power) * ************************************************************************************/ -static void stm32_lcdinput(void) +static void stm32_lcdinput(FAR struct stm32_lower_s *priv) { -#ifdef CONFIG_LCD_FASTCONFIG - putreg32(LCD_INPUT, LCD_CRL); - putreg32(LCD_INPUT, LCD_CRH); -#else +#ifndef CONFIG_LCD_FASTCONFIG int i; - - /* Configure GPIO data lines as inputs */ - - for (i = 0; i < 16; i++) - { - stm32_configgpio(g_lcdin[i]); - } #endif + + /* Check if we are already configured for input */ + + if (priv->output) + { + /* Configure GPIO data lines as inputs */ + +#ifdef CONFIG_LCD_FASTCONFIG + putreg32(LCD_INPUT, LCD_CRL); + putreg32(LCD_INPUT, LCD_CRH); +#else + for (i = 0; i < 16; i++) + { + stm32_configgpio(g_lcdin[i]); + } +#endif + /* No longer configured for output */ + + priv->output = false; + } } /************************************************************************************ @@ -426,15 +489,30 @@ static void stm32_lcdinput(void) * ************************************************************************************/ -static void stm32_lcdoutput(void) +static void stm32_lcdoutput(FAR struct stm32_lower_s *priv) { +#ifndef CONFIG_LCD_FASTCONFIG int i; +#endif - /* Configure GPIO data lines as outputs */ + /* Check if we are already configured for output */ - for (i = 0; i < 16; i++) + if (!priv->output) { - stm32_configgpio(g_lcdout[i]); + /* Configure GPIO data lines as outputs */ + +#ifdef CONFIG_LCD_FASTCONFIG + putreg32(LCD_OUTPUT, LCD_CRL); + putreg32(LCD_OUTPUT, LCD_CRH); +#else + for (i = 0; i < 16; i++) + { + stm32_configgpio(g_lcdout[i]); + } +#endif + /* Now we are configured for output */ + + priv->output = true; } } @@ -454,17 +532,18 @@ static void stm32_lcdoutput(void) int up_lcdinitialize(void) { + FAR struct stm32_lower_s *priv = &g_lcdlower; int i; /* Only initialize the driver once */ - if (!g_ssd1289drvr) + if (!priv->drvr) { lcdvdbg("Initializing\n"); /* Configure GPIO pins */ - stm32_lcdoutput(); + stm32_lcdoutput(priv); for (i = 0; i < NLCD_CONFIG; i++) { stm32_configgpio(g_lcdconfig[i]); @@ -472,8 +551,8 @@ int up_lcdinitialize(void) /* Configure and enable the LCD */ - g_ssd1289drvr = ssd1289_lcdinitialize(&g_ssd1289); - if (!g_ssd1289drvr) + priv->drvr = ssd1289_lcdinitialize(&priv->dev); + if (!priv->drvr) { lcddbg("ERROR: ssd1289_lcdinitialize failed\n"); return -ENODEV; @@ -482,7 +561,7 @@ int up_lcdinitialize(void) /* Turn the display off */ - g_ssd1289drvr->setpower(g_ssd1289drvr, 0); + priv->drvr->setpower(priv->drvr, 0); return OK; } @@ -497,8 +576,9 @@ int up_lcdinitialize(void) FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) { + FAR struct stm32_lower_s *priv = &g_lcdlower; DEBUGASSERT(lcddev == 0); - return g_ssd1289drvr; + return priv->drvr; } /************************************************************************************ @@ -511,9 +591,11 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) void up_lcduninitialize(void) { + FAR struct stm32_lower_s *priv = &g_lcdlower; + /* Turn the display off */ - g_ssd1289drvr->setpower(g_ssd1289drvr, 0); + priv->drvr->setpower(priv->drvr, 0); } #endif /* CONFIG_LCD_SSD1289 */ diff --git a/nuttx/configs/shenzhou/src/up_touchscreen.c b/nuttx/configs/shenzhou/src/up_touchscreen.c index 92b057f5d4..9f584e5bb9 100644 --- a/nuttx/configs/shenzhou/src/up_touchscreen.c +++ b/nuttx/configs/shenzhou/src/up_touchscreen.c @@ -177,7 +177,7 @@ static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable) /* Attach and enable, or detach and disable */ - ivdbg("IRQ:%d enable:%d\n", STM32_TCS_IRQ, enable); + ivdbg("enable:%d\n", enable); if (enable) { (void)stm32_gpiosetevent(GPIO_TP_INT, false, true, true, diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig index 851263d279..640239e637 100644 --- a/nuttx/drivers/lcd/Kconfig +++ b/nuttx/drivers/lcd/Kconfig @@ -43,6 +43,7 @@ config LCD_P14201 p14201.c. Driver for RiT P14201 series display with SD1329 IC controller. This OLED is used with older versions of the TI/Luminary LM3S8962 Evaluation Kit. + if LCD_P14201 config P14201_NINTERFACES int "Number of physical P14201 devices" @@ -189,6 +190,33 @@ config LCD_UG9664HSWAG01 Technology Inc. Used with the LPC Xpresso and Embedded Artists base board. +config LCD_SSD1289 + bool "LCD Based on SSD1289 Controller" + default n + ---help--- + Enables generic support for any LCD based on the Solomon Systech, + Ltd, SSD1289 Controller. Use of this driver will usually require so + detailed customization of the LCD initialization code as necessary + for the specific LCD driven by the SSD1289 controller. + +if LCD_SSD1289 + +choice + prompt "SSD1289 Initialization Profile" + default SSD1289_PROFILE1 + +config SSD1289_PROFILE1 + bool "Profile 1" + +config SSD1289_PROFILE2 + bool "Profile 2" + +config SSD1289_PROFILE3 + bool "Profile 3" + +endchoice +endif + choice prompt "LCD Orientation" default LCD_LANDSCAPE diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c index 58c6069682..3d5ba96d31 100644 --- a/nuttx/drivers/lcd/ssd1289.c +++ b/nuttx/drivers/lcd/ssd1289.c @@ -766,7 +766,7 @@ static int ssd1289_getvideoinfo(FAR struct lcd_dev_s *dev, { DEBUGASSERT(dev && vinfo); lcdvdbg("fmt: %d xres: %d yres: %d nplanes: 1\n", - SSD1289_COLORFMT, SSD1289_XRES, SSD1289_XRES); + SSD1289_COLORFMT, SSD1289_XRES, SSD1289_YRES); vinfo->fmt = SSD1289_COLORFMT; /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ vinfo->xres = SSD1289_XRES; /* Horizontal resolution in pixel columns */ @@ -925,6 +925,7 @@ static inline int ssd1289_hwinitialize(FAR struct ssd1289_dev_s *priv) #ifndef CONFIG_LCD_NOGETRUN uint16_t id; #endif + int ret; /* Select the LCD */ @@ -1168,19 +1169,20 @@ static inline int ssd1289_hwinitialize(FAR struct ssd1289_dev_s *priv) /* One driver has a 50 msec delay here */ /* up_mdelay(50); */ - return OK; + ret = OK; } #ifndef CONFIG_LCD_NOGETRUN else { lcddbg("Unsupported LCD type\n"); - return -ENODEV; + ret = -ENODEV; } #endif /* De-select the LCD */ lcd->deselect(lcd); + return ret; } /*************************************************************************************