From 53159328821d252d29e3227ed78fbd8147af5cf0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 May 2012 15:45:46 +0000 Subject: [PATCH] Add generic SSD1289 LCD driver git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4768 7fd9a85b-ad96-42d3-883c-3090e2eb8679 --- nuttx/ChangeLog | 4 + nuttx/configs/stm3240g-eval/src/up_lcd.c | 2 +- nuttx/drivers/lcd/Make.defs | 8 +- nuttx/drivers/lcd/sd1329.h | 2 +- nuttx/drivers/lcd/ssd1289.c | 1202 ++++++++++++++++++++++ nuttx/drivers/lcd/ssd1289.h | 425 ++++++++ nuttx/include/nuttx/lcd/ssd1289.h | 138 +++ 7 files changed, 1777 insertions(+), 4 deletions(-) create mode 100644 nuttx/drivers/lcd/ssd1289.c create mode 100644 nuttx/drivers/lcd/ssd1289.h create mode 100644 nuttx/include/nuttx/lcd/ssd1289.h diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 38bf017adf..519e69ee54 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -2801,5 +2801,9 @@ * configs/stm3240g-eval/nxwm/defconfig: Enable support for NxConsole keyboard input. Increasing spacing of icons. * configs/stm3240g-eval/nxwm/defconfig: Use a larger font for the calculator. + * include/nuttx/lcd/ssd1289.h, drivers/lcd/ssd1289.c and .h: Generic LCD + driver for LCDs based on the Solomon Systech SSD1289 LCD driver. This + of this as a template for an LCD driver that will have to be cusomized + for your particular LCD hardware. diff --git a/nuttx/configs/stm3240g-eval/src/up_lcd.c b/nuttx/configs/stm3240g-eval/src/up_lcd.c index e209880750..45e4a2b57b 100644 --- a/nuttx/configs/stm3240g-eval/src/up_lcd.c +++ b/nuttx/configs/stm3240g-eval/src/up_lcd.c @@ -1191,7 +1191,7 @@ void up_lcduninitialize(void) * This is a non-standard LCD interface just for the stm3240g-EVAL board. Because * of the various rotations, clearing the display in the normal way by writing a * sequences of runs that covers the entire display can be very slow. Here the - * dispaly is cleared by simply setting all GRAM memory to the specified color. + * display is cleared by simply setting all GRAM memory to the specified color. * **************************************************************************************/ diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs index 596cce7d5d..d3ea174d2f 100644 --- a/nuttx/drivers/lcd/Make.defs +++ b/nuttx/drivers/lcd/Make.defs @@ -1,8 +1,8 @@ ############################################################################ # drivers/lcd/Make.defs # -# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Copyright (C) 2010-2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -51,6 +51,10 @@ ifeq ($(CONFIG_LCD_UG9664HSWAG01),y) CSRCS += ug-9664hswag01.c endif +ifeq ($(CONFIG_LCD_SSD1289),y) + CSRCS += ssd1289.c +endif + # Include LCD driver build support DEPPATH += --dep-path lcd diff --git a/nuttx/drivers/lcd/sd1329.h b/nuttx/drivers/lcd/sd1329.h index f578d808cf..5d2ad4948d 100644 --- a/nuttx/drivers/lcd/sd1329.h +++ b/nuttx/drivers/lcd/sd1329.h @@ -2,7 +2,7 @@ * drivers/lcd/sd1329.h * * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c new file mode 100644 index 0000000000..c463a550f9 --- /dev/null +++ b/nuttx/drivers/lcd/ssd1289.c @@ -0,0 +1,1202 @@ +/************************************************************************************** + * drivers/lcd/ssd1289.c + * + * Generic LCD driver for LCDs based on the Solomon Systech SSD1289 LCD controller. + * Think of this as a template for an LCD driver that you will proably ahve to + * customize for any particular LCD hardware. + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * + * References: SSD1289, Rev 1.3, Apr 2007, Solomon Systech Limited + * + * 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 + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "ssd1289.h" + +#ifdef CONFIG_LCD_SSD1289 + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ +/* Configuration **********************************************************************/ + +/* Check contrast selection */ + +#if !defined(CONFIG_LCD_MAXCONTRAST) +# define CONFIG_LCD_MAXCONTRAST 1 +#endif + +/* Check power setting */ + +#if !defined(CONFIG_LCD_MAXPOWER) || CONFIG_LCD_MAXPOWER < 1 +# define CONFIG_LCD_MAXPOWER 1 +#endif + +#if CONFIG_LCD_MAXPOWER > 255 +# error "CONFIG_LCD_MAXPOWER must be less than 256 to fit in uint8_t" +#endif + +/* Check orientation */ + +#if defined(CONFIG_LCD_PORTRAIT) +# if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) || defined(CONFIG_LCD_RPORTRAIT) +# error "Cannot define both portrait and any other orientations" +# endif +#elif defined(CONFIG_LCD_RPORTRAIT) +# if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) +# error "Cannot define both rportrait and any other orientations" +# endif +#elif defined(CONFIG_LCD_LANDSCAPE) +# ifdef CONFIG_LCD_RLANDSCAPE +# error "Cannot define both landscape and any other orientations" +# endif +#elif !defined(CONFIG_LCD_RLANDSCAPE) +# define CONFIG_LCD_LANDSCAPE 1 +#endif + +/* Define CONFIG_DEBUG_LCD to enable detailed LCD debug output. Verbose debug must + * also be enabled. + */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_GRAPHICS +# undef CONFIG_DEBUG_LCD +#endif + +#ifndef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_LCD +#endif + +/* Display/Color Properties ***********************************************************/ +/* Display Resolution */ + +#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) +# define SSD1289_XRES 320 +# define SSD1289_YRES 240 +#else +# define SSD1289_XRES 240 +# define SSD1289_YRES 320 +#endif + +/* Color depth and format */ + +#define SSD1289_BPP 16 +#define SSD1289_COLORFMT FB_FMT_RGB16_565 + +/* Debug ******************************************************************************/ + +#ifdef CONFIG_DEBUG_LCD +# define lcddbg dbg +# define lcdvdbg vdbg +#else +# define lcddbg(x...) +# define lcdvdbg(x...) +#endif + +/************************************************************************************** + * Private Type Definition + **************************************************************************************/ + +/* This structure describes the state of this driver */ + +struct ssd1289_dev_s +{ + /* Publically visible device structure */ + + struct lcd_dev_s dev; + + /* Private LCD-specific information follows */ + + FAR struct ssd1289_lcd_s *lcd; /* The contained platform-specific, LCD interface */ + uint8_t power; /* Current power setting */ + + /* 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. + */ + + uint16_t runbuffer[SSD1289_XRES]; +}; + +/************************************************************************************** + * Private Function Protototypes + **************************************************************************************/ +/* Low Level LCD access */ + +static void ssd1289_putreg(FAR struct ssd1289_lcd_s *lcd, uint8_t regaddr, + uint16_t regval); +#ifndef CONFIG_SSD1289_WRONLY +static uint16_t ssd1289_readreg(FAR struct ssd1289_lcd_s *lcd, uint8_t regaddr); +#endif +static inline void ssd1289_gramwrite(FAR struct ssd1289_lcd_s *lcd, uint16_t rgbcolor); +#ifndef CONFIG_SSD1289_WRONLY +static inline void ssd1289_readsetup(FAR struct ssd1289_lcd_s *lcd, FAR uint16_t *accum); +static inline uint16_t ssd1289_gramread(FAR struct ssd1289_lcd_s *lcd, FAR uint16_t *accum); +#endif +static void ssd1289_setcursor(FAR struct ssd1289_lcd_s *lcd, uint16_t column, + uint16_t row); + +/* LCD Data Transfer Methods */ + +static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels); +static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels); + +/* LCD Configuration */ + +static int ssd1289_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo); +static int ssd1289_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 ssd1289_getpower(FAR struct lcd_dev_s *dev); +static int ssd1289_setpower(FAR struct lcd_dev_s *dev, int power); +static int ssd1289_getcontrast(FAR struct lcd_dev_s *dev); +static int ssd1289_setcontrast(FAR struct lcd_dev_s *dev, unsigned int contrast); + +/* Initialization */ + +static inline void ssd1289_hwinitialize(FAR struct ssd1289_dev_s *priv); + +/************************************************************************************** + * Private Data + **************************************************************************************/ + +/* This driver can support only a signal SSD1289 device. This is due to an + * unfortunate decision made whent he getrun and putrun methods were designed. The + * following is the single SSD1289 driver state instance: + */ + +static struct ssd1289_dev_s g_lcddev; + +/************************************************************************************** + * Private Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: ssd1289_putreg(lcd, + * + * Description: + * Write to an LCD register + * + **************************************************************************************/ + +static void ssd1289_putreg(FAR struct ssd1289_lcd_s *lcd, uint8_t regaddr, uint16_t regval) +{ + /* Set the index register to the register address and write the register contents */ + + lcd->index(lcd, regaddr); + lcd->write(lcd, regval); +} + +/************************************************************************************** + * Name: ssd1289_readreg + * + * Description: + * Read from an LCD register + * + **************************************************************************************/ + +#ifndef CONFIG_SSD1289_WRONLY +static uint16_t ssd1289_readreg(FAR struct ssd1289_lcd_s *lcd, uint8_t regaddr) +{ + /* Set the index register to the register address and read the register contents */ + + lcd->index(lcd, regaddr); + return lcd->read(lcd); +} +#endif + +/************************************************************************************** + * Name: ssd1289_gramselect + * + * Description: + * Setup to read or write multiple pixels to the GRAM memory + * + **************************************************************************************/ + +static inline void ssd1289_gramselect(FAR struct ssd1289_lcd_s *lcd) +{ + lcd->index(lcd, SSD1289_DATA); +} + +/************************************************************************************** + * Name: ssd1289_gramwrite + * + * Description: + * Setup to read or write multiple pixels to the GRAM memory + * + **************************************************************************************/ + +static inline void ssd1289_gramwrite(FAR struct ssd1289_lcd_s *lcd, uint16_t data) +{ + lcd->write(lcd, data); +} + +/************************************************************************************** + * Name: ssd1289_readsetup + * + * Description: + * Prime the operation by reading one pixel from the GRAM memory if necessary for + * this LCD type. When reading 16-bit gram data, there may be some shifts in the + * returned data: + * + * - ILI932x: Discard first dummy read; no shift in the return data + * + **************************************************************************************/ + +#ifndef CONFIG_SSD1289_WRONLY +static inline void ssd1289_readsetup(FAR struct ssd1289_lcd_s *lcd, FAR uint16_t *accum) +{ + /* Read-ahead one pixel */ + + *accum = lcd->read(lcd); +} +#endif + +/************************************************************************************** + * Name: ssd1289_gramread + * + * Description: + * Read one correctly aligned pixel from the GRAM memory. Possibly shifting the + * data and possibly swapping red and green components. + * + * - ILI932x: Unknown -- assuming colors are in the color order + * + **************************************************************************************/ + +#ifndef CONFIG_SSD1289_WRONLY +static inline uint16_t ssd1289_gramread(FAR struct ssd1289_lcd_s *lcd, FAR uint16_t *accum) +{ + /* Read the value (GRAM register already selected) */ + + return lcd->read(lcd); +} +#endif + +/************************************************************************************** + * Name: ssd1289_setcursor + * + * Description: + * Set the cursor position. In landscape mode, the "column" is actually the physical + * Y position and the "row" is the physical X position. + * + **************************************************************************************/ + +static void ssd1289_setcursor(FAR struct ssd1289_lcd_s *lcd, uint16_t column, uint16_t row) +{ +#if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT) + ssd1289_putreg(lcd, SSD1289_XADDR, column); /* 0-239 */ + ssd1289_putreg(lcd, SSD1289_YADDR, row); /* 0-319 */ +#elif defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) + ssd1289_putreg(lcd, SSD1289_XADDR, row); /* 0-239 */ + ssd1289_putreg(lcd, SSD1289_YADDR, column); /* 0-319 */ +#endif +} + +/************************************************************************************** + * Name: ssd1289_dumprun + * + * Description: + * Dump the contexts of the run buffer: + * + * run - The buffer in containing the run read to be dumped + * npixels - The number of pixels to dump + * + **************************************************************************************/ + +#if 0 /* Sometimes useful */ +static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixels) +{ + int i, j; + + lib_rawprintf("\n%s:\n", msg); + for (i = 0; i < npixels; i += 16) + { + up_putc(' '); + lib_rawprintf(" "); + for (j = 0; j < 16; j++) + { + lib_rawprintf(" %04x", *run++); + } + up_putc('\n'); + } +} +#endif + +/************************************************************************************** + * Name: ssd1289_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) + * + **************************************************************************************/ + +static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels) +{ + FAR struct ssd1289_dev_s *priv = &g_lcddev; + FAR struct ssd1289_lcd_s *lcd = priv->lcd; + FAR const uint16_t *src = (FAR const uint16_t*)buffer; + int i; + + /* Buffer must be provided and aligned to a 16-bit address boundary */ + + lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0); + + /* Select the LCD */ + + lcd->select(lcd); + + /* Write the run to GRAM. */ + +#ifdef CONFIG_LCD_LANDSCAPE + /* Convert coordinates -- Here the edge away from the row of buttons on + * the STM3240G-EVAL is used as the top. + */ + + /* Write the GRAM data, manually incrementing X */ + + for (i = 0; i < npixels; i++) + { + /* Write the next pixel to this position */ + + ssd1289_setcursor(lcd, col, row); + ssd1289_gramselect(lcd); + ssd1289_gramwrite(lcd, *src); + + /* Increment to next column */ + + src++; + col++; + } +#elif defined(CONFIG_LCD_RLANDSCAPE) + /* Convert coordinates -- Here the edge next to the row of buttons on + * the STM3240G-EVAL is used as the top. + */ + + col = (SSD1289_XRES-1) - col; + row = (SSD1289_YRES-1) - row; + + /* Set the cursor position */ + + ssd1289_setcursor(lcd, col, row); + + /* Then write the GRAM data, auto-decrementing X */ + + ssd1289_gramselect(lcd); + for (i = 0; i < npixels; i++) + { + /* Write the next pixel to this position (auto-decrements to the next column) */ + + ssd1289_gramwrite(lcd, *src); + src++; + } +#elif defined(CONFIG_LCD_PORTRAIT) + /* Convert coordinates. In this configuration, the top of the display is to the left + * of the buttons (if the board is held so that the buttons are at the botton of the + * board). + */ + + col = (SSD1289_XRES-1) - col; + + /* Then write the GRAM data, manually incrementing Y (which is col) */ + + for (i = 0; i < npixels; i++) + { + /* Write the next pixel to this position */ + + ssd1289_setcursor(lcd, row, col); + ssd1289_gramselect(lcd); + ssd1289_gramwrite(lcd, *src); + + /* Increment to next column */ + + src++; + col--; + } +#else /* CONFIG_LCD_RPORTRAIT */ + /* Convert coordinates. In this configuration, the top of the display is to the right + * of the buttons (if the board is held so that the buttons are at the botton of the + * board). + */ + + row = (SSD1289_YRES-1) - row; + + /* Then write the GRAM data, manually incrementing Y (which is col) */ + + for (i = 0; i < npixels; i++) + { + /* Write the next pixel to this position */ + + ssd1289_setcursor(lcd, row, col); + ssd1289_gramselect(lcd); + ssd1289_gramwrite(lcd, *src); + + /* Decrement to next column */ + + src++; + col++; + } +#endif + + /* De-select the LCD */ + + lcd->deselect(lcd); + return OK; +} + +/************************************************************************************** + * Name: ssd1289_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) + * + **************************************************************************************/ + +static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels) +{ +#ifndef CONFIG_SSD1289_WRONLY + FAR struct ssd1289_dev_s *priv = &g_lcddev; + FAR struct ssd1289_lcd_s *lcd = priv->lcd; + FAR uint16_t *dest = (FAR uint16_t*)buffer; + uint16_t accum; + int i; + + /* Buffer must be provided and aligned to a 16-bit address boundary */ + + lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels); + DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0); + + /* Select the LCD */ + + lcd->select(lcd); + + /* Read the run from GRAM. */ + +#ifdef CONFIG_LCD_LANDSCAPE + /* Convert coordinates -- Here the edge away from the row of buttons on + * the STM3240G-EVAL is used as the top. + */ + + for (i = 0; i < npixels; i++) + { + /* Read the next pixel from this position */ + + ssd1289_setcursor(lcd, row, col); + ssd1289_gramselect(lcd); + ssd1289_readsetup(lcd, &accum); + *dest++ = ssd1289_gramread(lcd, &accum); + + /* Increment to next column */ + + col++; + } +#elif defined(CONFIG_LCD_RLANDSCAPE) + /* Convert coordinates -- Here the edge next to the row of buttons on + * the STM3240G-EVAL is used as the top. + */ + + col = (SSD1289_XRES-1) - col; + row = (SSD1289_YRES-1) - row; + + /* Set the cursor position */ + + ssd1289_setcursor(lcd, col, row); + + /* Then read the GRAM data, auto-decrementing Y */ + + ssd1289_gramselect(lcd); + + /* Prime the pump for unaligned read data */ + + ssd1289_readsetup(lcd, &accum); + + for (i = 0; i < npixels; i++) + { + /* Read the next pixel from this position (autoincrements to the next row) */ + + *dest++ = ssd1289_gramread(lcd, &accum); + } +#elif defined(CONFIG_LCD_PORTRAIT) + /* Convert coordinates. In this configuration, the top of the display is to the left + * of the buttons (if the board is held so that the buttons are at the botton of the + * board). + */ + + col = (SSD1289_XRES-1) - col; + + /* Then read the GRAM data, manually incrementing Y (which is col) */ + + for (i = 0; i < npixels; i++) + { + /* Read the next pixel from this position */ + + ssd1289_setcursor(lcd, row, col); + ssd1289_gramselect(lcd); + ssd1289_readsetup(lcd, &accum); + *dest++ = ssd1289_gramread(lcd, &accum); + + /* Increment to next column */ + + col--; + } +#else /* CONFIG_LCD_RPORTRAIT */ + /* Convert coordinates. In this configuration, the top of the display is to the right + * of the buttons (if the board is held so that the buttons are at the botton of the + * board). + */ + + row = (SSD1289_YRES-1) - row; + + /* Then write the GRAM data, manually incrementing Y (which is col) */ + + for (i = 0; i < npixels; i++) + { + /* Write the next pixel to this position */ + + ssd1289_setcursor(lcd, row, col); + ssd1289_gramselect(lcd); + ssd1289_readsetup(lcd, &accum); + *dest++ = ssd1289_gramread(lcd, &accum); + + /* Decrement to next column */ + + col++; + } +#endif + + /* De-select the LCD */ + + lcd->deselect(lcd); + return OK; +#else + return -ENOSYS; +#endif +} + +/************************************************************************************** + * Name: ssd1289_getvideoinfo + * + * Description: + * Get information about the LCD video controller configuration. + * + **************************************************************************************/ + +static int ssd1289_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo) +{ + DEBUGASSERT(dev && vinfo); + lcdvdbg("fmt: %d xres: %d yres: %d nplanes: 1\n", + SSD1289_COLORFMT, SSD1289_XRES, SSD1289_XRES); + + vinfo->fmt = SSD1289_COLORFMT; /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ + vinfo->xres = SSD1289_XRES; /* Horizontal resolution in pixel columns */ + vinfo->yres = SSD1289_YRES; /* Vertical resolution in pixel rows */ + vinfo->nplanes = 1; /* Number of color planes supported */ + return OK; +} + +/************************************************************************************** + * Name: ssd1289_getplaneinfo + * + * Description: + * Get information about the configuration of each LCD color plane. + * + **************************************************************************************/ + +static int ssd1289_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, + FAR struct lcd_planeinfo_s *pinfo) +{ + FAR struct ssd1289_dev_s *priv = (FAR struct ssd1289_dev_s *)dev; + + DEBUGASSERT(dev && pinfo && planeno == 0); + lcdvdbg("planeno: %d bpp: %d\n", planeno, SSD1289_BPP); + + pinfo->putrun = ssd1289_putrun; /* Put a run into LCD memory */ + pinfo->getrun = ssd1289_getrun; /* Get a run from LCD memory */ + pinfo->buffer = (uint8_t*)priv->runbuffer; /* Run scratch buffer */ + pinfo->bpp = SSD1289_BPP; /* Bits-per-pixel */ + return OK; +} + +/************************************************************************************** + * Name: ssd1289_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 ssd1289_getpower(FAR struct lcd_dev_s *dev) +{ + lcdvdbg("power: %d\n", 0); + return g_lcddev.power; +} + +/************************************************************************************** + * Name: ssd1289_poweroff + * + * Description: + * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On + * backlit LCDs, this setting may correspond to the backlight setting. + * + **************************************************************************************/ + +static int ssd1289_poweroff(FAR struct ssd1289_lcd_s *lcd) +{ + /* Set the backlight off */ + + lcd->backlight(lcd, 0); + + /* Turn the display off */ + + ssd1289_putreg(lcd, SSD1289_DSPCTRL, 0); + + /* Remember the power off state */ + + g_lcddev.power = 0; + return OK; +} + +/************************************************************************************** + * Name: ssd1289_setpower + * + * Description: + * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On + * backlit LCDs, this setting may correspond to the backlight setting. + * + **************************************************************************************/ + +static int ssd1289_setpower(FAR struct lcd_dev_s *dev, int power) +{ + FAR struct ssd1289_dev_s *priv = (FAR struct ssd1289_dev_s *)dev; + FAR struct ssd1289_lcd_s *lcd = priv->lcd; + + lcdvdbg("power: %d\n", power); + DEBUGASSERT((unsigned)power <= CONFIG_LCD_MAXPOWER); + + /* Set new power level */ + + if (power > 0) + { + /* Set the backlight level */ + + lcd->backlight(lcd, power); + + /* Then turn the display on: + * D=ON(3) CM=0 DTE=0 GON=1 SPT=0 VLE=0 PT=0 + */ + + ssd1289_putreg(lcd, SSD1289_DSPCTRL, + (SSD1289_DSPCTRL_ON | SSD1289_DSPCTRL_GON | + SSD1289_DSPCTRL_VLE(0))); + + g_lcddev.power = power; + } + else + { + /* Turn the display off */ + + ssd1289_poweroff(lcd); + } + + return OK; +} + +/************************************************************************************** + * Name: ssd1289_getcontrast + * + * Description: + * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static int ssd1289_getcontrast(FAR struct lcd_dev_s *dev) +{ + lcdvdbg("Not implemented\n"); + return -ENOSYS; +} + +/************************************************************************************** + * Name: ssd1289_setcontrast + * + * Description: + * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static int ssd1289_setcontrast(FAR struct lcd_dev_s *dev, unsigned int contrast) +{ + lcdvdbg("contrast: %d\n", contrast); + return -ENOSYS; +} + +/************************************************************************************** + * Name: ssd1289_hwinitialize + * + * Description: + * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static inline void ssd1289_hwinitialize(FAR struct ssd1289_dev_s *priv) +{ + FAR struct ssd1289_lcd_s *lcd = priv->lcd; +#ifndef CONFIG_SSD1289_WRONLY + uint16_t id; +#endif + + /* Select the LCD and home the cursor position */ + + lcd->select(lcd); + +#ifndef CONFIG_SSD1289_WRONLY + id = ssd1289_readreg(lcd, SSD1289_DEVCODE); + lcddbg("LCD ID: %04x\n", id); + + /* Check if the ID is for the SSD1289 */ + + if (id == SSD1289_DEVCODE_VALUE) +#endif + { + /* LCD controller configuration. Many details of the controller initialization + * must, unfortunately, vary from LCD to LCD. I have looked at the spec and at + * three different drivers for LCDs that have SSD1289 controllers. I have tried + * to summarize these differences as alternatives in the comments. + * + * Most of the differences between LCDs are nothing more than a few minor bit + * settings. The most significant difference betwen LCD drivers in is the + * manner in which the LCD is powered up and in how the power controls are set. + */ + + /* Most drivers just enable the oscillator */ +#if 1 + ssd1289_putreg(lcd, SSD1289_OSCSTART, SSD1289_OSCSTART_OSCEN); +#else + /* But one goes through a more complex start-up sequence. Something like the + * following: + * First, put the display in INTERNAL operation: + * D=INTERNAL(1) CM=0 DTE=0 GON=1 SPT=0 VLE=0 PT=0 + */ + + ssd1289_putreg(lcd, SSD1289_DSPCTRL, + (SSD1289_DSPCTRL_INTERNAL | SSD1289_DSPCTRL_GON | + SSD1289_DSPCTRL_VLE(0))); + + /* Then enable the oscillator */ + + ssd1289_putreg(lcd, SSD1289_OSCSTART, SSD1289_OSCSTART_OSCEN); + + /* Turn the display on: + * D=ON(3) CM=0 DTE=0 GON=1 SPT=0 VLE=0 PT=0 + */ + + ssd1289_putreg(lcd, SSD1289_DSPCTRL, + (SSD1289_DSPCTRL_ON | SSD1289_DSPCTRL_GON | + SSD1289_DSPCTRL_VLE(0))); + + /* Take the LCD out of sleep mode */ + + ssd1289_putreg(lcd, SSD1289_SLEEP, 0); + up_mdelay(30); + + /* Turn the display on: + * D=INTERNAL(1) CM=0 DTE=1 GON=1 SPT=0 VLE=0 PT=0 + */ + + ssd1289_putreg(lcd, SSD1289_DSPCTRL, + (SSD1289_DSPCTRL_ON | SSD1289_DSPCTRL_DTE | + SSD1289_DSPCTRL_GON | define SSD1289_DSPCTRL_VLE(0))); +#endif + + /* Set up power control registers. There is a lot of variability + * from LCD-to-LCD in how the power registers are configured. + * + * PWRCTRL1: + * AP=medium-to-large, DC=Fosc/4, BT=+5/-4, DCT=Fosc/4 + * Alternatives: + * AP=Large-to-maximum, DC=Fosc/4, BT=+5/-4, DCT=Fosc/4 + * AP=small-to-medium, DC=Flinex24, BT=+5/-4, DCT=Flinxx24 + * PWRCTRL2: + * SSD1289_PWRCTRL2_VRC_5p1V + * Alternatives + * SSD1289_PWRCTRL2_VRC_5p3V + * PWRCTRL3: + * SSD1289_PWRCTRL3_VRH_x2p335 + * Alternatives: + * SSD1289_PWRCTRL3_VRH_x2p165 + * SSD1289_PWRCTRL3_VRH_x2p500 + * NOTE: Many have bit 8 set which is not defined in the SSD1289 spec. + * PWRCTRL4: + * VDV=11, VCOMG=1 + * Alternatives: + * VDV=9 + * VDV=13 + * PWRCTRL5: + * VCM=56, NOTP=1 + * Alternatives: + * VCM=60 + */ + + ssd1289_putreg(lcd, SSD1289_PWRCTRL1, + (SSD1289_PWRCTRL1_AP_MEDLG | SSD1289_PWRCTRL1_DC_FOSd4 | + SSD1289_PWRCTRL1_BT_p5m4 | SSD1289_PWRCTRL1_DCT_FOSd4)); + + ssd1289_putreg(lcd, SSD1289_PWRCTRL2, + SSD1289_PWRCTRL2_VRC_5p1V); + + /* One driver adds a delay here.. I doubt that this is really necessary. + * Alternative: No delay + */ +#if 1 + up_mdelay(15); +#endif + + ssd1289_putreg(lcd, SSD1289_PWRCTRL3, + SSD1289_PWRCTRL3_VRH_x2p335); + ssd1289_putreg(lcd, SSD1289_PWRCTRL4, + (SSD1289_PWRCTRL4_VDV(11) | SSD1289_PWRCTRL4_VCOMG)); + ssd1289_putreg(lcd, SSD1289_PWRCTRL5, + (SSD1289_PWRCTRL5_VCM(56) | SSD1289_PWRCTRL5_NOTP)); + + /* One driver does an odd setting of the the driver output control. + * No idea why. + */ +#if 0 + ssd1289_putreg(lcd, SSD1289_OUTCTRL, + (SSD1289_OUTCTRL_MUX(12) | SSD1289_OUTCTRL_TB | + SSD1289_OUTCTRL_BGR | SSD1289_OUTCTRL_CAD)); +#endif + + /* The same driver does another small delay here */ +#if 1 + up_mdelay(15); +#endif + + /* After this point, the drivers differ only in some varying register + * bit settings. + */ + + /* Set the driver output control. + * PORTRAIT MODES: + * MUX=319, TB=1, SM=0, BGR=1, CAD=0, REV=1, RL=0 + * LANDSCAPE MODES: + * MUX=319, TB=0, SM=0, BGR=1, CAD=0, REV=1, RL=0 + */ + +#if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT) + ssd1289_putreg(lcd, SSD1289_OUTCTRL, + (SSD1289_OUTCTRL_MUX(319) | SSD1289_OUTCTRL_TB | + SSD1289_OUTCTRL_BGR | SSD1289_OUTCTRL_REV); +#else + ssd1289_putreg(lcd, SSD1289_OUTCTRL, + (SSD1289_OUTCTRL_MUX(319) | SSD1289_OUTCTRL_BGR | + SSD1289_OUTCTRL_REV)); +#endif + + /* Set the LCD driving AC waveform + * NW=0, WSMD=0, EOR=1, BC=1, ENWD=0, FLD=0 + */ + + ssd1289_putreg(lcd, SSD1289_ACCTRL, + (SSD1289_ACCTRL_EOR | SSD1289_ACCTRL_BC)); + + /* Take the LCD out of sleep mode */ + + ssd1289_putreg(lcd, SSD1289_SLEEP, 0); + + /* Set entry mode */ + +#if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT) + /* LG=0, AM=0, ID=3, TY=2, DMODE=0, WMODE=0, OEDEF=0, TRANS=0, DRM=3 + * Alternative TY=2 (But TY only applies in 262K color mode) + */ + + ssd1289_putreg(lcd, SSD1289_ENTRY, + (SSD1289_ENTRY_ID_HINCVINC | SSD1289_ENTRY_TY_B | + SSD1289_ENTRY_DMODE_RAM | SSD1289_ENTRY_DFM_65K)); +#else + /* LG=0, AM=1, ID=3, TY=2, DMODE=0, WMODE=0, OEDEF=0, TRANS=0, DRM=3 */ + /* Alternative TY=2 (But TY only applies in 262K color mode) */ + + ssd1289_putreg(lcd, SSD1289_ENTRY, + (SSD1289_ENTRY_AM | SSD1289_ENTRY_ID_HINCVINC | + SSD1289_ENTRY_TY_B | SSD1289_ENTRY_DMODE_RAM | + SSD1289_ENTRY_DFM_65K)); +#endif + + /* Clear compare registers */ + + ssd1289_putreg(lcd, SSD1289_CMP1, 0); + ssd1289_putreg(lcd, SSD1289_CMP2, 0); + up_mdelay(100); + + /* Set Horizontal and vertical porch. + * Horizontal porch: 239 pixels per line, delay=28 + * Vertical porch: VBP=3, XFP=0 + */ + + ssd1289_putreg(lcd, SSD1289_HPORCH, + (28 << SSD1289_HPORCH_HBP_SHIFT) | (239 << SSD1289_HPORCH_XL_SHIFT)); + ssd1289_putreg(lcd, SSD1289_VPORCH, + (3 << SSD1289_VPORCH_VBP_SHIFT) | (0 << SSD1289_VPORCH_XFP_SHIFT)); + + /* Set display control. + * D=ON(3), CM=0 (not 8-color), DTE=1, GON=1, SPT=0, VLE=1 PT=0 + */ + + ssd1289_putreg(lcd, SSD1289_DSPCTRL, + (SSD1289_DSPCTRL_ON | SSD1289_DSPCTRL_DTE | + SSD1289_DSPCTRL_GON | define SSD1289_DSPCTRL_VLE(1))); + + /* Frame cycle control. Alternative: SSD1289_FCYCCTRL_DIV8 */ + + ssd1289_putreg(lcd, SSD1289_FCYCCTRL, 0); + + /* Gate scan start position = 0 */ + + ssd1289_putreg(lcd, SSD1289_GSTART, 0); + + /* Clear vertical scrolling */ + + ssd1289_putreg(lcd, SSD1289_VSCROLL1, 0); + ssd1289_putreg(lcd, SSD1289_VSCROLL2, 0); + + /* Setup window 1 (0-319) */ + + ssd1289_putreg(lcd, SSD1289_W1START, 0); + ssd1289_putreg(lcd, SSD1289_W1END, 319); + + /* Disable window 2 (0-0) */ + + ssd1289_putreg(lcd, SSD1289_W2START, 0); + ssd1289_putreg(lcd, SSD1289_W2END, 0); + + /* Horizontal start and end (0-239) */ + + ssd1289_putreg(lcd, SSD1289_HADDR, + (0 << SSD1289_HADDR_HSA_SHIFT) | (239 << SSD1289_HADDR_HEA_SHIFT)); + + /* Vertical start and end (0-319) */ + + ssd1289_putreg(lcd, SSD1289_VSTART, 0); + ssd1289_putreg(lcd, SSD1289_VEND, 319); + + /* Gamma controls */ + + ssd1289_putreg(lcd, SSD1289_GAMMA1, 0x0707); + ssd1289_putreg(lcd, SSD1289_GAMMA2, 0x0204); /* Alternative: 0x0704 */ + ssd1289_putreg(lcd, SSD1289_GAMMA3, 0x0204); + ssd1289_putreg(lcd, SSD1289_GAMMA4, 0x0502); + ssd1289_putreg(lcd, SSD1289_GAMMA5, 0x0507); + ssd1289_putreg(lcd, SSD1289_GAMMA6, 0x0204); + ssd1289_putreg(lcd, SSD1289_GAMMA7, 0x0204); + ssd1289_putreg(lcd, SSD1289_GAMMA8, 0x0502); + ssd1289_putreg(lcd, SSD1289_GAMMA9, 0x0302); + ssd1289_putreg(lcd, SSD1289_GAMMA10, 0x0302); /* Alternative: 0x1f00 */ + + /* Clear write mask */ + + ssd1289_putreg(lcd, SSD1289_WRMASK1, 0); + ssd1289_putreg(lcd, SSD1289_WRMASK2, 0); + + /* Set frame frequency = 65Hz (This should not be necessary since this + * is the default POR value) + */ + + ssd1289_putreg(lcd, SSD1289_FFREQ, SSD1289_FFREQ_OSC_FF65); + + /* Set the cursor at the home position and set the index register to + * the gram data register (I can't imagine these are necessary). + */ + + ssd1289_setcursor(lcd, 0, 0); + ssd1289_gramselect(lcd); + + /* One driver has a 50 msec delay here */ +#if 0 + up_mdelay(50); +#endif + } + else + { + lcddbg("Unsupported LCD type\n"); + } + + /* De-select the LCD */ + + lcd->deselect(lcd); +} + + /************************************************************************************* + * Public Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: ssd1289_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). + * + **************************************************************************************/ + +FAR struct lcd_dev_s *ssd1289_lcdinitialize(FAR struct ssd1289_lcd_s *lcd) +{ + lcdvdbg("Initializing\n"); + + /* If we ccould support multiple SSD1289 devices, this is where we would allocate + * a new driver data structure... but we can't. Why not? Because of a bad should + * the form of the getrun() and putrun methods. + */ + + FAR struct ssd1289_dev_s *priv = &g_lcddev; + + /* Initialize the driver data structure */ + + priv->dev.getvideoinfo = ssd1289_getvideoinfo; + priv->dev.getplaneinfo = ssd1289_getplaneinfo; + priv->dev.getpower = ssd1289_getpower; + priv->dev.setpower = ssd1289_setpower; + priv->dev.getcontrast = ssd1289_getcontrast; + priv->dev.setcontrast = ssd1289_setcontrast; + priv->lcd = lcd; + + /* Configure and enable LCD */ + + ssd1289_hwinitialize(priv); + + /* Clear the display (setting it to the color 0=black) */ + + ssd1289_clear(&priv->dev, 0); + + /* Turn the display off */ + + ssd1289_poweroff(lcd); + return &g_lcddev.dev; +} + +/************************************************************************************** + * Name: ssd1289_clear + * + * Description: + * This is a non-standard LCD interface just for the stm3240g-EVAL board. Because + * of the various rotations, clearing the display in the normal way by writing a + * sequences of runs that covers the entire display can be very slow. Here the + * display is cleared by simply setting all GRAM memory to the specified color. + * + **************************************************************************************/ + +void ssd1289_clear(FAR struct lcd_dev_s *dev, uint16_t color) +{ + FAR struct ssd1289_dev_s *priv = (FAR struct ssd1289_dev_s *)dev; + FAR struct ssd1289_lcd_s *lcd = priv->lcd; + uint32_t i; + + /* Select the LCD and home the cursor position */ + + lcd->select(lcd); + ssd1289_setcursor(lcd, 0, 0); + + /* Prepare to write GRAM data */ + + ssd1289_gramselect(lcd); + + /* Copy color into all of GRAM. Orientation does not matter in this case. */ + + for (i = 0; i < SSD1289_XRES * SSD1289_YRES; i++) + { + ssd1289_gramwrite(lcd, color); + } + + /* De-select the LCD */ + + lcd->deselect(lcd); +} + +#endif /* CONFIG_LCD_SSD1289 */ diff --git a/nuttx/drivers/lcd/ssd1289.h b/nuttx/drivers/lcd/ssd1289.h new file mode 100644 index 0000000000..77606776ef --- /dev/null +++ b/nuttx/drivers/lcd/ssd1289.h @@ -0,0 +1,425 @@ +/************************************************************************************** + * drivers/lcd/ssd1289.h + * Definitions for the Solomon Systech SSD1289 LCD controller + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: SSD1289, Rev 1.3, Apr 2007, Solomon Systech Limited + * + * 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 __DRIVERS_LCD_SSD1289_H +#define __DRIVERS_LCD_SSD1289_H + +/************************************************************************************** + * Included Files + **************************************************************************************/ + +#include + +#ifdef CONFIG_LCD_SSD1289 + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ + +/* SSD1289 Register Addresses (All with DC=1) */ + +#define SSD1289_OSCSTART 0x00 /* Oscillation Start (write) */ +#define SSD1289_DEVCODE 0x00 /* Oscillation Start (read) */ +#define SSD1289_OUTCTRL 0x01 /* Driver output control */ +#define SSD1289_ACCTRL 0x02 /* LCD drive AC control */ +#define SSD1289_PWRCTRL1 0x03 /* Power control 1 */ +#define SSD1289_CMP1 0x05 /* Compare register 1 */ +#define SSD1289_CMP2 0x06 /* Compare register 2 */ +#define SSD1289_DSPCTRL 0x07 /* Display control */ +#define SSD1289_FCYCCTRL 0x0b /* Frame cycle control */ +#define SSD1289_PWRCTRL2 0x0c /* Power control 2 */ +#define SSD1289_PWRCTRL3 0x0d /* Power control 3 */ +#define SSD1289_PWRCTRL4 0x0e /* Power control 4 */ +#define SSD1289_GSTART 0x0f /* Gate scan start position */ +#define SSD1289_SLEEP 0x10 /* Sleep mode */ +#define SSD1289_ENTRY 0x11 /* Entry mode */ +#define SSD1289_OPT3 0x12 /* Optimize Access Speed 3 */ +#define SSD1289_GIFCTRL 0x15 /* Generic Interface Control */ +#define SSD1289_HPORCH 0x16 /* Horizontal Porch */ +#define SSD1289_VPORCH 0x17 /* Vertical Porch */ +#define SSD1289_PWRCTRL5 0x1e /* Power control 5 */ +#define SSD1289_DATA 0x22 /* RAM data/write data */ +#define SSD1289_WRMASK1 0x23 /* RAM write data mask 1 */ +#define SSD1289_WRMASK2 0x24 /* RAM write data mask 2 */ +#define SSD1289_FFREQ 0x25 /* Frame Frequency */ +#define SSD1289_VCOMOTP1 0x28 /* VCOM OTP */ +#define SSD1289_OPT1 0x28 /* Optimize Access Speed 1 */ +#define SSD1289_VCOMOTP2 0x29 /* VCOM OTP */ +#define SSD1289_OPT2 0x2f /* Optimize Access Speed 2 */ +#define SSD1289_GAMMA1 0x30 /* Gamma control 1 */ +#define SSD1289_GAMMA2 0x31 /* Gamma control 2 */ +#define SSD1289_GAMMA3 0x32 /* Gamma control 3 */ +#define SSD1289_GAMMA4 0x33 /* Gamma control 4 */ +#define SSD1289_GAMMA5 0x34 /* Gamma control 5 */ +#define SSD1289_GAMMA6 0x35 /* Gamma control 6 */ +#define SSD1289_GAMMA7 0x36 /* Gamma control 7 */ +#define SSD1289_GAMMA8 0x37 /* Gamma control 8 */ +#define SSD1289_GAMMA9 0x3a /* Gamma control 9 */ +#define SSD1289_GAMMA10 0x3b /* Gamma control 10 */ +#define SSD1289_VSCROLL1 0x41 /* Vertical scroll control 1 */ +#define SSD1289_VSCROLL2 0x42 /* Vertical scroll control 2 */ +#define SSD1289_HADDR 0x44 /* Horizontal RAM address position */ +#define SSD1289_VSTART 0x45 /* Vertical RAM address start position */ +#define SSD1289_VEND 0x46 /* Vertical RAM address end position */ +#define SSD1289_W1START 0x48 /* First window start */ +#define SSD1289_W1END 0x49 /* First window end */ +#define SSD1289_W2START 0x4a /* Second window start */ +#define SSD1289_W2END 0x4b /* Second window end */ +#define SSD1289_XADDR 0x4e /* Set GDDRAM X address counter */ +#define SSD1289_YADDR 0x4f /* Set GDDRAM Y address counter */ + +/* SSD1289 Register Bit definitions */ + +/* Index register (DC=0) */ + +#define SSD1289_INDEX_MASK 0xff + +/* Device code (read) */ + +#define SSD1289_DEVCODE_VALUE 0x8989 + +/* Oscillation Start (write) */ + +#define SSD1289_OSCSTART_OSCEN (1 << 0) /* Enable oscillator */ + +/* Driver output control */ + +#define SSD1289_OUTCTRL_MUX_SHIFT (0) /* Number of lines for the LCD driver */ +#define SSD1289_OUTCTRL_MUX_MASK (0x1ff < SSD1289_OUTCTRL_MUX_SHIFT) +# define SSD1289_OUTCTRL_MUX(n) ((n) < SSD1289_OUTCTRL_MUX_SHIFT) +#define SSD1289_OUTCTRL_TB (1 << 9) /* Selects the output shift direction of the gate driver */ +#define SSD1289_OUTCTRL_SM (1 << 10) /* Scanning order of gate driver */ +#define SSD1289_OUTCTRL_BGR (1 << 11) /* Order from RGB to BGR in 18-bit GDDRAM data */ +#define SSD1289_OUTCTRL_CAD (1 << 12) /* Retention capacitor configuration of the TFT panel */ +#define SSD1289_OUTCTRL_REV (1 << 13) /* Reversed display */ +#define SSD1289_OUTCTRL_RL (1 << 14) /* RL pin state */ + +/* LCD drive AC control */ + +#define SSD1289_ACCTRL_NW_SHIFT (0) /* Number of lines to alternate in N-line inversion */ +#define SSD1289_ACCTRL_NW_MASK (0xff << SSD1289_ACCTRL_NW_SHIFT) +#define SSD1289_ACCTRL_WSMD (1 << 8) /* Waveform of WSYNC output */ +#define SSD1289_ACCTRL_EOR (1 << 9) /* EOR signals */ +#define SSD1289_ACCTRL_BC (1 << 10) /* Select the liquid crystal drive waveform */ +#define SSD1289_ACCTRL_ENWS (1 << 11) /* Enables WSYNC output pin */ +#define SSD1289_ACCTRL_FLD (1 << 12) /* Set display in interlace drive mode */ + +/* Power control 2 */ + +#define SSD1289_PWRCTRL1_AP_SHIFT (1) /* Current from internal operational amplifier */ +#define SSD1289_PWRCTRL1_AP_MASK (7 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_LEAST (0 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_SMALL (1 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_SMMED (2 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_MEDIUM (3 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_MEDLG (4 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_LARGE (5 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_LGMX (6 << SSD1289_PWRCTRL1_AP_SHIFT) +# define SSD1289_PWRCTRL1_AP_MAX (7 << SSD1289_PWRCTRL1_AP_SHIFT) +#define SSD1289_PWRCTRL1_DC_SHIFT (4) /* Set the step-up cycle of the step-up circuit for 262k-color mode */ +#define SSD1289_PWRCTRL1_DC_MASK (15 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx24 (0 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx16 (1 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx12 (2 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx8 (3 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx6 (4 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx5 (5 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx4 (6 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx3 (7 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx2 (8 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FLINEx1 (9 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FOSd4 (10 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FOSd6 (11 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FOSd8 (12 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FOSd10 (13 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FOSd12 (14 << SSD1289_PWRCTRL1_DC_SHIFT) +# define SSD1289_PWRCTRL1_DC_FOSd16 (15 << SSD1289_PWRCTRL1_DC_SHIFT) +#define SSD1289_PWRCTRL1_BT_SHIFT (9) /* Control the step-up factor of the step-up circuit */ +#define SSD1289_PWRCTRL1_BT_MASK (7 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p6m5 (0 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p6m4 (1 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p6m6 (2 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p5m5 (3 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p5m4 (4 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p5m3 (5 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p4m4 (6 << SSD1289_PWRCTRL1_BT_SHIFT) +# define SSD1289_PWRCTRL1_BT_p4m3 (7 << SSD1289_PWRCTRL1_BT_SHIFT) +#define SSD1289_PWRCTRL1_DCT_SHIFT (12) /* Step-up cycle of the step-up circuit for 8-color mode */ +#define SSD1289_PWRCTRL1_DCT_MASK (15 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx24 (0 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx16 (1 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx12 (2 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx8 (3 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx6 (4 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx5 (5 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx4 (6 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx3 (7 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx2 (8 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FLINEx1 (9 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FOSd4 (10 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FOSd6 (11 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FOSd8 (12 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FOSd10 (13 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FOSd12 (14 << SSD1289_PWRCTRL1_DCT_SHIFT) +# define SSD1289_PWRCTRL1_DCT_FOSd16 (15 << SSD1289_PWRCTRL1_DCT_SHIFT) + +/* Compare register 1 and 2 */ + +#define SSD1289_CMP1_CPG_SHIFT (2) +#define SSD1289_CMP1_CPG_MASK (0x3f << SSD1289_CMP1_CPG_SHIFT) +#define SSD1289_CMP1_CPR_SHIFT (10) +#define SSD1289_CMP1_CPR_MASK (0x3f << SSD1289_CMP1_CPR_SHIFT) + +#define SSD1289_CMP2_CPB_SHIFT (2) +#define SSD1289_CMP2_CPB_MASK (0x3f << SSD1289_CMP2_CPB_SHIFT) + +/* Display control */ + +#define SSD1289_DSPCTRL_D_SHIFT (0) /* Display control */ +#define SSD1289_DSPCTRL_D_MASK (3 << SSD1289_DSPCTRL_D_SHIFT) +# define SSD1289_DSPCTRL_OFF (0 << SSD1289_DSPCTRL_D_SHIFT) +# define SSD1289_DSPCTRL_INTERNAL (1 << SSD1289_DSPCTRL_D_SHIFT) +# define SSD1289_DSPCTRL_ON (3 << SSD1289_DSPCTRL_D_SHIFT) +#define SSD1289_DSPCTRL_CM (1 << 3) /* 8-color mode setting */ +#define SSD1289_DSPCTRL_DTE (1 << 4) /* Selected gate level */ +#define SSD1289_DSPCTRL_GON (1 << 5) /* Gate off level */ +#define SSD1289_DSPCTRL_SPT (1 << 8) /* 2-division LCD drive */ +#define SSD1289_DSPCTRL_VLE_SHIFT (9) /* Vertical scroll control */ +#define SSD1289_DSPCTRL_VLE_MASK (3 << SSD1289_DSPCTRL_VLE_SHIFT) +# define SSD1289_DSPCTRL_VLE(n) ((n) << SSD1289_DSPCTRL_VLE_SHIFT) +#define SSD1289_DSPCTRL_PT_SHIFT (11) /* Normalize the source outputs */ +#define SSD1289_DSPCTRL_PT_MASK (3 << SSD1289_DSPCTRL_PT_SHIFT) +# define SSD1289_DSPCTRL_PT(n) ((n) << SSD1289_DSPCTRL_PT_SHIFT) + +/* Frame cycle control */ + +#define SSD1289_FCYCCTRL_RTN_SHIFT (0) /* Number of clocks in each line */ +#define SSD1289_FCYCCTRL_RTN_MASK (3 << SSD1289_FCYCCTRL_RTN_SHIFT) +# define SSD1289_FCYCCTRL_RTN(n) (((n)-16) << SSD1289_FCYCCTRL_RTN_SHIFT) +#define SSD1289_FCYCCTRL_SRTN (1 << 4) /* When SRTN =1, RTN3-0 value will be count */ +#define SSD1289_FCYCCTRL_SDIV (1 << 5) /* When SDIV = 1, DIV1-0 value will be count */ +#define SSD1289_FCYCCTRL_DIV_SHIFT (6) /* Set the division ratio of clocks */ +#define SSD1289_FCYCCTRL_DIV_MASK (3 << SSD1289_FCYCCTRL_DIV_SHIFT) +# define SSD1289_FCYCCTRL_DIV1 (0 << SSD1289_FCYCCTRL_DIV_SHIFT) +# define SSD1289_FCYCCTRL_DIV2 (1 << SSD1289_FCYCCTRL_DIV_SHIFT) +# define SSD1289_FCYCCTRL_DIV4 (2 << SSD1289_FCYCCTRL_DIV_SHIFT) +# define SSD1289_FCYCCTRL_DIV8 (3 << SSD1289_FCYCCTRL_DIV_SHIFT) +#define SSD1289_FCYCCTRL_EQ_SHIFT (8) /* Sets the equalizing period */ +#define SSD1289_FCYCCTRL_EQ_MASK (3 << SSD1289_FCYCCTRL_EQ_SHIFT) +# define SSD1289_FCYCCTRL_EQ(n) (((n)-1) << SSD1289_FCYCCTRL_EQ_SHIFT) /* n = 2-8 clocks */ +#define SSD1289_FCYCCTRL_SDT_SHIFT (12) /* Set delay amount from the gate output */ +#define SSD1289_FCYCCTRL_SDT_MASK (3 << SSD1289_FCYCCTRL_SDT_SHIFT) +# define SSD1289_FCYCCTRL_SDT(n) ((n) << SSD1289_FCYCCTRL_SDT_SHIFT) /* n = 1-3 clocks */ +#define SSD1289_FCYCCTRL_NO_SHIFT (14) /* Sets amount of non-overlap of the gate output */ +#define SSD1289_FCYCCTRL_NO_MASK (3 << SSD1289_FCYCCTRL_NO_SHIFT) +# define SSD1289_FCYCCTRL_NO(n) ((n) << SSD1289_FCYCCTRL_NO_SHIFT) /* n = 1-3 clocks */ + +/* Power control 2 */ + +#define SSD1289_PWRCTRL2_VRC_SHIFT (0) /* Adjust VCIX2 output voltage */ +#define SSD1289_PWRCTRL2_VRC_MASK (7 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p1V (0 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p2V (1 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p3V (2 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p4V (3 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p5V (4 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p6V (5 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p7V (6 << SSD1289_PWRCTRL2_VRC_SHIFT) +# define SSD1289_PWRCTRL2_VRC_5p8V (7 << SSD1289_PWRCTRL2_VRC_SHIFT) + +/* Power control 3 */ + +#define SSD1289_PWRCTRL3_VRH_SHIFT (0) /* Set amplitude magnification of VLCD63 */ +#define SSD1289_PWRCTRL3_VRH_MASK (15 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x1p540 (0 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x1p620 (1 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x1p700 (2 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x1p780 (3 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x1p850 (4 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x1p930 (5 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p020 (6 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p090 (7 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p165 (8 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p245 (9 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p335 (10 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p400 (11 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p500 (12 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p570 (13 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p645 (14 << SSD1289_PWRCTRL3_VRH_SHIFT) +# define SSD1289_PWRCTRL3_VRH_x2p725 (15 << SSD1289_PWRCTRL3_VRH_SHIFT) + +/* Power control 4 */ + +#define SSD1289_PWRCTRL4_VDV_SHIFT (9) /* Set amplitude magnification of VLCD63 */ +#define SSD1289_PWRCTRL4_VDV_MASK (32 << SSD1289_PWRCTRL4_VDV_SHIFT) +# define SSD1289_PWRCTRL4_VDV(n) ((n) << SSD1289_PWRCTRL4_VDV_SHIFT) +#define SSD1289_PWRCTRL4_VCOMG (1 << 13) /* VcomL variable */ + +/* Gate scan start position */ + +#define SSD1289_GSTART_MASK 0x1ff + +/* Sleep mode */ + +#define SSD1289_SLEEP_ON (1 << 0) + +/* Entry mode */ + +#define SSD1289_ENTRY_LG_SHIFT (0) /* Write after comparing */ +#define SSD1289_ENTRY_LG_MASK (7 << SSD1289_ENTRY_LG_SHIFT) +#define SSD1289_ENTRY_AM (1 << 3) /* Address counter direction */ +#define SSD1289_ENTRY_ID_SHIFT (4) /* Address increment mode */ +#define SSD1289_ENTRY_ID_MASK (3 << SSD1289_ENTRY_ID_SHIFT) +# define SSD1289_ENTRY_ID_HDECVDEC (0 << SSD1289_ENTRY_ID_SHIFT) +# define SSD1289_ENTRY_ID_HINCVDEC (1 << SSD1289_ENTRY_ID_SHIFT) +# define SSD1289_ENTRY_ID_HDECVINC (2 << SSD1289_ENTRY_ID_SHIFT) +# define SSD1289_ENTRY_ID_HINCVINC (3 << SSD1289_ENTRY_ID_SHIFT) +#define SSD1289_ENTRY_TY_SHIFT (6) /* RAM data write method */ +#define SSD1289_ENTRY_TY_MASK (3 << SSD1289_ENTRY_TY_SHIFT) +# define SSD1289_ENTRY_TY_A (0 << SSD1289_ENTRY_TY_SHIFT) +# define SSD1289_ENTRY_TY_B (1 << SSD1289_ENTRY_TY_SHIFT) +# define SSD1289_ENTRY_TY_C (2 << SSD1289_ENTRY_TY_SHIFT) +#define SSD1289_ENTRY_DMODE_SHIFT (8) /* Data display mode */ +#define SSD1289_ENTRY_DMODE_MASK (3 << SSD1289_ENTRY_DMODE_SHIFT) +# define SSD1289_ENTRY_DMODE_RAM (0 << SSD1289_ENTRY_DMODE_SHIFT) +# define SSD1289_ENTRY_DMODE_GENERIC (1 << SSD1289_ENTRY_DMODE_SHIFT) +# define SSD1289_ENTRY_DMODE_RAMGEN (2 << SSD1289_ENTRY_DMODE_SHIFT) +# define SSD1289_ENTRY_DMODE_GENRAM (3 << SSD1289_ENTRY_DMODE_SHIFT) +#define SSD1289_ENTRY_WMODE (1 << 10) /* Select source of data in RAM */ +#define SSD1289_ENTRY_OEDEF (1 << 11) /* Define display window */ +#define SSD1289_ENTRY_TRANS (1 << 12) /* Transparent display */ +#define SSD1289_ENTRY_DFM_SHIFT (13) /* Color display mode */ +#define SSD1289_ENTRY_DFM_MASK (3 << SSD1289_ENTRY_DFM_SHIFT) +# define SSD1289_ENTRY_DFM_262K (2 << SSD1289_ENTRY_DFM_SHIFT) +# define SSD1289_ENTRY_DFM_65K (3 << SSD1289_ENTRY_DFM_SHIFT) +#define SSD1289_ENTRY_VSMODE (1 << 15) /* Frame frequency depends on VSYNC */ + +/* Generic Interface Control */ + +#define SSD1289_GIFCTRL_INVVS (1 << 0) /* Sets the signal polarity of DOTCLK pin */ +#define SSD1289_GIFCTRL_INVHS (1 << 1) /* Sets the signal polarity of DEN pin */ +#define SSD1289_GIFCTRL_NVDEN (1 << 2) /* Sets the signal polarity of HSYNC pin */ +#define SSD1289_GIFCTRL_INVDOT (1 << 3) /* Sets the signal polarity of VSYNC pin */ + +/* Horizontal Porch */ + +#define SSD1289_HPORCH_HBP_SHIFT (0) /* Set delay from falling edge of HSYNC signal to data */ +#define SSD1289_HPORCH_HBP_MASK (0xff << SSD1289_HPORCH_HBP_SHIFT) +#define SSD1289_HPORCH_XL_SHIFT (8) /* number of valid pixel per line */ +#define SSD1289_HPORCH_XL_MASK (0xff << SSD1289_HPORCH_XL_SHIFT) + +/* Vertical Porch */ + +#define SSD1289_VPORCH_VBP_SHIFT (0) /* Set delay from falling edge of VSYNC signal to line */ +#define SSD1289_VPORCH_VBP_MASK (0xff << SSD1289_VPORCH_VBP_SHIFT) +#define SSD1289_VPORCH_XFP_SHIFT (8) /* Delay from last line to falling edge of VSYNC of next frame */ +#define SSD1289_VPORCH_XFP_MASK (0xff << SSD1289_VPORCH_XFP_SHIFT) +#define SSD1289_VPORCH_ + +/* Power control 5 */ + +#define SSD1289_PWRCTRL5_VCM_SHIFT (0) /* Set the VcomH voltage */ +#define SSD1289_PWRCTRL5_VCM_MASK (0x3f << SSD1289_PWRCTRL5_VCM_SHIFT) +# define SSD1289_PWRCTRL5_VCM(n) ((n) << SSD1289_PWRCTRL5_VCM_SHIFT) +#define SSD1289_PWRCTRL5_NOTP (1 << 7) /* 1=VCM valid */ + +/* RAM write data mask 1 */ + +#define SSD1289_WRMASK1_WMG_SHIFT (2) +#define SSD1289_WRMASK1_WMG_MASK (0x3f << SSD1289_WRMASK1_WMG_SHIFT) +#define SSD1289_WRMASK1_WMR_SHIFT (10) +#define SSD1289_WRMASK1_WMR_MASK (0x3f << SSD1289_WRMASK1_WMR_SHIFT) + +#define SSD1289_WRMASK2_WMB_SHIFT (2) +#define SSD1289_WRMASK2_WMB_MASK (0x3f << SSD1289_WRMASK2_WMB_SHIFT) + +/* Frame Frequency */ + +#define SSD1289_FFREQ_OSC_SHIFT (12) /* Set the frame frequency */ +#define SSD1289_FFREQ_OSC_MASK (15 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF50 (0 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF55 (2 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF60 (5 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF65 (8 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF70 (10 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF75 (12 << SSD1289_FFREQ_OSC_SHIFT) +# define SSD1289_FFREQ_OSC_FF80 (14 << SSD1289_FFREQ_OSC_SHIFT) + +/* VCOM OTP */ + +#define SSD1289_VCOMOTP1_ACTIVATE 0x0006 +#define SSD1289_VCOMOTP1_FIRE 0x000a +#define SSD1289_VCOMOTP2_ACTIVATE 0x80c0 + +/* Optimize Access Speed 1, 2, 3 (omitted) */ + +/* Gamma control 1-10. Magic values. I won't try to represent the fields. */ + +/* Vertical scroll control 1 and 2 */ + +#define SSD1289_VSCROLL_MASK 0x1ff /* Scroll length */ + +/* Horizontal RAM address position */ + +#define SSD1289_HADDR_HSA_SHIFT (0) /* Window horizontal start address */ +#define SSD1289_HADDR_HSA_MASK (0xff << SSD1289_HADDR_HSA_SHIFT) +#define SSD1289_HADDR_HEA_SHIFT (8) /* Window horizontal end address */ +#define SSD1289_HADDR_HEA_MASK (0xff << SSD1289_HADDR_HEA_SHIFT) + +/* Vertical RAM address start/end position */ + +#define SSD1289_VSTART_MASK 0x1ff /* Window Vertical start address */ +#define SSD1289_VEND_MASK 0x1ff /* Window Vertical end address */ + +/* First window start/end */ + +#define SSD1289_W1START_MASK 0x1ff /* Start line for first screen */ +#define SSD1289_W1END_MASK 0x1ff /* End line for first screen */ + +/* Second window start/end */ + +#define SSD1289_W2START_MASK 0x1ff /* Start line for second screen */ +#define SSD1289_W2END_MASK 0x1ff /* End line for second screen */ + +/* Set GDDRAM X/Y address counter */ + +#define SSD1289_XADDR_MASK 0xff /* GDDRAM X address in the address counter */ +#define SSD1289_YADDR_MASK 0x1ff /* GDDRAM Y address in the address counter */ + +#endif /* CONFIG_LCD_SSD1289 */ +#endif /* __DRIVERS_LCD_SSD1289_H */ diff --git a/nuttx/include/nuttx/lcd/ssd1289.h b/nuttx/include/nuttx/lcd/ssd1289.h new file mode 100644 index 0000000000..95e1f1d07c --- /dev/null +++ b/nuttx/include/nuttx/lcd/ssd1289.h @@ -0,0 +1,138 @@ +/************************************************************************************** + * include/nuttx/lcd/ssd1289.h + * Definitions for the Solomon Systech SSD1289 LCD controller + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: SSD1289, Rev 1.3, Apr 2007, Solomon Systech Limited + * + * 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 __INCLUDE_NUTTX_LCD_SSD1289_H +#define __INCLUDE_NUTTX_LCD_SSD1289_H + +/************************************************************************************** + * Included Files + **************************************************************************************/ + +#include + +#ifdef CONFIG_LCD_SSD1289 + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ +/* Configuration **********************************************************************/ +/* CONFIG_SSD1289_WRONLY - The LCD interface support write-only operation. +*/ + +/************************************************************************************** + * Public Types + **************************************************************************************/ + +/* This structure defines the interface to the LCD provided by the platform. The + * nature of this interface is hidden from the SSD1289 driver. + */ + +struct ssd1289_lcd_s +{ + /* Interface to write to a SSD1289 register. + * + * - select Select the device (as necessary). The meaning of selecting (and + * and deselecting) is not defined. select() will be called before + * starting any sequence of operations. deselect() when that sequence + * of operations is complete. + * - deselect Deselect the device (as necessary) + * - index Set register index + * - read Read data from the LCD (auto-incrementing) + * - write Write data to the LCD (auto-incrementing) + * - backlight Set the backlight power level (0=OFF; CONFIG_LCD_MAXPOWER=MAX) + */ + + void (*select)(FAR struct ssd1289_lcd_s *dev); + void (*deselect)(FAR struct ssd1289_lcd_s *dev); + void (*index)(FAR struct ssd1289_lcd_s *dev, uint8_t index); +#ifndef CONFIG_SSD1289_WRONLY + uint16_t (*read)(FAR struct ssd1289_lcd_s *dev); +#endif + void (*write)(FAR struct ssd1289_lcd_s *dev, uint16_t value); + void (*backlight)(FAR struct ssd1289_lcd_s *dev, int power); + + /* platform-specific data may follow */ +}; + +/************************************************************************************** + * Public Data + **************************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************** + * Public Function Prototypes + **************************************************************************************/ + +/************************************************************************************** + * Name: ssd1289_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). + * + **************************************************************************************/ + +EXTERN FAR struct lcd_dev_s *ssd1289_lcdinitialize(FAR struct ssd1289_lcd_s *lcd); + +/************************************************************************************** + * Name: ssd1289_clear + * + * Description: + * This is a non-standard LCD interface. Because of the various rotations, clearing + * the display in the normal way by writing a sequences of runs that covers the + * entire display can be very slow. Here the display is cleared by simply setting + * all GRAM memory to the specified color. + * + **************************************************************************************/ + +EXTERN void ssd1289_clear(FAR struct lcd_dev_s *dev, uint16_t color); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_LCD_SSD1289 */ +#endif /* __INCLUDE_NUTTX_LCD_SSD1289_H */ \ No newline at end of file