From 7dd1e8bf754ae9e5ccef8441877a53faa50d5bc2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 26 Mar 2013 20:06:53 +0000 Subject: LPC17 LCD driver is code complete and in need of testing git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5788 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lpc17xx/Kconfig | 123 +++++++++++++++-------- nuttx/arch/arm/src/lpc17xx/Make.defs | 4 + nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h | 9 +- nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c | 1 + nuttx/arch/arm/src/lpc17xx/lpc17_lcd.c | 146 ++++++++++++++++++++++++++-- nuttx/arch/arm/src/lpc17xx/lpc17_lcd.h | 6 +- 6 files changed, 237 insertions(+), 52 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lpc17xx/Kconfig b/nuttx/arch/arm/src/lpc17xx/Kconfig index 77093086a..57bd9a3e9 100644 --- a/nuttx/arch/arm/src/lpc17xx/Kconfig +++ b/nuttx/arch/arm/src/lpc17xx/Kconfig @@ -328,6 +328,7 @@ config LPC17_EEPROM endmenu menu "Serial driver options" + depends on LPC17_UART0 || LPC17_UART1 || LPC17_UART2 || LPC17_UART3 || LPC17_UART4 config SERIAL_TERMIOS bool "Serial driver TERMIOS supported" @@ -376,20 +377,18 @@ config UART3_FLOWCONTROL endmenu menu "ADC driver options" + depends on LPC17_ADC config ADC0_AVERAGE int "ADC0 average" - depends on LPC17_ADC default 200 config ADC0_MASK int "ADC0 mask" - depends on LPC17_ADC default 1 config ADC0_SPS int "ADC0 SPS" - depends on LPC17_ADC default 1000 config ADC_CHANLIST @@ -413,10 +412,10 @@ config ADC_CHANLIST config ADC_NCHANNELS int "ADC0 number of channels" - depends on LPC17_ADC + depends on ADC_CHANLIST default 0 ---help--- - If CONFIG_ADC_CHANLIST is enabled, then the platform specific code + If ADC_CHANLIST is enabled, then the platform specific code must do two things: (1) define ADC_NCHANNELS in the configuration file and (2) provide an array g_adc_chanlist[] with the channel numbers matching the ADC0_MASK within the board-specific library. @@ -424,10 +423,10 @@ config ADC_NCHANNELS endmenu menu "CAN driver options" + depends on LPC17_CAN1 || LPC17_CAN2 config CAN_EXTID bool "CAN extended IDs" - depends on LPC17_CAN1 || LPC17_CAN2 default n ---help--- Enables support for the 29-bit extended ID. Default Standard 11-bit IDs. @@ -462,35 +461,31 @@ config CAN2_DIVISOR config CAN_TSEG1 int "TSEG1 quanta" - depends on LPC17_CAN1 || LPC17_CAN2 default 6 ---help--- The number of CAN time quanta in segment 1. Default: 6 config CAN_TSEG2 int "TSEG2 quanta" - depends on LPC17_CAN1 || LPC17_CAN2 default 4 ---help--- The number of CAN time quanta in segment 2. Default: 7 config CAN_SAM bool "CAN sampling" - depends on LPC17_CAN1 || LPC17_CAN2 default n ---help--- The bus is sampled 3 times (recommended for low to medium speed buses to spikes on the bus-line). config CAN_LOOPBACK bool "CAN looopback mode" - depends on LPC17_CAN1 || LPC17_CAN2 default n ---help--- Enable CAN loopback mode config CAN_REGDEBUG bool "Register level debug" - depends on LPC17_CAN1 || LPC17_CAN2 + depends on DEBUG default n ---help--- Output detailed register-level CAN debug information. Requires also DEBUG and DEBUG_CAN. @@ -504,6 +499,7 @@ config GPIO_IRQ Enable support for GPIO interrupts menu "I2C driver options" + depends on LPC17_I2C0 || LPC17_I2C1 || LPC17_I2C2 config I2C0_FREQ int "I2C0 frequency" @@ -553,84 +549,77 @@ config SDIO_WIDTH_D1_ONLY endmenu menu "Ethernet driver options" + depends on LPC17_ETHERNET config PHY_AUTONEG bool "Autonegiation" - depends on LPC17_ETHERNET ---help--- Enable auto-negotion config PHY_SPEED100 bool "100Mbit/Sec" - depends on LPC17_ETHERNET && !PHY_AUTONEG + depends on !PHY_AUTONEG ---help--- Select 100Mbit vs. 10Mbit speed. config PHY_FDUPLEX bool "Full duplex" - depends on LPC17_ETHERNET && !PHY_AUTONEG + depends on !PHY_AUTONEG ---help--- Select full (vs. half) duplex config NET_EMACRAM_SIZE int "EMAC RAM Size" - depends on LPC17_ETHERNET default 16384 ---help--- Size of EMAC RAM. Default: 16384 bytes config NET_NTXDESC int "Number of Tx descriptors" - depends on LPC17_ETHERNET default 18 ---help--- Configured number of Tx descriptors. Default: 18 config NET_NRXDESC int "Number of Rx descriptors" - depends on LPC17_ETHERNET default 18 ---help--- Configured number of Rx descriptors. Default: 18 config NET_PRIORITY int "Ethernet interrupt priority" - depends on LPC17_ETHERNET default 0 ---help--- Ethernet interrupt priority. The is default is the higest priority (0). config NET_WOL bool "Wake-up on LAN" - depends on LPC17_ETHERNET default n ---help--- Enable Wake-up on Lan (not fully implemented). config NET_REGDEBUG bool "Ethernet register-level debug" - depends on LPC17_ETHERNET && DEBUG + depends on DEBUG default n ---help--- Enable low level register debug. Also needs DEBUG. config NET_DUMPPACKET bool "Enable packet dumping" - depends on LPC17_ETHERNET && DEBUG + depends on DEBUG default n ---help--- Dump all received and transmitted packets. Also needs DEBUG. config NET_HASH bool "Hashing" - depends on LPC17_ETHERNET default n ---help--- Enable receipt of near-perfect match frames. config NET_MULTICAST bool "Multicast" - depends on LPC17_ETHERNET default y if NET_IGMP default n if !NET_IGMP ---help--- @@ -639,18 +628,83 @@ config NET_MULTICAST endmenu +menu "LCD device driver options" + depends on LPC17_LCD + +config LPC17_LCD_VRAMBASE + hex "Video RAM base address" + default 0xa0010000 + ---help--- + Base address of the video RAM frame buffer. The default is + (LPC17_EXTDRAM_CS0 + 0x00010000) + +config LPC17_LCD_REFRESH_FREQ + int "LCD refesh rate (Hz)" + default 50 + ---help--- + LCD refesh rate (Hz) + +config LPC17_LCD_BPP + int "Bits per pixel" + default 16 + ---help--- + Bits per pixel + +config LPC17_LCD_BACKCOLOR + hex "Initial background color" + default 0x0 + ---help--- + Initial background color + +config LPC17_LCD_HWIDTH + int "Display width (pixels)" + default 480 + ---help--- + Horizontal width the display in pixels + +config LPC17_LCD_HPULSE + int "Horizontal pulse" + default 2 + +config LPC17_LCD_HFRONTPORCH + int "Horizontal front porch" + default 5 + +config LPC17_LCD_HBACKPORCH + int "Horizontal back porch" + default 40 + +config LPC17_LCD_VHEIGHT + int "Display height (rows)" + default 272 + ---help--- + Vertical height of the display in rows + +config LPC17_LCD_VPULSE + int "Vertical pulse" + default 2 + +config LPC17_LCD_VFRONTPORCH + int "Vertical front porch" + default 8 + +config LPC17_LCD_VBACKPORCH + int "Vertical back porch" + default 8 + +endmenu + menu "USB device driver options" + depends on LPC17_USBDEV config LPC17_USBDEV_EP0_MAXSIZE int "EP0 Max packet size" - depends on LPC17_USBDEV default 64 ---help--- Endpoint 0 maximum packet size. Default: 64 config LPC17_USBDEV_FRAME_INTERRUPT bool "USB frame interrupt" - depends on LPC17_USBDEV default n ---help--- Handle USB Start-Of-Frame events. Enable reading SOF from interrupt @@ -659,42 +713,37 @@ config LPC17_USBDEV_FRAME_INTERRUPT config LPC17_USBDEV_EPFAST_INTERRUPT bool "EP fast interrupt handling" - depends on LPC17_USBDEV default n ---help--- Enable high priority interrupts. I have no idea why you might want to do that config LPC17_USBDEV_NDMADESCRIPTORS int "Number of DMA descriptors" - depends on LPC17_USBDEV default 8 ---help--- Number of DMA descriptors to allocate in SRAM. Default: 8 config LPC17_USBDEV_DMA bool "Enable USB device DMA" - depends on LPC17_USBDEV default n ---help--- Enable lpc17xx-specific DMA support config LPC17_USBDEV_NOVBUS bool "Disable VBUS support" - depends on LPC17_USBDEV default n ---help--- Define if the hardware implementation does not support the VBUS signal config LPC17_USBDEV_NOLED bool "Disable USB device LCD support" - depends on LPC17_USBDEV default n ---help--- Define if the hardware implementation does not support the LED output config LPC17_USBDEV_REGDEBUG bool "Register level debug" - depends on LPC17_USBDEV && DEBUG + depends on DEBUG default n ---help--- Output detailed register-level USB device debug information. Requires also DEBUG. @@ -702,45 +751,40 @@ config LPC17_USBDEV_REGDEBUG endmenu menu "USB host driver options" + depends on LPC17_USBHOST config USBHOST_OHCIRAM_SIZE int "OHCI RAM Size" - depends on LPC17_USBHOST default 16384 ---help--- Total size of OHCI RAM (in AHB SRAM Bank 1). Default: 16384 config USBHOST_NEDS int "Number of Endpoint Descriptors" - depends on LPC17_USBHOST default 2 ---help--- Number of endpoint descriptors. Default: 2 config USBHOST_NTDS int "Number of transfer descriptors" - depends on LPC17_USBHOST default 3 ---help--- Number of transfer descriptors. Default: 3 config USBHOST_TDBUFFERS int "Number of descriptor buffers" - depends on LPC17_USBHOST default 2 ---help--- Number of transfer descriptor buffers. Default: 2 config USBHOST_TDBUFSIZE int "Descriptor buffer size" - depends on LPC17_USBHOST default 128 ---help--- Size of one transfer descriptor buffer. Default 128 config USBHOST_IOBUFSIZE int "I/O buffer size" - depends on LPC17_USBHOST default 512 ---help--- Size of one end-user I/O buffer. This can be zero if the application @@ -748,28 +792,25 @@ config USBHOST_IOBUFSIZE config USBHOST_BULK_DISABLE bool "Disable bulk EPs" - depends on LPC17_USBHOST default n ---help--- Disable support for bulk endpoints. config USBHOST_INT_DISABLE bool "Disable interupt EPs" - depends on LPC17_USBHOST default n ---help--- Disable support for interrupt endpoints. config USBHOST_ISOC_DISABLE bool "Disable isochronous EPs" - depends on LPC17_USBHOST default n ---help--- Disable support for isochronous endpoints. config LPC17_USBHOST_REGDEBUG bool "Register level debug" - depends on LPC17_USBHOST && DEBUG + depends on DEBUG default n ---help--- Output detailed register-level USB host debug information. Requires also DEBUG. diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs index b1b455cf5..4766e94f9 100644 --- a/nuttx/arch/arm/src/lpc17xx/Make.defs +++ b/nuttx/arch/arm/src/lpc17xx/Make.defs @@ -122,6 +122,10 @@ ifeq ($(CONFIG_DEBUG_GPIO),y) CHIP_CSRCS += lpc17_gpiodbg.c endif +ifeq ($(CONFIG_LPC17_LCD),y) +CHIP_CSRCS += lpc17_lcd.c +endif + ifeq ($(CONFIG_USBDEV),y) CHIP_CSRCS += lpc17_usbdev.c endif diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h index 0cea0ab1b..8b0e65134 100644 --- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h +++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h @@ -178,6 +178,14 @@ #define LCD_CTRL_LCDEN (1 << 0) /* Bit 0: LCD enable control bit */ #define LCD_CTRL_LCDBPP_SHIFT (1) /* Bits 1-3: LCD bits per pixel */ #define LCD_CTRL_LCDBPP_MASK (7 << LCD_CTRL_LCDBPP_SHIFT) +# define LCD_CTRL_LCDBPP_1 (0 << LCD_CTRL_LCDBPP_SHIFT) /* 1 bpp */ +# define LCD_CTRL_LCDBPP_2 (1 << LCD_CTRL_LCDBPP_SHIFT) /* 2 bpp */ +# define LCD_CTRL_LCDBPP_4 (2 << LCD_CTRL_LCDBPP_SHIFT) /* 4 bpp */ +# define LCD_CTRL_LCDBPP_8 (3 << LCD_CTRL_LCDBPP_SHIFT) /* 8 bpp */ +# define LCD_CTRL_LCDBPP_16 (4 << LCD_CTRL_LCDBPP_SHIFT) /* 16 bpp */ +# define LCD_CTRL_LCDBPP_24 (5 << LCD_CTRL_LCDBPP_SHIFT) /* 24 bpp (TFT panel only) */ +# define LCD_CTRL_LCDBPP_565 (6 << LCD_CTRL_LCDBPP_SHIFT) /* 16 bpp, 5:6:5 mode */ +# define LCD_CTRL_LCDBPP_444 (7 << LCD_CTRL_LCDBPP_SHIFT) /* 12 bpp, 4:4:4 mode */ #define LCD_CTRL_LCDBW (1 << 4) /* Bit 4: STN LCD monochrome/color selection */ #define LCD_CTRL_LCDTFT (1 << 5) /* Bit 5: LCD TFT type selection */ #define LCD_CTRL_LCDMONO8 (1 << 6) /* Bit 6: Monochrome LCD interface bit */ @@ -250,7 +258,6 @@ /* LCD CRSR_CTRL - Cursor Control Register */ #define LCD_CRSR_CTRL_CRSON (1 << 0) /* Bit 0: Cursor enable */ -#define LCD_CRSR_CTRL_CRSON_MASK (1 << LCD_CRSR_CTRL_CRSON_SHIFT) /* Bits 1-3: Reserved */ #define LCD_CRSR_CTRL_CRSRNUM_SHIFT (4) /* Bits 4-5: Cursor image number */ #define LCD_CRSR_CTRL_CRSRNUM_MASK (3 << LCD_CRSR_CTRL_CRSRNUM1_0_SHIFT) diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c index 387875120..97a5c19d6 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c @@ -856,6 +856,7 @@ void lpc17_gpiowrite(lpc17_pinset_t pinset, bool value) { offset = LPC17_FIO_CLR_OFFSET; } + putreg32((1 << pin), fiobase + offset); } } diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.c b/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.c index 270250d83..0ba8a5af0 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.c @@ -45,16 +45,32 @@ #include #include -#include "lpc17_internal.h" +#include + +#include "up_arch.h" +#include "chip/lpc17_syscon.h" +#include "lpc17_gpio.h" +#include "lpc17_lcd.h" /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ +#define LPC17_LCD_CLK_PER_LINE (CONFIG_LPC17_LCD_HWIDTH + CONFIG_LPC17_LCD_HPULSE + CONFIG_LPC17_LCD_HFRONTPORCH + CONFIG_LPC17_LCD_HBACKPORCH) +#define LPC17_LCD_LINES_PER_FRAME (CONFIG_LPC17_LCD_VHEIGHT + CONFIG_LPC17_LCD_VPULSE + CONFIG_LPC17_LCD_VFRONTPORCH + CONFIG_LPC17_LCD_VBACKPORCH) +#define LPC17_LCD_PIXEL_CLOCK (LPC17_LCD_CLK_PER_LINE * LPC17_LCD_LINES_PER_FRAME * CONFIG_LPC17_LCD_REFRESH_FREQ) + /* Framebuffer characteristics in bytes */ -#define FB_WIDTH ((CONFIG_LPC17_LCD_HWIDTH * CONFIG_LPC17_LCD_BPP + 7) / 8) -#define FB_SIZE (FB_WIDTH * CONFIG_LPC17_LCD_VHEIGHT) +#if CONFIG_LPC17_LCD_BPP == 16 +# define FB_STRIDE ((CONFIG_LPC17_LCD_HWIDTH * sizeof(uint16_t) + 7) / 8) +#elif CONFIG_LPC17_LCD_BPP == 24 +# define FB_STRIDE ((CONFIG_LPC17_LCD_HWIDTH * sizeof(uint32_t) + 7) / 8) +#else +# error "Unsupported BPP" +#endif + +#define FB_SIZE (FB_STRIDE * CONFIG_LPC17_LCD_VHEIGHT) /* Delays */ @@ -120,7 +136,7 @@ static const struct fb_planeinfo_s g_planeinfo = { .fbmem = (FAR void *)CONFIG_LPC17_LCD_VRAMBASE, .fblen = FB_SIZE, - .stride = FB_WIDTH, + .stride = FB_STRIDE, .bpp = CONFIG_LPC17_LCD_BPP, }; @@ -425,6 +441,7 @@ static int lpc17_setcursor(FAR struct fb_vtable_s *vtable, int up_fbinitialize(void) { + uint32_t regval; int i; /* Disable LCD controller */ @@ -478,7 +495,122 @@ int up_fbinitialize(void) lpc17_configgpio(GPIO_LCD_ENABM); lpc17_configgpio(GPIO_LCD_PWR); -#warning "Missing logic" + /* Turn on LCD clock */ + + regval = getreg32(LPC17_SYSCON_PCONP); + regval |= SYSCON_PCONP_PCLCD; + putreg32(regval, LPC17_SYSCON_PCONP); + + /* Disable the cursor */ + + regval = getreg32(LPC17_LCD_CRSR_CRTL); + regval &= ~LCD_CRSR_CTRL_CRSON; + putreg32(regval, LPC17_LCD_CRSR_CRTL); + + /* Disable GLCD controller */ + + putreg32(0, LPC17_LCD_CTRL); + + /* Set the bits per pixel */ + + regval = getreg32(LPC17_LCD_CTRL); + regval &= ~LCD_CTRL_LCDBPP_MASK; + +#if CONFIG_LPC17_LCD_BPP == 16 + regval |= LCD_CTRL_LCDBPP_565; /* 16-bit 5:6:5 */ +#else /* if CONFIG_LPC17_LCD_BPP == 24 */ + regval |= LCD_CTRL_LCDBPP_24; /* 24-bit TFT panel only */ + regval |= LCD_CTRL_LCDTFT; +#endif + putreg32(regval, LPC17_LCD_CTRL); + + /* Single panel */ + + regval &= ~LCD_CTRL_LCDDUAL; + putreg32(regval, LPC17_LCD_CTRL); + + /* Normal RGB output */ + + regval &= ~LCD_CTRL_BGR; + putreg32(regval, LPC17_LCD_CTRL); + + /* Little endian byte order */ + + regval &= ~LCD_CTRL_BEBO; + putreg32(regval, LPC17_LCD_CTRL); + + /* Little endian pixel order */ + + regval &= ~LCD_CTRL_BEPO; + putreg32(regval, LPC17_LCD_CTRL); + + /* Disable power */ + + regval &= ~LCD_CTRL_LCDPWR; + putreg32(regval, LPC17_LCD_CTRL); + + /* Initialize pixel clock (assuming clock source is CCLK) */ + + putreg32(LPC17_CCLK / LPC17_LCD_PIXEL_CLOCK, LPC17_SYSCON_LCDCFG); + + /* Bypass internal pixel clock divider */ + + regval = getreg32(LPC17_LCD_POL); + regval |= LCD_POL_BCD; + putreg32(regval, LPC17_LCD_POL); + + /* Select the CCLK for the LCD block clock source */ + + regval &= ~LCD_POL_CLKSEL; + putreg32(regval, LPC17_LCD_POL); + + /* LCDFP pin is active LOW and inactive HIGH */ + + regval |= LCD_POL_IVS; + putreg32(regval, LPC17_LCD_POL); + + /* LCDLP pin is active LOW and inactive HIGH */ + + regval |= LCD_POL_IHS; + putreg32(regval, LPC17_LCD_POL); + + /* Data is driven out into the LCD on the falling edge */ + + regval &= ~LCD_POL_IPC; + putreg32(regval, LPC17_LCD_POL); + + /* Active high */ + + regval &= ~LCD_POL_IOE; + putreg32(regval, LPC17_LCD_POL); + + regval &= ~LCD_POL_CPL_MASK; + regval |= (CONFIG_LPC17_LCD_HWIDTH-1) << LCD_POL_CPL_SHIFT; + putreg32(regval, LPC17_LCD_POL); + + /* Initialize horizontal timing */ + + putreg32(0, LPC17_LCD_TIMH); + + regval = (((CONFIG_LPC17_LCD_HWIDTH/16) - 1) << LCD_TIMH_PPL_SHIFT | + (CONFIG_LPC17_LCD_HPULSE - 1) << LCD_TIMH_HSW_SHIFT | + (CONFIG_LPC17_LCD_HFRONTPORCH - 1) << LCD_TIMH_HFP_SHIFT | + (CONFIG_LPC17_LCD_HBACKPORCH - 1) << LCD_TIMH_HBP_SHIFT); + putreg32(regval, LPC17_LCD_TIMH); + + /* Initialize vertical timing */ + + putreg32(0, LPC17_LCD_TIMV); + + regval = ((CONFIG_LPC17_LCD_VHEIGHT - 1) << LCD_TIMV_LPP_SHIFT | + (CONFIG_LPC17_LCD_VPULSE - 1) << LCD_TIMV_VSW_SHIFT | + (CONFIG_LPC17_LCD_VFRONTPORCH) << LCD_TIMV_VFP_SHIFT | + (CONFIG_LPC17_LCD_VBACKPORCH) << LCD_TIMV_VBP_SHIFT); + + /* Frame base address doubleword aligned */ + + putreg32(CONFIG_LPC17_LCD_VRAMBASE & ~7, LPC17_LCD_UPBASE); + putreg32(CONFIG_LPC17_LCD_VRAMBASE & ~7, LPC17_LCD_LPBASE); /* Clear the display */ @@ -487,7 +619,7 @@ int up_fbinitialize(void) /* Enable LCD */ - regval = getreg32(LPC17_LCD_CTRL); + regval = getreg32(LPC17_LCD_CTRL); regval |= LCD_CTRL_LCDEN; putreg32(regval, LPC17_LCD_CTRL); @@ -550,7 +682,7 @@ void fb_uninitialize(void) * ************************************************************************************/ -void lpc17_lcdclear(nxgl_pixel_t color) +void lpc17_lcdclear(nxgl_mxpixel_t color) { #if CONFIG_LPC17_LCD_BPP == 16 uint16_t *dest; diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.h b/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.h index e17a8cc53..d16673eeb 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.h +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_lcd.h @@ -59,13 +59,13 @@ /* LCD refresh rate */ #ifndef CONFIG_LPC17_LCD_REFRESH_FREQ -# define CONFIG_LPC17_LCD_REFRESH_FREQ (50) /* Hz */ +# define CONFIG_LPC17_LCD_REFRESH_FREQ (50) /* Hz */ #endif /* Bits per pixel */ #ifndef CONFIG_LPC17_LCD_BPP -# define CONFIG_LPC17_LCD_BPP 16 /* Bytes per pixel */ +# define CONFIG_LPC17_LCD_BPP 16 /* Bits per pixel */ #endif /* Color format */ @@ -107,7 +107,7 @@ # define CONFIG_LPC17_LCD_VHEIGHT 272 /* Height in rows */ #endif -#define CONFIG_LPC17_LCD_VPULSE +#ifndef CONFIG_LPC17_LCD_VPULSE # define CONFIG_LPC17_LCD_VPULSE 2 #endif -- cgit v1.2.3