From b262b5a5c69de0d0c304d3f1e1cd72c17ced05b8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 4 Apr 2015 11:49:15 -0600 Subject: More renaming: up_lcdinitialize->board_lcd_initialize, up_lcdgetdev->board_lcd_getdev, up_lcduninitialize->board_lcd_uninitialize --- nuttx/arch/sim/src/Makefile | 2 +- nuttx/arch/sim/src/board_lcd.c | 428 +++++++++++++++++++++ nuttx/arch/sim/src/up_lcd.c | 428 --------------------- nuttx/configs/compal_e99/src/ssd1783.c | 27 +- nuttx/configs/hymini-stm32v/src/stm32_r61505u.c | 15 +- nuttx/configs/hymini-stm32v/src/stm32_ssd1289.c | 13 +- nuttx/configs/kwikstik-k40/src/k40_lcd.c | 13 +- nuttx/configs/maple/src/stm32_lcd.c | 9 +- .../mikroe-stm32f4/src/mikroe-stm32f4-internal.h | 13 - nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt2.c | 13 +- .../configs/mikroe-stm32f4/src/stm32_mio283qt9a.c | 13 +- nuttx/configs/mikroe-stm32f4/src/stm32_nsh.c | 2 +- nuttx/configs/pic32mx7mmb/src/pic32_mio283qt2.c | 13 +- nuttx/configs/sam3u-ek/src/sam_lcd.c | 13 +- nuttx/configs/sam4e-ek/src/sam_ili9325.c | 13 +- nuttx/configs/sam4e-ek/src/sam_ili9341.c | 13 +- nuttx/configs/samv71-xult/README.txt | 12 +- nuttx/configs/samv71-xult/src/sam_ili9488.c | 13 +- nuttx/configs/shenzhou/src/stm32_ili93xx.c | 15 +- nuttx/configs/shenzhou/src/stm32_ssd1289.c | 15 +- nuttx/configs/stm3210e-eval/src/stm32_lcd.c | 13 +- nuttx/configs/stm3220g-eval/src/stm32_lcd.c | 13 +- nuttx/configs/stm3240g-eval/src/stm32_lcd.c | 13 +- nuttx/configs/stm32f429i-disco/src/stm32_lcd.c | 13 +- nuttx/configs/stm32f4discovery/src/stm32_ssd1289.c | 13 +- .../configs/viewtool-stm32f107/src/stm32_ssd1289.c | 13 +- nuttx/configs/zkit-arm-1769/src/lpc17_lcd.c | 15 +- nuttx/graphics/nxmu/nx_start.c | 8 +- nuttx/include/nuttx/board.h | 26 ++ nuttx/include/nuttx/lcd/lcd.h | 25 +- 30 files changed, 632 insertions(+), 603 deletions(-) create mode 100644 nuttx/arch/sim/src/board_lcd.c delete mode 100644 nuttx/arch/sim/src/up_lcd.c (limited to 'nuttx') diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index 0fd5bfea9..2a0a7b5cc 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -69,7 +69,7 @@ ifeq ($(CONFIG_DEV_CONSOLE),y) endif ifeq ($(CONFIG_NX_LCDDRIVER),y) - CSRCS += up_lcd.c + CSRCS += board_lcd.c else CSRCS += up_framebuffer.c ifeq ($(CONFIG_SIM_X11FB),y) diff --git a/nuttx/arch/sim/src/board_lcd.c b/nuttx/arch/sim/src/board_lcd.c new file mode 100644 index 000000000..ecac19aa2 --- /dev/null +++ b/nuttx/arch/sim/src/board_lcd.c @@ -0,0 +1,428 @@ +/**************************************************************************** + * arch/sim/src/board_lcd.c + * + * Copyright (C) 2011, 2015 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 + * 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ +/* Check contrast selection */ + +#if !defined(CONFIG_LCD_MAXCONTRAST) +# define CONFIG_LCD_MAXCONTRAST 100 +#endif + +/* Check power setting */ + +#if !defined(CONFIG_LCD_MAXPOWER) +# define CONFIG_LCD_MAXPOWER 100 +#endif + +/* Simulated LCD geometry and color format */ + +#ifndef CONFIG_SIM_FBWIDTH +# define CONFIG_SIM_FBWIDTH 320 /* Framebuffer width in pixels */ +#endif + +#ifndef CONFIG_SIM_FBHEIGHT +# define CONFIG_SIM_FBHEIGHT 240 /* Framebuffer height in pixels */ +#endif + +#ifndef CONFIG_SIM_FBBPP +# define CONFIG_SIM_FBBPP 16 /* Framebuffer bytes per pixel (RGB) */ +#endif + +#define FB_STRIDE ((CONFIG_SIM_FBBPP * CONFIG_SIM_FBWIDTH + 7) >> 3) + +#undef FB_FMT +#if CONFIG_SIM_FBBPP == 1 +# define FB_FMT FB_FMT_RGB1 +#elif CONFIG_SIM_FBBPP == 4 +# define FB_FMT FB_FMT_RGB4 +#elif CONFIG_SIM_FBBPP == 8 +# define FB_FMT FB_FMT_RGB8 +#elif CONFIG_SIM_FBBPP == 16 +# define FB_FMT FB_FMT_RGB16_565 +#elif CONFIG_SIM_FBBPP == 24 +# define FB_FMT FB_FMT_RGB24 +#elif CONFIG_SIM_FBBPP == 32 +# define FB_FMT FB_FMT_RGB32 +#else +# error "Unsupported BPP" +#endif + +/* Debug ********************************************************************/ +/* 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 + +#ifdef CONFIG_DEBUG_LCD +# define lcddbg(format, ...) vdbg(format, ##__VA_ARGS__) +#else +# define lcddbg(x...) +#endif + +/**************************************************************************** + * Private Type Definition + ****************************************************************************/ + +/* This structure describes the state of this driver */ + +struct sim_dev_s +{ + /* Publically visible device structure */ + + struct lcd_dev_s dev; + + /* Private LCD-specific information follows */ + + uint8_t power; /* Current power setting */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* LCD Data Transfer Methods */ + +static int sim_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels); +static int sim_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels); + +/* LCD Configuration */ + +static int sim_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo); +static int sim_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 sim_getpower(struct lcd_dev_s *dev); +static int sim_setpower(struct lcd_dev_s *dev, int power); +static int sim_getcontrast(struct lcd_dev_s *dev); +static int sim_setcontrast(struct lcd_dev_s *dev, unsigned int contrast); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This is working memory allocated by the LCD driver for each LCD device + * and for each color plane. This memory will hold one raster line of data. + * The size of the allocated run buffer must therefore be at least + * (bpp * xres / 8). Actual alignment of the buffer must conform to the + * bitwidth of the underlying pixel type. + * + * If there are multiple planes, they may share the same working buffer + * because different planes will not be operate on concurrently. However, + * if there are multiple LCD devices, they must each have unique run buffers. + */ + +static uint8_t g_runbuffer[FB_STRIDE]; + +/* This structure describes the overall LCD video controller */ + +static const struct fb_videoinfo_s g_videoinfo = +{ + .fmt = FB_FMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ + .xres = CONFIG_SIM_FBWIDTH, /* Horizontal resolution in pixel columns */ + .yres = CONFIG_SIM_FBHEIGHT, /* Vertical resolution in pixel rows */ + .nplanes = 1, /* Number of color planes supported */ +}; + +/* This is the standard, NuttX Plane information object */ + +static const struct lcd_planeinfo_s g_planeinfo = +{ + .putrun = sim_putrun, /* Put a run into LCD memory */ + .getrun = sim_getrun, /* Get a run from LCD memory */ + .buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */ + .bpp = CONFIG_SIM_FBBPP, /* Bits-per-pixel */ +}; + +/* This is the standard, NuttX LCD driver object */ + +static struct sim_dev_s g_lcddev = +{ + .dev = + { + /* LCD Configuration */ + + .getvideoinfo = sim_getvideoinfo, + .getplaneinfo = sim_getplaneinfo, + + /* LCD RGB Mapping -- Not supported */ + /* Cursor Controls -- Not supported */ + + /* LCD Specific Controls */ + + .getpower = sim_getpower, + .setpower = sim_setpower, + .getcontrast = sim_getcontrast, + .setcontrast = sim_setcontrast, + }, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sim_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 sim_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels) +{ + lcddbg("row: %d col: %d npixels: %d\n", row, col, npixels); + return OK; +} + +/**************************************************************************** + * Name: sim_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 sim_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels) +{ + lcddbg("row: %d col: %d npixels: %d\n", row, col, npixels); + return -ENOSYS; +} + +/**************************************************************************** + * Name: sim_getvideoinfo + * + * Description: + * Get information about the LCD video controller configuration. + * + ****************************************************************************/ + +static int sim_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo) +{ + DEBUGASSERT(dev && vinfo); + gvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n", + g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); + memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s)); + return OK; +} + +/**************************************************************************** + * Name: sim_getplaneinfo + * + * Description: + * Get information about the configuration of each LCD color plane. + * + ****************************************************************************/ + +static int sim_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, + FAR struct lcd_planeinfo_s *pinfo) +{ + DEBUGASSERT(dev && pinfo && planeno == 0); + gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); + memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s)); + return OK; +} + +/**************************************************************************** + * Name: sim_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 sim_getpower(struct lcd_dev_s *dev) +{ + gvdbg("power: %d\n", 0); + return g_lcddev.power; +} + +/**************************************************************************** + * Name: sim_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 sim_setpower(struct lcd_dev_s *dev, int power) +{ + gvdbg("power: %d\n", power); + DEBUGASSERT(power <= CONFIG_LCD_MAXPOWER); + + /* Set new power level */ + + g_lcddev.power = power; + return OK; +} + +/**************************************************************************** + * Name: sim_getcontrast + * + * Description: + * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). + * + ****************************************************************************/ + +static int sim_getcontrast(struct lcd_dev_s *dev) +{ + gvdbg("Not implemented\n"); + return -ENOSYS; +} + +/**************************************************************************** + * Name: sim_setcontrast + * + * Description: + * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). + * + ****************************************************************************/ + +static int sim_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) +{ + gvdbg("contrast: %d\n", contrast); + return -ENOSYS; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_lcd_initialize + * + * Description: + * Initialize the LCD video hardware. The initial state of the LCD is + * fully initialized, display memory cleared, and the LCD ready to use, + * but with the power setting at 0 (full off). + * + ****************************************************************************/ + +int board_lcd_initialize(void) +{ + gvdbg("Initializing\n"); + return OK; +} + +/**************************************************************************** + * Name: board_lcd_getdev + * + * Description: + * Return a a reference to the LCD object for the specified LCD. This + * allows support for multiple LCD devices. + * + ****************************************************************************/ + +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) +{ + DEBUGASSERT(lcddev == 0); + return &g_lcddev.dev; +} + +/**************************************************************************** + * Name: board_lcd_uninitialize + * + * Description: + * Unitialize the LCD support + * + ****************************************************************************/ + +void board_lcd_uninitialize(void) +{ +} diff --git a/nuttx/arch/sim/src/up_lcd.c b/nuttx/arch/sim/src/up_lcd.c deleted file mode 100644 index fb815d12e..000000000 --- a/nuttx/arch/sim/src/up_lcd.c +++ /dev/null @@ -1,428 +0,0 @@ -/**************************************************************************** - * arch/sim/src/up_lcd.c - * - * Copyright (C) 2011 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 - * 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 - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Configuration ************************************************************/ -/* Check contrast selection */ - -#if !defined(CONFIG_LCD_MAXCONTRAST) -# define CONFIG_LCD_MAXCONTRAST 100 -#endif - -/* Check power setting */ - -#if !defined(CONFIG_LCD_MAXPOWER) -# define CONFIG_LCD_MAXPOWER 100 -#endif - -/* Simulated LCD geometry and color format */ - -#ifndef CONFIG_SIM_FBWIDTH -# define CONFIG_SIM_FBWIDTH 320 /* Framebuffer width in pixels */ -#endif - -#ifndef CONFIG_SIM_FBHEIGHT -# define CONFIG_SIM_FBHEIGHT 240 /* Framebuffer height in pixels */ -#endif - -#ifndef CONFIG_SIM_FBBPP -# define CONFIG_SIM_FBBPP 16 /* Framebuffer bytes per pixel (RGB) */ -#endif - -#define FB_STRIDE ((CONFIG_SIM_FBBPP * CONFIG_SIM_FBWIDTH + 7) >> 3) - -#undef FB_FMT -#if CONFIG_SIM_FBBPP == 1 -# define FB_FMT FB_FMT_RGB1 -#elif CONFIG_SIM_FBBPP == 4 -# define FB_FMT FB_FMT_RGB4 -#elif CONFIG_SIM_FBBPP == 8 -# define FB_FMT FB_FMT_RGB8 -#elif CONFIG_SIM_FBBPP == 16 -# define FB_FMT FB_FMT_RGB16_565 -#elif CONFIG_SIM_FBBPP == 24 -# define FB_FMT FB_FMT_RGB24 -#elif CONFIG_SIM_FBBPP == 32 -# define FB_FMT FB_FMT_RGB32 -#else -# error "Unsupported BPP" -#endif - -/* Debug ********************************************************************/ -/* 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 - -#ifdef CONFIG_DEBUG_LCD -# define lcddbg(format, ...) vdbg(format, ##__VA_ARGS__) -#else -# define lcddbg(x...) -#endif - -/**************************************************************************** - * Private Type Definition - ****************************************************************************/ - -/* This structure describes the state of this driver */ - -struct sim_dev_s -{ - /* Publically visible device structure */ - - struct lcd_dev_s dev; - - /* Private LCD-specific information follows */ - - uint8_t power; /* Current power setting */ -}; - -/**************************************************************************** - * Private Function Protototypes - ****************************************************************************/ - -/* LCD Data Transfer Methods */ - -static int sim_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, - size_t npixels); -static int sim_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels); - -/* LCD Configuration */ - -static int sim_getvideoinfo(FAR struct lcd_dev_s *dev, - FAR struct fb_videoinfo_s *vinfo); -static int sim_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 sim_getpower(struct lcd_dev_s *dev); -static int sim_setpower(struct lcd_dev_s *dev, int power); -static int sim_getcontrast(struct lcd_dev_s *dev); -static int sim_setcontrast(struct lcd_dev_s *dev, unsigned int contrast); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/* This is working memory allocated by the LCD driver for each LCD device - * and for each color plane. This memory will hold one raster line of data. - * The size of the allocated run buffer must therefore be at least - * (bpp * xres / 8). Actual alignment of the buffer must conform to the - * bitwidth of the underlying pixel type. - * - * If there are multiple planes, they may share the same working buffer - * because different planes will not be operate on concurrently. However, - * if there are multiple LCD devices, they must each have unique run buffers. - */ - -static uint8_t g_runbuffer[FB_STRIDE]; - -/* This structure describes the overall LCD video controller */ - -static const struct fb_videoinfo_s g_videoinfo = -{ - .fmt = FB_FMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ - .xres = CONFIG_SIM_FBWIDTH, /* Horizontal resolution in pixel columns */ - .yres = CONFIG_SIM_FBHEIGHT, /* Vertical resolution in pixel rows */ - .nplanes = 1, /* Number of color planes supported */ -}; - -/* This is the standard, NuttX Plane information object */ - -static const struct lcd_planeinfo_s g_planeinfo = -{ - .putrun = sim_putrun, /* Put a run into LCD memory */ - .getrun = sim_getrun, /* Get a run from LCD memory */ - .buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */ - .bpp = CONFIG_SIM_FBBPP, /* Bits-per-pixel */ -}; - -/* This is the standard, NuttX LCD driver object */ - -static struct sim_dev_s g_lcddev = -{ - .dev = - { - /* LCD Configuration */ - - .getvideoinfo = sim_getvideoinfo, - .getplaneinfo = sim_getplaneinfo, - - /* LCD RGB Mapping -- Not supported */ - /* Cursor Controls -- Not supported */ - - /* LCD Specific Controls */ - - .getpower = sim_getpower, - .setpower = sim_setpower, - .getcontrast = sim_getcontrast, - .setcontrast = sim_setcontrast, - }, -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sim_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 sim_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, - size_t npixels) -{ - lcddbg("row: %d col: %d npixels: %d\n", row, col, npixels); - return OK; -} - -/**************************************************************************** - * Name: sim_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 sim_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, - size_t npixels) -{ - lcddbg("row: %d col: %d npixels: %d\n", row, col, npixels); - return -ENOSYS; -} - -/**************************************************************************** - * Name: sim_getvideoinfo - * - * Description: - * Get information about the LCD video controller configuration. - * - ****************************************************************************/ - -static int sim_getvideoinfo(FAR struct lcd_dev_s *dev, - FAR struct fb_videoinfo_s *vinfo) -{ - DEBUGASSERT(dev && vinfo); - gvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n", - g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); - memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s)); - return OK; -} - -/**************************************************************************** - * Name: sim_getplaneinfo - * - * Description: - * Get information about the configuration of each LCD color plane. - * - ****************************************************************************/ - -static int sim_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, - FAR struct lcd_planeinfo_s *pinfo) -{ - DEBUGASSERT(dev && pinfo && planeno == 0); - gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); - memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s)); - return OK; -} - -/**************************************************************************** - * Name: sim_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 sim_getpower(struct lcd_dev_s *dev) -{ - gvdbg("power: %d\n", 0); - return g_lcddev.power; -} - -/**************************************************************************** - * Name: sim_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 sim_setpower(struct lcd_dev_s *dev, int power) -{ - gvdbg("power: %d\n", power); - DEBUGASSERT(power <= CONFIG_LCD_MAXPOWER); - - /* Set new power level */ - - g_lcddev.power = power; - return OK; -} - -/**************************************************************************** - * Name: sim_getcontrast - * - * Description: - * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). - * - ****************************************************************************/ - -static int sim_getcontrast(struct lcd_dev_s *dev) -{ - gvdbg("Not implemented\n"); - return -ENOSYS; -} - -/**************************************************************************** - * Name: sim_setcontrast - * - * Description: - * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). - * - ****************************************************************************/ - -static int sim_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) -{ - gvdbg("contrast: %d\n", contrast); - return -ENOSYS; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_lcdinitialize - * - * Description: - * Initialize the LCD video hardware. The initial state of the LCD is - * fully initialized, display memory cleared, and the LCD ready to use, - * but with the power setting at 0 (full off). - * - ****************************************************************************/ - -int up_lcdinitialize(void) -{ - gvdbg("Initializing\n"); - return OK; -} - -/**************************************************************************** - * Name: up_lcdgetdev - * - * Description: - * Return a a reference to the LCD object for the specified LCD. This - * allows support for multiple LCD devices. - * - ****************************************************************************/ - -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) -{ - DEBUGASSERT(lcddev == 0); - return &g_lcddev.dev; -} - -/**************************************************************************** - * Name: up_lcduninitialize - * - * Description: - * Unitialize the LCD support - * - ****************************************************************************/ - -void up_lcduninitialize(void) -{ -} - diff --git a/nuttx/configs/compal_e99/src/ssd1783.c b/nuttx/configs/compal_e99/src/ssd1783.c index 64ed6a2e7..e1bf5054f 100644 --- a/nuttx/configs/compal_e99/src/ssd1783.c +++ b/nuttx/configs/compal_e99/src/ssd1783.c @@ -40,6 +40,10 @@ * ************************************************************************************/ +/************************************************************************************ + * Included Files + ************************************************************************************/ + #include #include @@ -50,19 +54,26 @@ #include #include +#include #include #include #include "up_arch.h" #include "ssd1783.h" +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + /* Color depth and format */ + #define LCD_BPP 16 #define LCD_COLORFMT FB_FMT_RGB16_555 /* Display Resolution */ -# define LCD_XRES 98 -# define LCD_YRES 67 + +#define LCD_XRES 98 +#define LCD_YRES 67 /* Debug ******************************************************************************/ @@ -448,7 +459,7 @@ static inline void lcd_initialize(void) /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -457,7 +468,7 @@ static inline void lcd_initialize(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { gvdbg("Initializing\n"); @@ -470,7 +481,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -478,7 +489,7 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; @@ -486,14 +497,14 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Un-initialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { lcd_setpower(&g_lcddev.dev, 0); } diff --git a/nuttx/configs/hymini-stm32v/src/stm32_r61505u.c b/nuttx/configs/hymini-stm32v/src/stm32_r61505u.c index b722e18cf..c519abb05 100755 --- a/nuttx/configs/hymini-stm32v/src/stm32_r61505u.c +++ b/nuttx/configs/hymini-stm32v/src/stm32_r61505u.c @@ -50,6 +50,7 @@ #include #include +#include #include #include @@ -907,7 +908,7 @@ static void lcd_backlight(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -916,7 +917,7 @@ static void lcd_backlight(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { unsigned short id; @@ -937,7 +938,7 @@ int up_lcdinitialize(void) { /* Not a R61505U ? */ - gdbg("up_lcdinitialize: LCD ctrl is not a R61505U"); + gdbg("board_lcd_initialize: LCD ctrl is not a R61505U"); return ERROR; } @@ -956,7 +957,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -964,21 +965,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Un-initialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { lcd_setpower(&g_lcddev.dev, 0); stm32_deselectlcd(); diff --git a/nuttx/configs/hymini-stm32v/src/stm32_ssd1289.c b/nuttx/configs/hymini-stm32v/src/stm32_ssd1289.c index 942375edc..faa37bc87 100644 --- a/nuttx/configs/hymini-stm32v/src/stm32_ssd1289.c +++ b/nuttx/configs/hymini-stm32v/src/stm32_ssd1289.c @@ -44,6 +44,7 @@ #include #include +#include #include #include @@ -466,7 +467,7 @@ static void stm32_enablefsmc(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -475,7 +476,7 @@ static void stm32_enablefsmc(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { /* Only initialize the driver once */ @@ -507,7 +508,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -515,21 +516,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return g_ssd1289drvr; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the display off */ diff --git a/nuttx/configs/kwikstik-k40/src/k40_lcd.c b/nuttx/configs/kwikstik-k40/src/k40_lcd.c index 30139b94e..57e0dfb0c 100644 --- a/nuttx/configs/kwikstik-k40/src/k40_lcd.c +++ b/nuttx/configs/kwikstik-k40/src/k40_lcd.c @@ -43,6 +43,7 @@ #include #include +#include #include #include "up_arch.h" @@ -86,7 +87,7 @@ **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -95,7 +96,7 @@ * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { gvdbg("Initializing\n"); #warning "Missing logic" @@ -103,7 +104,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -111,7 +112,7 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); #warning "Missing logic" @@ -119,14 +120,14 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { #warning "Missing logic" } diff --git a/nuttx/configs/maple/src/stm32_lcd.c b/nuttx/configs/maple/src/stm32_lcd.c index d00edea2c..c143e905e 100644 --- a/nuttx/configs/maple/src/stm32_lcd.c +++ b/nuttx/configs/maple/src/stm32_lcd.c @@ -48,6 +48,7 @@ #include #include +#include #include #include #include @@ -178,7 +179,7 @@ static FAR struct memlcd_priv_s memlcd_priv = ****************************************************************************/ /**************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is @@ -187,7 +188,7 @@ static FAR struct memlcd_priv_s memlcd_priv = * ****************************************************************************/ -FAR int up_lcdinitialize(void) +FAR int board_lcd_initialize(void) { lcddbg("Initializing lcd\n"); @@ -217,7 +218,7 @@ FAR int up_lcdinitialize(void) } /**************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This @@ -225,7 +226,7 @@ FAR int up_lcdinitialize(void) * ****************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return l_lcddev; diff --git a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h index 9bf2aa6e0..c3e3c6fdf 100644 --- a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h +++ b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h @@ -253,19 +253,6 @@ void weak_function stm32_usbinitialize(void); void stm32_lcdinitialize(void); #endif -/**************************************************************************************************** - * Name: up_lcdinitialize - * - * Description: - * Initialize the LCD video hardware. The initial state of the LCD is fully initialized, display - * memory cleared, and the LCD ready to use, but with the power setting at 0 (full off). - * - ****************************************************************************************************/ - -#if defined(CONFIG_LCD_MIO283QT2) || defined(CONFIG_LCD_MIO283QT9A) -int up_lcdinitialize(void); -#endif - /**************************************************************************************************** * Name: up_vs1053initialize * diff --git a/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt2.c b/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt2.c index 708a3d20e..859be4425 100644 --- a/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt2.c +++ b/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt2.c @@ -51,6 +51,7 @@ #include #include +#include #include #include @@ -484,7 +485,7 @@ void stm32_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -493,7 +494,7 @@ void stm32_lcdinitialize(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { /* Only initialize the driver once. NOTE: The LCD GPIOs were already configured * by stm32_lcdinitialize. @@ -530,7 +531,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -538,21 +539,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return g_stm32f4_lcd.drvr; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the display off */ diff --git a/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt9a.c b/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt9a.c index 375d8aea3..7ef040f86 100644 --- a/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt9a.c +++ b/nuttx/configs/mikroe-stm32f4/src/stm32_mio283qt9a.c @@ -52,6 +52,7 @@ #include #include +#include #include #include @@ -485,7 +486,7 @@ void stm32_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -494,7 +495,7 @@ void stm32_lcdinitialize(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { /* Only initialize the driver once. NOTE: The LCD GPIOs were already configured * by stm32_lcdinitialize. @@ -531,7 +532,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -539,21 +540,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return g_stm32f4_lcd.drvr; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Uninitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the display off */ diff --git a/nuttx/configs/mikroe-stm32f4/src/stm32_nsh.c b/nuttx/configs/mikroe-stm32f4/src/stm32_nsh.c index 836b4273e..bff2f0678 100644 --- a/nuttx/configs/mikroe-stm32f4/src/stm32_nsh.c +++ b/nuttx/configs/mikroe-stm32f4/src/stm32_nsh.c @@ -348,7 +348,7 @@ int board_app_initialize(void) syslog(LOG_INFO, "Initializing TFT LCD module\n"); - ret = up_lcdinitialize(); + ret = board_lcd_initialize(); if (ret != OK) { syslog(LOG_ERR, "ERROR: Failed to initialize TFT LCD module\n"); diff --git a/nuttx/configs/pic32mx7mmb/src/pic32_mio283qt2.c b/nuttx/configs/pic32mx7mmb/src/pic32_mio283qt2.c index ff0e10ac2..5384ffeec 100644 --- a/nuttx/configs/pic32mx7mmb/src/pic32_mio283qt2.c +++ b/nuttx/configs/pic32mx7mmb/src/pic32_mio283qt2.c @@ -49,6 +49,7 @@ #include #include +#include #include #include @@ -410,7 +411,7 @@ static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -419,7 +420,7 @@ static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { uint32_t regval; @@ -485,7 +486,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -493,21 +494,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return g_pic32mx7mmb_lcd.drvr; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the display off */ diff --git a/nuttx/configs/sam3u-ek/src/sam_lcd.c b/nuttx/configs/sam3u-ek/src/sam_lcd.c index 07de0aeec..feed61988 100644 --- a/nuttx/configs/sam3u-ek/src/sam_lcd.c +++ b/nuttx/configs/sam3u-ek/src/sam_lcd.c @@ -118,6 +118,7 @@ #include #include +#include #include #include @@ -856,7 +857,7 @@ static int sam_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -865,7 +866,7 @@ static int sam_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { #ifdef CONFIG_DEBUG_LCD uint16_t hxregval; @@ -1038,7 +1039,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows @@ -1046,21 +1047,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { lcdvdbg("lcddev: %d\n", lcddev); return lcddev == 0 ? &g_lcddev_s.dev : NULL; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the framebuffer support. * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the LCD off */ diff --git a/nuttx/configs/sam4e-ek/src/sam_ili9325.c b/nuttx/configs/sam4e-ek/src/sam_ili9325.c index eb419c467..532e20803 100644 --- a/nuttx/configs/sam4e-ek/src/sam_ili9325.c +++ b/nuttx/configs/sam4e-ek/src/sam_ili9325.c @@ -125,6 +125,7 @@ #include #include +#include #include #include #include @@ -1304,7 +1305,7 @@ static inline int sam_lcd_initialize(void) ************************************************************************************/ /************************************************************************************ - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -1313,7 +1314,7 @@ static inline int sam_lcd_initialize(void) * ************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { FAR struct sam_dev_s *priv = &g_lcddev; int ret; @@ -1351,7 +1352,7 @@ int up_lcdinitialize(void) } /************************************************************************************ - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows @@ -1359,21 +1360,21 @@ int up_lcdinitialize(void) * ************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************ - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Uninitialize the LCD support * ************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { FAR struct sam_dev_s *priv = &g_lcddev; diff --git a/nuttx/configs/sam4e-ek/src/sam_ili9341.c b/nuttx/configs/sam4e-ek/src/sam_ili9341.c index 6e54073ee..d752c665a 100644 --- a/nuttx/configs/sam4e-ek/src/sam_ili9341.c +++ b/nuttx/configs/sam4e-ek/src/sam_ili9341.c @@ -125,6 +125,7 @@ #include #include +#include #include #include #include @@ -1183,7 +1184,7 @@ static inline int sam_lcd_initialize(void) ************************************************************************************/ /************************************************************************************ - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -1192,7 +1193,7 @@ static inline int sam_lcd_initialize(void) * ************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { FAR struct sam_dev_s *priv = &g_lcddev; int ret; @@ -1230,7 +1231,7 @@ int up_lcdinitialize(void) } /************************************************************************************ - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows @@ -1238,21 +1239,21 @@ int up_lcdinitialize(void) * ************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************ - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Uninitialize the LCD support * ************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { FAR struct sam_dev_s *priv = &g_lcddev; diff --git a/nuttx/configs/samv71-xult/README.txt b/nuttx/configs/samv71-xult/README.txt index 6f4de1bfe..231eb8e4b 100644 --- a/nuttx/configs/samv71-xult/README.txt +++ b/nuttx/configs/samv71-xult/README.txt @@ -755,8 +755,11 @@ Testing has also been performed using the maXTouch Xplained Pro LCD maXTouch Xplained Pro Standard Extension Header ----------------------------------------------- The LCD could be connected either via EXT1 or EXT2 using the 2x10 20-pin -cable and the maXTouch Xplained Pro standard extension header. Access is -then performed in SPI mode. +cable and the maXTouch Xplained Pro standard extension header. Access would +then be performed in SPI mode. + +NOTE: There is currently no support for use of the LCD in SPI mode. See +the next paragraph where the LCD/EXT4 connection is discussion. NOTE the 3 switch mode selector on the back of the maXtouch. All switches should be in the ON position to select 4-wire SPI mode. @@ -863,6 +866,10 @@ in the OFF-ON-OFF positions to select 16-bit color mode. 50 GND - - Ground ---- ------------ ---- -------- ----------------------------------------------------------- +NOTE: Use of LCD/EXT4 conflicts with the Arduino RXD pin (PD28). You cannot +put the maXTouch Xplained in LCD/EXT4 and also use the Arduino RXD/TXD pins +as your serial console. + Connecting the flat cable. I was embarrassed to say that I did not know how the connectors worked. Let me share this so that, perhaps, I can save you the same embarrassment: @@ -878,7 +885,6 @@ the same embarrassment: toward the board. Lock the cable in place by pushing the tabs back in place. - MXT Configuration Options ------------------------- diff --git a/nuttx/configs/samv71-xult/src/sam_ili9488.c b/nuttx/configs/samv71-xult/src/sam_ili9488.c index 734b9794b..8cfe62101 100644 --- a/nuttx/configs/samv71-xult/src/sam_ili9488.c +++ b/nuttx/configs/samv71-xult/src/sam_ili9488.c @@ -129,6 +129,7 @@ #include #include +#include #include #include #include @@ -1541,7 +1542,7 @@ static inline int sam_lcd_initialize(void) ****************************************************************************/ /**************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is @@ -1550,7 +1551,7 @@ static inline int sam_lcd_initialize(void) * ****************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { FAR struct sam_dev_s *priv = &g_lcddev; int ret; @@ -1628,7 +1629,7 @@ errout_with_waitsem: } /**************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This @@ -1636,21 +1637,21 @@ errout_with_waitsem: * ****************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /**************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Uninitialize the LCD support * ****************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { FAR struct sam_dev_s *priv = &g_lcddev; diff --git a/nuttx/configs/shenzhou/src/stm32_ili93xx.c b/nuttx/configs/shenzhou/src/stm32_ili93xx.c index 3da0df253..41391f6c0 100644 --- a/nuttx/configs/shenzhou/src/stm32_ili93xx.c +++ b/nuttx/configs/shenzhou/src/stm32_ili93xx.c @@ -67,7 +67,7 @@ * 45 PE14 DB14 To TFT LCD (CN13, pin 17) * 46 PE15 DB15 To TFT LCD (CN13, pin 18) * - * NOTE: The backlight signl NC_BL (CN13, pin 24) is pulled high and not under + * NOTE: The backlight signal NC_BL (CN13, pin 24) is pulled high and not under * software control * * On LCD module: @@ -120,6 +120,7 @@ #include #include +#include #include #include @@ -1863,7 +1864,7 @@ static inline int stm32_lcdinitialize(FAR struct stm32_dev_s *priv) ************************************************************************************/ /************************************************************************************ - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -1872,7 +1873,7 @@ static inline int stm32_lcdinitialize(FAR struct stm32_dev_s *priv) * ************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { FAR struct stm32_dev_s *priv = &g_lcddev; int ret; @@ -1912,7 +1913,7 @@ int up_lcdinitialize(void) } /************************************************************************************ - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -1920,21 +1921,21 @@ int up_lcdinitialize(void) * ************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************ - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * ************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { FAR struct stm32_dev_s *priv = &g_lcddev; diff --git a/nuttx/configs/shenzhou/src/stm32_ssd1289.c b/nuttx/configs/shenzhou/src/stm32_ssd1289.c index 1558201e1..d40dbf0af 100644 --- a/nuttx/configs/shenzhou/src/stm32_ssd1289.c +++ b/nuttx/configs/shenzhou/src/stm32_ssd1289.c @@ -50,6 +50,7 @@ #include #include +#include #include #include #include @@ -109,7 +110,7 @@ struct stm32_lower_s }; /************************************************************************************** - * Private Function Protototypes + * Private Function Prototypes **************************************************************************************/ /* Helpers */ @@ -529,7 +530,7 @@ static void stm32_lcdoutput(FAR struct stm32_lower_s *priv) ************************************************************************************/ /************************************************************************************ - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -538,7 +539,7 @@ static void stm32_lcdoutput(FAR struct stm32_lower_s *priv) * ************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { FAR struct stm32_lower_s *priv = &g_lcdlower; int i; @@ -574,7 +575,7 @@ int up_lcdinitialize(void) } /************************************************************************************ - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows @@ -582,7 +583,7 @@ int up_lcdinitialize(void) * ************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { FAR struct stm32_lower_s *priv = &g_lcdlower; DEBUGASSERT(lcddev == 0); @@ -590,14 +591,14 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) } /************************************************************************************ - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * ************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { FAR struct stm32_lower_s *priv = &g_lcdlower; diff --git a/nuttx/configs/stm3210e-eval/src/stm32_lcd.c b/nuttx/configs/stm3210e-eval/src/stm32_lcd.c index 4168f39a7..5bc221338 100644 --- a/nuttx/configs/stm3210e-eval/src/stm32_lcd.c +++ b/nuttx/configs/stm3210e-eval/src/stm32_lcd.c @@ -67,6 +67,7 @@ #include #include +#include #include #include @@ -1766,7 +1767,7 @@ static void stm3210e_backlight(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -1775,7 +1776,7 @@ static void stm3210e_backlight(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { #ifdef CONFIG_PM int ret; @@ -1813,7 +1814,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -1821,21 +1822,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { stm3210e_poweroff(); stm32_deselectlcd(); diff --git a/nuttx/configs/stm3220g-eval/src/stm32_lcd.c b/nuttx/configs/stm3220g-eval/src/stm32_lcd.c index 39878b296..d173cb2c0 100644 --- a/nuttx/configs/stm3220g-eval/src/stm32_lcd.c +++ b/nuttx/configs/stm3220g-eval/src/stm32_lcd.c @@ -53,6 +53,7 @@ #include #include +#include #include #include @@ -1122,7 +1123,7 @@ static inline void stm3220g_lcdinitialize(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -1131,7 +1132,7 @@ static inline void stm3220g_lcdinitialize(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { lcdvdbg("Initializing\n"); @@ -1155,7 +1156,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -1163,21 +1164,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { stm3220g_poweroff(); stm32_deselectlcd(); diff --git a/nuttx/configs/stm3240g-eval/src/stm32_lcd.c b/nuttx/configs/stm3240g-eval/src/stm32_lcd.c index 350fc33b1..c1f92d774 100644 --- a/nuttx/configs/stm3240g-eval/src/stm32_lcd.c +++ b/nuttx/configs/stm3240g-eval/src/stm32_lcd.c @@ -53,6 +53,7 @@ #include #include +#include #include #include @@ -1121,7 +1122,7 @@ static inline void stm3240g_lcdinitialize(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -1130,7 +1131,7 @@ static inline void stm3240g_lcdinitialize(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { lcdvdbg("Initializing\n"); @@ -1154,7 +1155,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -1162,21 +1163,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return &g_lcddev.dev; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { stm3240g_poweroff(); stm32_deselectlcd(); diff --git a/nuttx/configs/stm32f429i-disco/src/stm32_lcd.c b/nuttx/configs/stm32f429i-disco/src/stm32_lcd.c index e885927e3..765cb84f7 100644 --- a/nuttx/configs/stm32f429i-disco/src/stm32_lcd.c +++ b/nuttx/configs/stm32f429i-disco/src/stm32_lcd.c @@ -43,6 +43,7 @@ #include #include +#include #include #include @@ -413,7 +414,7 @@ static int stm32_ili9341_initialize(void) #ifdef CONFIG_STM32F429I_DISCO_ILI9341_LCDIFACE /**************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD Device. @@ -424,7 +425,7 @@ static int stm32_ili9341_initialize(void) * ***************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Set display off */ @@ -435,7 +436,7 @@ void up_lcduninitialize(void) /**************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a reference to the LCD object for the specified LCD Device. @@ -449,7 +450,7 @@ void up_lcduninitialize(void) * ***************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { if (lcddev == ILI9341_LCD_DEVICE) { @@ -461,7 +462,7 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) /**************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is @@ -476,7 +477,7 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) * ****************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { /* check if always initialized */ diff --git a/nuttx/configs/stm32f4discovery/src/stm32_ssd1289.c b/nuttx/configs/stm32f4discovery/src/stm32_ssd1289.c index 74c6ee22e..741a5b590 100644 --- a/nuttx/configs/stm32f4discovery/src/stm32_ssd1289.c +++ b/nuttx/configs/stm32f4discovery/src/stm32_ssd1289.c @@ -50,6 +50,7 @@ #include #include +#include #include #include #include @@ -339,7 +340,7 @@ void stm32_selectlcd(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -348,7 +349,7 @@ void stm32_selectlcd(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { /* Only initialize the driver once */ @@ -390,7 +391,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -398,21 +399,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return g_ssd1289drvr; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the display off */ diff --git a/nuttx/configs/viewtool-stm32f107/src/stm32_ssd1289.c b/nuttx/configs/viewtool-stm32f107/src/stm32_ssd1289.c index cb7329ada..7e42cf854 100644 --- a/nuttx/configs/viewtool-stm32f107/src/stm32_ssd1289.c +++ b/nuttx/configs/viewtool-stm32f107/src/stm32_ssd1289.c @@ -43,6 +43,7 @@ #include #include +#include #include #include @@ -532,7 +533,7 @@ static void stm32_enablefsmc(void) **************************************************************************************/ /************************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize * * Description: * Initialize the LCD video hardware. The initial state of the LCD is fully @@ -541,7 +542,7 @@ static void stm32_enablefsmc(void) * **************************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { /* Only initialize the driver once */ @@ -575,7 +576,7 @@ int up_lcdinitialize(void) } /************************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev * * Description: * Return a a reference to the LCD object for the specified LCD. This allows support @@ -583,21 +584,21 @@ int up_lcdinitialize(void) * **************************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { DEBUGASSERT(lcddev == 0); return g_ssd1289drvr; } /************************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize * * Description: * Unitialize the LCD support * **************************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* Turn the display off */ diff --git a/nuttx/configs/zkit-arm-1769/src/lpc17_lcd.c b/nuttx/configs/zkit-arm-1769/src/lpc17_lcd.c index 3ccda6f8a..a0dff00f6 100644 --- a/nuttx/configs/zkit-arm-1769/src/lpc17_lcd.c +++ b/nuttx/configs/zkit-arm-1769/src/lpc17_lcd.c @@ -49,10 +49,11 @@ #include #include +#include +#include #include #include #include -#include #include "up_arch.h" #include "up_internal.h" @@ -103,10 +104,10 @@ FAR struct lcd_dev_s *dev; ****************************************************************************/ /**************************************************************************** - * Name: up_lcdinitialize + * Name: board_lcd_initialize ****************************************************************************/ -int up_lcdinitialize(void) +int board_lcd_initialize(void) { lpc17_configgpio(ZKITARM_OLED_RST); lpc17_configgpio(ZKITARM_OLED_RS); @@ -128,10 +129,10 @@ int up_lcdinitialize(void) } /**************************************************************************** - * Name: up_lcdgetdev + * Name: board_lcd_getdev ****************************************************************************/ -FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) { dev = st7567_initialize(spi, lcddev); if (!dev) @@ -151,10 +152,10 @@ FAR struct lcd_dev_s *up_lcdgetdev(int lcddev) } /**************************************************************************** - * Name: up_lcduninitialize + * Name: board_lcd_uninitialize ****************************************************************************/ -void up_lcduninitialize(void) +void board_lcd_uninitialize(void) { /* TO-FIX */ } diff --git a/nuttx/graphics/nxmu/nx_start.c b/nuttx/graphics/nxmu/nx_start.c index 589557013..419a65b6f 100644 --- a/nuttx/graphics/nxmu/nx_start.c +++ b/nuttx/graphics/nxmu/nx_start.c @@ -107,19 +107,19 @@ int nx_server(int argc, char *argv[]) #elif defined(CONFIG_NX_LCDDRIVER) /* Initialize the LCD device */ - ret = up_lcdinitialize(); + ret = board_lcd_initialize(); if (ret < 0) { - gdbg("ERROR: up_lcdinitialize failed: %d\n", ret); + gdbg("ERROR: board_lcd_initialize failed: %d\n", ret); return EXIT_FAILURE; } /* Get the device instance */ - dev = up_lcdgetdev(CONFIG_NXSTART_DEVNO); + dev = board_lcd_getdev(CONFIG_NXSTART_DEVNO); if (!dev) { - gdbg("ERROR: up_lcdgetdev failed, devno=%d\n", CONFIG_NXSTART_DEVNO); + gdbg("ERROR: board_lcd_getdev failed, devno=%d\n", CONFIG_NXSTART_DEVNO); return EXIT_FAILURE; } diff --git a/nuttx/include/nuttx/board.h b/nuttx/include/nuttx/board.h index 8efa64668..d78ace4d7 100644 --- a/nuttx/include/nuttx/board.h +++ b/nuttx/include/nuttx/board.h @@ -272,6 +272,32 @@ FAR struct fb_vtable_s *board_graphics_setup(unsigned int devno); int board_ioctl(unsigned int cmd, uintptr_t arg); #endif +/**************************************************************************** + * Name: board_lcd_initialize, board_lcd_getdev, board_lcd_uninitialize + * + * Description: + * If an architecture supports a parallel or serial LCD, then it must + * provide APIs to access the LCD as follows: + * + * board_lcd_initialize - 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). + * board_lcd_getdev - Return a a reference to the LCD object for + * the specified LCD. This allows support for + * multiple LCD devices. + * board_lcd_uninitialize - Uninitialize the LCD support + * + ***************************************************************************/ + +#ifdef CONFIG_LCD +struct lcd_dev_s; /* Forward reference */ + +int board_lcd_initialize(void); +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev); +void board_lcd_uninitialize(void); +#endif + /**************************************************************************** * Name: board_led_initialize * diff --git a/nuttx/include/nuttx/lcd/lcd.h b/nuttx/include/nuttx/lcd/lcd.h index daf8e9982..0358f6de5 100644 --- a/nuttx/include/nuttx/lcd/lcd.h +++ b/nuttx/include/nuttx/lcd/lcd.h @@ -184,33 +184,12 @@ struct lcd_dev_s #ifdef __cplusplus #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif -/**************************************************************************** - * Name: up_lcdinitialize, up_lcdgetdev, up_lcduninitialize - * - * Description: - * If an architecture supports a parallel or serial LCD, then it must - * provide APIs to access the LCD as follows: - * - * up_lcdinitialize - 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). - * up_lcdgetdev - Return a a reference to the LCD object for - * the specified LCD. This allows support for - * multiple LCD devices. - * up_lcduninitialize - Unitialize the LCD support - * - ***************************************************************************/ - -EXTERN int up_lcdinitialize(void); -EXTERN FAR struct lcd_dev_s *up_lcdgetdev(int lcddev); -EXTERN void up_lcduninitialize(void); - #undef EXTERN #ifdef __cplusplus } -- cgit v1.2.3