summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-12-05 19:54:23 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-12-05 19:54:23 +0000
commit01f3ee254fad306d40da1dbaa47efe2909df7b35 (patch)
tree5ed949c9b5461b71f2e79aa318daa3af4da96063 /nuttx
parentcfa1ad10cc2205b7593733ce44467b9c01aa59ae (diff)
downloadpx4-nuttx-01f3ee254fad306d40da1dbaa47efe2909df7b35.tar.gz
px4-nuttx-01f3ee254fad306d40da1dbaa47efe2909df7b35.tar.bz2
px4-nuttx-01f3ee254fad306d40da1dbaa47efe2909df7b35.zip
Add backlight control
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3163 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h7
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/up_lcd.c119
-rwxr-xr-xnuttx/drivers/lcd/Make.defs9
-rwxr-xr-xnuttx/drivers/lcd/nokia6100.c119
-rw-r--r--nuttx/include/nuttx/fb.h109
-rwxr-xr-xnuttx/include/nuttx/lcd/nokia6100.h23
6 files changed, 299 insertions, 87 deletions
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
index d7244e17c..b1a461a24 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
@@ -165,12 +165,13 @@
* P1[23]/MCFB1/PWM1[4]/MISO0 37 MISO0
* P1[24]/MCFB2/PWM1[5]/MOSI0 38 MOSI0
* P3[25]/MAT0[0]/PWM1[2] 27 LCD_RST
- * P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL
+ * P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL (PWM1)
*/
-#define LPC1766STK_LCD_CS (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN25)
+#define LPC1766STK_LCD_CS (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN21)
#define LPC1766STK_LCD_RST (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN25)
-#define LPC1766STK_LCD_BL (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN26)
+#define LPC1766STK_LCD_BL GPIO_PWM1p3_3
+#define GPIO_PWM1p3 GPIO_PWM1p3_3
/* SD/MMC GPIO PIN SIGNAL NAME
* -------------------------------- ---- --------------
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c b/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
index 4f2a9123e..2fc3a4426 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
@@ -48,6 +48,7 @@
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/nokia6100.h>
+#include "lpc17_syscon.h"
#include "lpc17_internal.h"
#include "lpc17stk_internal.h"
@@ -57,6 +58,16 @@
* Pre-Processor Definitions
****************************************************************************/
+/* Check power setting */
+
+#if !defined(CONFIG_LCD_MAXPOWER) || CONFIG_LCD_MAXPOWER != 128
+# error "CONFIG_LCD_MAXPOWER must be 128"
+#endif
+
+/* Backlight OFF PWM setting */
+
+#define NOKIA_BACKLIGHT_OFF 0x40
+
/* Define the CONFIG_LCD_NOKIADBG to enable detailed debug output (stuff you
* would never want to see unless you are debugging this file).
*
@@ -85,6 +96,84 @@
****************************************************************************/
/****************************************************************************
+ * Name: nokia_blinitialize
+ *
+ * Description:
+ * Initialize PWM1 to manage the LCD backlight.
+ *
+ ****************************************************************************/
+
+void nokia_blinitialize(void)
+{
+ uint32_t regval;
+
+ /* Enable clocking of PWM1 */
+
+ regval = regreg32(LPC17_SYSCON_PCONP);
+ regval |= SYSCON_PCONP_PCPWM1;
+ putreg32(regval, LPC17_SYSCON_PCONP);
+
+ /* Disable and reset PWM1 */
+
+ regval = getreg32(LPC17_PWM1_TCR);
+ regval &= ~(PWM_TCR_PWMEN|PWM_TCR_CNTREN);
+ regval |= PWM_TCR_CNTRRST;
+ putreg32(regval, LPC17_PWM1_TCR);
+
+ /* Put PWM1 in timer mode */
+
+ regval = getreg32(LPC17_PWM1_CTCR);
+ regval &= ~PWM_CTCR_MODE_MASK;
+ regval |= PWM_CTCR_MODE_TIMER;
+ putreg32(regval, LPC17_PWM1_CTCR);
+
+ /* Reset on MR0 */
+
+ putreg32(PWM_MCR_MR0R, LPC17_PWM1_MCR);
+
+ /* Single edge controlled mod for PWM3 and enable output */
+
+ regval = getreg32(LPC17_PWM1_PCR);
+ regval &= ~PWM_PCR_SEL3;
+ regval |= PWM_PCR_ENA3;
+ putreg32(regval, LPC17_PWM1_PCR);
+
+ /* Clear prescaler */
+
+ putreg32(0, LPC17_PWM1_PR);
+
+ /* Set 8-bit resolution */
+
+ putreg32(0xff, LPC17_PWM1_MCR);
+
+ /* Enable PWM match 1 latch */
+
+ regval = getreg32(LPC17_PWM1_LER);
+ regval |= PWM_LER_M0EN;
+ putreg32(regval, LPC17_PWM1_LER);
+
+ /* Clear match register 3 */
+
+ putreg32(0, LPC17_PWM1_MR3);
+
+ /* Enable PWM1 */
+
+ regval |= PWM_LER_M3EN;
+ putreg32(regval, LPC17_PWM1_LER);
+
+ regval = getreg32(LPC17_PWM1_TCR);
+ regval &= ~(PWM_TCR_CNTRRST);
+ regval |= (PWM_TCR_PWMEN|PWM_TCR_CNTREN);
+ putreg32(regval, LPC17_PWM1_TCR);
+
+ nokia_backlight(0);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: up_nxdrvinit
*
* Description:
@@ -111,6 +200,10 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
lpc17_gpiowrite(LPC1766STK_LCD_RST, true);
up_msdelay(5);
+ /* Configure PWM1 to support the backlight */
+
+ nokia_blinitialize();
+
/* Get the SSP port (configure as a Freescale SPI port) */
spi = up_spiinitialize(0);
@@ -140,4 +233,30 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
return NULL;
}
+/****************************************************************************
+ * Name: nokia_backlight
+ *
+ * Description:
+ * The Nokia 6100 backlight is controlled by logic outside of the LCD
+ * assembly. This function must be provided by board specific logic to
+ * manage the backlight. This function will receive a power value (0:
+ * full off - CONFIG_LCD_MAXPOWER: full on) and should set the backlight
+ * accordingly.
+ *
+ * On the Olimex LPC1766STK, the backlight level is controlled by PWM1.
+ *
+ ****************************************************************************/
+
+int nokia_backlight(unsigned int power)
+{
+ uint32_t regval;
+
+ putreg32(NOKIA_BACKLIGHT_OFF + power, LPC17_PWM1_MR3);
+
+ regval = getreg32(LPC17_PWM1_LER);
+ regval |= PWM_LER_M3EN;
+ putreg32(regval, LPC17_PWM1_LER);
+ return OK;
+}
+
#endif /* CONFIG_NX_LCDDRIVER && CONFIG_LCD_NOKIA6100 && CONFIG_LPC17_SSP0 */
diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs
index f49d500a3..bf0ade180 100755
--- a/nuttx/drivers/lcd/Make.defs
+++ b/nuttx/drivers/lcd/Make.defs
@@ -36,12 +36,17 @@
LCD_ASRCS =
LCD_CSRCS =
+# Don't build anything if there is no NX support for LCD drivers
+
ifeq ($(CONFIG_NX_LCDDRIVER),y)
+
ifeq ($(CONFIG_LCD_P14201),y)
LCD_CSRCS = p14201.c
-else
+endif
+
ifeq ($(CONFIG_LCD_NOKIA6100),y)
LCD_CSRCS = nokia6100.c
-else
+endif
+
endif
diff --git a/nuttx/drivers/lcd/nokia6100.c b/nuttx/drivers/lcd/nokia6100.c
index 4d8b0d7f5..b570c0839 100755
--- a/nuttx/drivers/lcd/nokia6100.c
+++ b/nuttx/drivers/lcd/nokia6100.c
@@ -82,12 +82,14 @@
* CONFIG_NOKIA6100_BPP - Device supports 8, 12, and 16 bits per pixel.
* CONFIG_NOKIA6100_S1D15G10 - Selects the Epson S1D15G10 display controller
* CONFIG_NOKIA6100_PCF8833 - Selects the Phillips PCF8833 display controller
+ * CONFIG_NOKIA6100_BLINIT - Initial backlight setting
*
* Required LCD driver settings:
* CONFIG_LCD_NOKIA6100 - Enable Nokia 6100 support
* CONFIG_LCD_MAXCONTRAST - must be 63 with the Epson controller and 127 with
* the Phillips controller.
- * CONFIG_LCD_MAXPOWER must be 1
+ * CONFIG_LCD_MAXPOWER - Maximum value of backlight setting. The backlight control is
+ * managed outside of the 6100 driver so this value has no meaning to the driver.
*/
/* Mode 0,0 should be use. However, somtimes you need to tinker with these things. */
@@ -96,6 +98,12 @@
# define CONFIG_NOKIA6100_SPIMODE SPIDEV_MODE0
#endif
+/* Default frequency: 1Mhz */
+
+#ifndef CONFIG_NOKIA6100_FREQUENCY
+# define CONFIG_NOKIA6100_FREQUENCY 1000000
+#endif
+
/* CONFIG_NOKIA6100_NINTERFACES determines the number of physical interfaces
* that will be supported.
*/
@@ -159,16 +167,10 @@
#endif
-/* Check power setting */
+/* Check initial backlight setting */
-#if !defined(CONFIG_LCD_MAXPOWER)
-# define CONFIG_LCD_MAXPOWER 1
-#endif
-
-#if CONFIG_LCD_MAXPOWER != 1
-# warning "CONFIG_LCD_MAXPOWER exceeds supported maximum"
-# undef CONFIG_LCD_MAXPOWER
-# define CONFIG_LCD_MAXPOWER 1
+#ifndef CONFIG_NOKIA6100_BLINIT
+# define CONFIG_NOKIA6100_BLINIT (NOKIA_DEFAULT_CONTRAST/3)
#endif
/* Color is 12bpp RGB with leftmost column contained in bits 7:4 */
@@ -186,6 +188,10 @@
# define CONFIG_NOKIA6100_WORDWIDTH 9
#endif
+/* If bit 9 is set, the byte is data; clear for commands */
+
+#define NOKIA_LCD_DATA (1 << 9)
+
/* Define the following to enable register-level debug output */
#undef CONFIG_LCD_REGDEBUG
@@ -204,10 +210,12 @@
/* Controller independent definitions *************************************************/
#ifdef CONFIG_NOKIA6100_PCF8833
-# define LCD_NOP PCF8833_NOP
+# define LCD_NOP PCF8833_NOP
+# define LCD_RAMWR PCF8833_RAMWR
#endif
#ifdef CONFIG_NOKIA6100_S1D15G10
-# define LCD_NOP S1D15G10_NOP
+# define LCD_NOP S1D15G10_NOP
+# define S1D15G10_RAMWR
#endif
/* Color Properties *******************************************************************/
@@ -219,8 +227,19 @@
/* Color depth and format */
-#define NOKIA_BPP 16
-#define NOKIA_COLORFMT FB_FMT_RGB16_565
+#if CONFIG_NOKIA6100_BPP == 8
+# define NOKIA_BPP 8
+# define NOKIA_COLORFMT FB_FMT_RGB8_332
+# define NOKIA_STRIDE NOKIA_XRES
+#elif CONFIG_NOKIA6100_BPP == 12
+# define NOKIA_BPP 12
+# define NOKIA_COLORFMT FB_FMT_RGB12_444
+# define NOKIA_STRIDE ((3*NOKIA_XRES+1)/2)
+#elif CONFIG_NOKIA6100_BPP == 16
+# define NOKIA_BPP 16
+# define NOKIA_COLORFMT FB_FMT_RGB16_565
+# define NOKIA_STRIDE (2*NOKIA_XRES)
+#endif
/* Debug ******************************************************************************/
@@ -245,7 +264,7 @@ struct nokia_dev_s
/* Private LCD-specific information follows */
uint8_t contrast;
- uint16_t linebuf[NOKIA_XRES+2];
+ uint16_t linebuf[NOKIA_STRIDE+2];
};
/**************************************************************************************
@@ -264,6 +283,7 @@ static void nokia_deselect(FAR struct spi_dev_s *spi);
#endif
static void nokia_sndcmd(FAR struct spi_dev_s *spi, const uint8_t cmd);
static void nokia_sndarray(FAR struct spi_dev_s *spi, int len, const uint8_t *cmddata);
+static void nokia_clrram(FAR struct spi_dev_s *spi);
/* LCD Data Transfer Methods */
@@ -685,7 +705,7 @@ static void nokia_sndarray(FAR struct spi_dev_s *spi, int len, const uint8_t *cm
uint16_t word;
int i;
- DEBUGASSERT(len <= NOKIA_XRES+1);
+ DEBUGASSERT(len <= NOKIA_STRIDE+1);
/* Copy the command into the line buffer. Bit 8 == 0 denotes a command. */
@@ -697,7 +717,7 @@ static void nokia_sndarray(FAR struct spi_dev_s *spi, int len, const uint8_t *cm
{
/* Bit 8 == 1 denotes data */
- *linebuf++ = (uin16_t)*cmddata++ | (1 << 8);
+ *linebuf++ = (uin16_t)*cmddata++ | NOKIA_LCD_DATA;
}
/* Terminate with a NOP */
@@ -718,6 +738,46 @@ static void nokia_sndarray(FAR struct spi_dev_s *spi, int len, const uint8_t *cm
}
/**************************************************************************************
+ * Name: nokia_clrram
+ *
+ * Description:
+ * Send a 1-byte command followed by len-1 data bytes.
+ *
+ **************************************************************************************/
+
+static void nokia_clrram(FAR struct spi_dev_s *spi)
+{
+ uint16_t *linebuf = priv->linebuf;
+ int i;
+
+ /* Set all zero data in the line buffer */
+
+ for (i = 0; i < NOKIA_STRIDE, i++)
+ {
+ /* Bit 8 == 1 denotes data */
+
+ *linebuf++ = NOKIA_LCD_DATA;
+ }
+
+ /* Select the LCD and send the RAMWR command */
+
+ nokia_select(spi);
+ SPI_SEND(spi, LCD_RAMWR);
+
+ /* Send the line buffer, once for each row. */
+
+ for (i = ; i < NOKIA_YRES-1; i++)
+ {
+ (void)SPI_SNDBLOCK(spi, priv->linebuf, NOKIA_STRIDE);
+ }
+ SPI_SEND(spi, LCD_NOP);
+
+ /* De-select the LCD */
+
+ nokia_deselect(spi);
+}
+
+/**************************************************************************************
* Name: nokia_putrun
*
* Description:
@@ -830,13 +890,21 @@ static int nokia_getpower(struct lcd_dev_s *dev)
static int nokia_setpower(struct lcd_dev_s *dev, int power)
{
struct nokia_dev_s *priv = (struct nokia_dev_s *)dev;
+ int ret;
gvdbg("power: %d\n", power);
DEBUGASSERT(power <= CONFIG_LCD_MAXPOWER);
- /* Set new power level */
+ /* Set new power level. The backlight power is controlled outside of the LCD
+ * assembly and must be managmed by board-specific logic.
+ */
- return OK;
+ ret = nokia_backlight(power);
+ if (ret == OK)
+ {
+ priv->power = power;
+ }
+ return ret;
}
/**************************************************************************************
@@ -905,6 +973,7 @@ static int nokia_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
static int nokia_initialize(struct nokia_dev_s *priv)
{
struct struct spi_dev_s *spi = priv->spi;
+ int i;
/* Configure the display */
@@ -923,12 +992,7 @@ static int nokia_initialize(struct nokia_dev_s *priv)
#endif
nokia_sndarray(spi, sizeof(g_paset), g_paset); /* Page address set */
nokia_sndarray(spi, sizeof(g_paset), g_caset); /* Column address set */
-
- /* Delay a bit to allow the power regulator circuits to stabilize. The turn
- * on the display.
- */
-
- up_msdelay(200);
+ nokia_clrram(spi);
nokia_sndcmd(spi, S1D15G10_DISON); /* Display on */
}
#endif
@@ -937,6 +1001,7 @@ static int nokia_initialize(struct nokia_dev_s *priv)
static int nokia_initialize(struct nokia_dev_s *priv)
{
struct struct spi_dev_s *spi = priv->spi;
+ int i;
nokia_sndcmd(spi, PCF8833_SLEEPOUT); /* Exit sleep mode */
nokia_sndcmd(spi, PCF8833_BSTRON); /* Turn on voltage booster */
@@ -945,6 +1010,7 @@ static int nokia_initialize(struct nokia_dev_s *priv)
nokia_sndarray(spi, sizeof(g_colmod), g_colmod); /* Color interface pixel format */
nokia_sndarray(spi, sizeof(g_setcon), g_setcon); /* Set contrast */
nokia_sndcmd(spi, PCF8833_NOP); /* No operation */
+ nokia_clrram(spi);
nokia_sndcmd(spi, PCF8833_DISPON); /* Display on */
}
#endif /* CONFIG_NOKIA6100_PCF8833 */
@@ -991,6 +1057,9 @@ FAR struct lcd_dev_s *nokia_lcdinitialize(FAR struct spi_dev_s *spi, unsigned in
if (nokia_initialize(priv) == OK)
{
+ /* Turn on the backlight */
+
+ nokia_backlight(CONFIG_NOKIA6100_BLINIT);
return &priv->dev;
}
return NULL;
diff --git a/nuttx/include/nuttx/fb.h b/nuttx/include/nuttx/fb.h
index dce0e183f..ab39b4c10 100644
--- a/nuttx/include/nuttx/fb.h
+++ b/nuttx/include/nuttx/fb.h
@@ -67,95 +67,96 @@
#define FB_FMT_RGB1 3 /* BPP=1 */
#define FB_FMT_RGB4 4 /* BPP=4 */
-#define FB_FMT_RGB8 5 /* BPP=8 */
-#define FB_FMT_RGB16_555 6 /* BPP=16 R=5, G=5, B=5 (1 unused bit) */
-#define FB_FMT_RGB16_565 7 /* BPP=16 R=6, G=6, B=5 */
-#define FB_FMT_RGB24 8 /* BPP=24 */
-#define FB_FMT_RGB32 9 /* BPP=32 */
+#define FB_FMT_RGB8_332 5 /* BPP=8 */
+#define FB_FMT_RGB12_444 6 /* BPP=12 */
+#define FB_FMT_RGB16_555 7 /* BPP=16 R=5, G=5, B=5 (1 unused bit) */
+#define FB_FMT_RGB16_565 8 /* BPP=16 R=6, G=6, B=5 */
+#define FB_FMT_RGB24 9 /* BPP=24 */
+#define FB_FMT_RGB32 10 /* BPP=32 */
/* Run length encoded RGB */
-#define FB_FMT_RGBRLE4 10 /* BPP=4 */
-#define FB_FMT_RGBRLE8 11 /* BPP=8 */
+#define FB_FMT_RGBRLE4 11 /* BPP=4 */
+#define FB_FMT_RGBRLE8 12 /* BPP=8 */
/* Raw RGB */
-#define FB_FMT_RGBRAW 12 /* BPP=? */
+#define FB_FMT_RGBRAW 13 /* BPP=? */
/* Raw RGB with arbitrary sample packing within a pixel. Packing and precision
* of R, G and B components is determined by bit masks for each.
*/
-#define FB_FMT_RGBBTFLD16 13 /* BPP=16 */
-#define FB_FMT_RGBBTFLD24 14 /* BPP=24 */
-#define FB_FMT_RGBBTFLD32 15 /* BPP=32 */
-#define FB_FMT_RGBA16 16 /* BPP=16 Raw RGB with alpha */
-#define FB_FMT_RGBA32 17 /* BPP=32 Raw RGB with alpha */
+#define FB_FMT_RGBBTFLD16 14 /* BPP=16 */
+#define FB_FMT_RGBBTFLD24 15 /* BPP=24 */
+#define FB_FMT_RGBBTFLD32 16 /* BPP=32 */
+#define FB_FMT_RGBA16 17 /* BPP=16 Raw RGB with alpha */
+#define FB_FMT_RGBA32 18 /* BPP=32 Raw RGB with alpha */
/* Raw RGB with a transparency field. Layout is as for stanadard RGB at 16 and
* 32 bits per pixel but the msb in each pixel indicates whether the pixel is
* transparent or not.
*/
-#define FB_FMT_RGBT16 18 /* BPP=16 */
-#define FB_FMT_RGBT32 19 /* BPP=32 */
+#define FB_FMT_RGBT16 19 /* BPP=16 */
+#define FB_FMT_RGBT32 20 /* BPP=32 */
#define FB_ISRGB(f) ((f) >= FB_FMT_RGB1) && (f) <= FB_FMT_RGBT32)
/* Packed YUV Formats *******************************************************/
-#define FB_FMT_AYUV 20 /* BPP=32 Combined YUV and alpha */
-#define FB_FMT_CLJR 21 /* BPP=8 4 pixels packed into a uint32_t.
+#define FB_FMT_AYUV 21 /* BPP=32 Combined YUV and alpha */
+#define FB_FMT_CLJR 22 /* BPP=8 4 pixels packed into a uint32_t.
* YUV 4:1:1 with l< 8 bits per YUV sample */
-#define FB_FMT_CYUV 22 /* BPP=16 UYVY except that height is reversed */
-#define FB_FMT_IRAW 23 /* BPP=? Intel uncompressed YUV */
-#define FB_FMT_IUYV 24 /* BPP=16 Interlaced UYVY (line order
+#define FB_FMT_CYUV 23 /* BPP=16 UYVY except that height is reversed */
+#define FB_FMT_IRAW 24 /* BPP=? Intel uncompressed YUV */
+#define FB_FMT_IUYV 25 /* BPP=16 Interlaced UYVY (line order
* 0,2,4,.., 1,3,5...) */
-#define FB_FMT_IY41 25 /* BPP=12 Interlaced Y41P (line order
+#define FB_FMT_IY41 26 /* BPP=12 Interlaced Y41P (line order
* 0,2,4,.., 1,3,5...) */
-#define FB_FMT_IYU2 26 /* BPP=24 */
-#define FB_FMT_HDYC 27 /* BPP=16 UYVY except uses the BT709 color space */
-#define FB_FMT_UYVP 28 /* BPP=24? YCbCr 4:2:2, 10-bits per component in U0Y0V0Y1 order */
-#define FB_FMT_UYVY 29 /* BPP=16 YUV 4:2:2 */
+#define FB_FMT_IYU2 27 /* BPP=24 */
+#define FB_FMT_HDYC 28 /* BPP=16 UYVY except uses the BT709 color space */
+#define FB_FMT_UYVP 29 /* BPP=24? YCbCr 4:2:2, 10-bits per component in U0Y0V0Y1 order */
+#define FB_FMT_UYVY 30 /* BPP=16 YUV 4:2:2 */
#define FB_FMT_UYNV FB_FMT_UYVY /* BPP=16 */
#define FB_FMT_Y422 FB_FMT_UYVY /* BPP=16 */
-#define FB_FMT_V210 30 /* BPP=32 10-bit 4:2:2 YCrCb */
-#define FB_FMT_V422 31 /* BPP=16 Upside down version of UYVY */
-#define FB_FMT_V655 32 /* BPP=16? 16-bit YUV 4:2:2 */
-#define FB_FMT_VYUY 33 /* BPP=? ATI Packed YUV Data */
-#define FB_FMT_YUYV 34 /* BPP=16 YUV 4:2:2 */
+#define FB_FMT_V210 31 /* BPP=32 10-bit 4:2:2 YCrCb */
+#define FB_FMT_V422 32 /* BPP=16 Upside down version of UYVY */
+#define FB_FMT_V655 33 /* BPP=16? 16-bit YUV 4:2:2 */
+#define FB_FMT_VYUY 34 /* BPP=? ATI Packed YUV Data */
+#define FB_FMT_YUYV 35 /* BPP=16 YUV 4:2:2 */
#define FB_FMT_YUY2 FB_FMT_YUYV /* BPP=16 YUV 4:2:2 */
#define FB_FMT_YUNV FB_FMT_YUYV /* BPP=16 YUV 4:2:2 */
-#define FB_FMT_YVYU 35 /* BPP=16 YUV 4:2:2 */
-#define FB_FMT_Y41P 36 /* BPP=12 YUV 4:1:1 */
-#define FB_FMT_Y411 37 /* BPP=12 YUV 4:1:1 */
-#define FB_FMT_Y211 38 /* BPP=8 */
-#define FB_FMT_Y41T 39 /* BPP=12 Y41P LSB for transparency */
-#define FB_FMT_Y42T 40 /* BPP=16 UYVY LSB for transparency */
-#define FB_FMT_YUVP 41 /* BPP=24? YCbCr 4:2:2 Y0U0Y1V0 order */
+#define FB_FMT_YVYU 36 /* BPP=16 YUV 4:2:2 */
+#define FB_FMT_Y41P 37 /* BPP=12 YUV 4:1:1 */
+#define FB_FMT_Y411 38 /* BPP=12 YUV 4:1:1 */
+#define FB_FMT_Y211 39 /* BPP=8 */
+#define FB_FMT_Y41T 40 /* BPP=12 Y41P LSB for transparency */
+#define FB_FMT_Y42T 41 /* BPP=16 UYVY LSB for transparency */
+#define FB_FMT_YUVP 42 /* BPP=24? YCbCr 4:2:2 Y0U0Y1V0 order */
#define FB_ISYUVPACKED(f) ((f) >= FB_FMT_AYUV) && (f) <= FB_FMT_YUVP)
/* Packed Planar YUV Formats ************************************************/
-#define FB_FMT_YVU9 42 /* BPP=9 8-bit Y followed by 8-bit 4x4 VU */
-#define FB_FMT_YUV9 43 /* BPP=9? */
-#define FB_FMT_IF09 44 /* BPP=9.5 YVU9 + 4x4 plane of delta relative to tframe. */
-#define FB_FMT_YV16 45 /* BPP=16 8-bit Y followed by 8-bit 2x1 VU */
-#define FB_FMT_YV12 46 /* BPP=12 8-bit Y followed by 8-bit 2x2 VU */
-#define FB_FMT_I420 47 /* BPP=12 8-bit Y followed by 8-bit 2x2 UV */
+#define FB_FMT_YVU9 43 /* BPP=9 8-bit Y followed by 8-bit 4x4 VU */
+#define FB_FMT_YUV9 44 /* BPP=9? */
+#define FB_FMT_IF09 45 /* BPP=9.5 YVU9 + 4x4 plane of delta relative to tframe. */
+#define FB_FMT_YV16 46 /* BPP=16 8-bit Y followed by 8-bit 2x1 VU */
+#define FB_FMT_YV12 47 /* BPP=12 8-bit Y followed by 8-bit 2x2 VU */
+#define FB_FMT_I420 48 /* BPP=12 8-bit Y followed by 8-bit 2x2 UV */
#define FB_FMT_IYUV FB_FMT_I420 /* BPP=12 */
-#define FB_FMT_NV12 48 /* BPP=12 8-bit Y followed by an interleaved 2x2 UV */
-#define FB_FMT_NV21 49 /* BPP=12 NV12 with UV reversed */
-#define FB_FMT_IMC1 50 /* BPP=12 YV12 except UV planes ame stride as Y */
-#define FB_FMT_IMC2 51 /* BPP=12 IMC1 except UV lines interleaved at half stride boundaries */
-#define FB_FMT_IMC3 52 /* BPP=12 As IMC1 except that UV swapped */
-#define FB_FMT_IMC4 53 /* BPP=12 As IMC2 except that UV swapped */
-#define FB_FMT_CLPL 54 /* BPP=12 YV12 but including a level of indirection. */
-#define FB_FMT_Y41B 55 /* BPP=12? 4:1:1 planar. */
-#define FB_FMT_Y42B 56 /* BPP=16? YUV 4:2:2 planar. */
-#define FB_FMT_CXY1 57 /* BPP=12 */
-#define FB_FMT_CXY2 58 /* BPP=16 */
+#define FB_FMT_NV12 49 /* BPP=12 8-bit Y followed by an interleaved 2x2 UV */
+#define FB_FMT_NV21 50 /* BPP=12 NV12 with UV reversed */
+#define FB_FMT_IMC1 51 /* BPP=12 YV12 except UV planes ame stride as Y */
+#define FB_FMT_IMC2 52 /* BPP=12 IMC1 except UV lines interleaved at half stride boundaries */
+#define FB_FMT_IMC3 53 /* BPP=12 As IMC1 except that UV swapped */
+#define FB_FMT_IMC4 54 /* BPP=12 As IMC2 except that UV swapped */
+#define FB_FMT_CLPL 55 /* BPP=12 YV12 but including a level of indirection. */
+#define FB_FMT_Y41B 56 /* BPP=12? 4:1:1 planar. */
+#define FB_FMT_Y42B 57 /* BPP=16? YUV 4:2:2 planar. */
+#define FB_FMT_CXY1 58 /* BPP=12 */
+#define FB_FMT_CXY2 59 /* BPP=16 */
#define FB_ISYUVPLANAR(f) ((f) >= FB_FMT_AYUV) && (f) <= FB_FMT_YUVP)
#define FB_ISYUV(f) (FB_ISYUVPACKED(f) || FB_ISYUVPLANAR(f))
diff --git a/nuttx/include/nuttx/lcd/nokia6100.h b/nuttx/include/nuttx/lcd/nokia6100.h
index 34c2fd3be..fd024e62d 100755
--- a/nuttx/include/nuttx/lcd/nokia6100.h
+++ b/nuttx/include/nuttx/lcd/nokia6100.h
@@ -51,17 +51,21 @@
*
* CONFIG_NOKIA6100_SPIMODE - Controls the SPI mode
* CONFIG_NOKIA6100_FREQUENCY - Define to use a different bus frequency
- * CONFIG_NOKIA6100_NINTERFACES - Specifies the number of physical Nokia 6100 devices that
- * will be supported.
+ * CONFIG_NOKIA6100_NINTERFACES - Specifies the number of physical Nokia
+ * 6100 devices that will be supported.
* CONFIG_NOKIA6100_BPP - Device supports 8, 12, and 16 bits per pixel.
* CONFIG_NOKIA6100_S1D15G10 - Selects the Epson S1D15G10 display controller
* CONFIG_NOKIA6100_PCF8833 - Selects the Phillips PCF8833 display controller
+ * CONFIG_NOKIA6100_BLINIT - Initial backlight setting
*
* Required LCD driver settings:
* CONFIG_LCD_NOKIA6100 - Enable Nokia 6100 support
* CONFIG_LCD_MAXCONTRAST - must be 63 with the Epson controller and 127 with
* the Phillips controller.
- * CONFIG_LCD_MAXPOWER must be 1
+ * CONFIG_LCD_MAXPOWER - Maximum value of backlight setting. The backlight
+ * control is managed outside of the 6100 driver so this value has no
+ * meaning to the driver. Board-specific logic may place restrictions on
+ * this value.
*/
/****************************************************************************
@@ -108,6 +112,19 @@ struct lcd_dev_s; /* see nuttx/lcd.h */
struct spi_dev_s; /* see nuttx/spi.h */
EXTERN FAR struct lcd_dev_s *nokia_lcdinitialize(FAR struct spi_dev_s *spi, unsigned int devno);
+/**************************************************************************************
+ * Name: nokia_backlight
+ *
+ * Description:
+ * The Nokia 6100 backlight is controlled by logic outside of the LCD assembly. This
+ * function must be provided by board specific logic to manage the backlight. This
+ * function will receive a power value (0: full off - CONFIG_LCD_MAXPOWER: full on)
+ * and should set the backlight accordingly.
+ *
+ **************************************************************************************/
+
+EXTERN int nokia_setpower(unsigned int power);
+
#undef EXTERN
#ifdef __cplusplus
}