summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-31 16:20:21 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-31 16:20:21 -0600
commit1aa554ab19210a162ab3ba7f8a635b1f11586aa2 (patch)
tree32eded82fe4e2e27796081de9c73f57613d1a322 /nuttx
parent89e6ac65fdaef533a95ad504bb18ec50c9cd977f (diff)
downloadpx4-nuttx-1aa554ab19210a162ab3ba7f8a635b1f11586aa2.tar.gz
px4-nuttx-1aa554ab19210a162ab3ba7f8a635b1f11586aa2.tar.bz2
px4-nuttx-1aa554ab19210a162ab3ba7f8a635b1f11586aa2.zip
Rename up_nxdrvinit() to board_graphics_setup(). Add CONFIG_BOARDCTL_GRAPHICS that will enabled calls to board_graphics_setup() from boardctrl(). In apps/ and NxWidgts/, replace all calls to up_nxdrvinit with calls to boardctl().
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/configs/Kconfig4
-rwxr-xr-xnuttx/configs/boardctl.c20
-rw-r--r--nuttx/configs/lm3s6965-ek/src/lm_oled.c14
-rw-r--r--nuttx/configs/lm3s8962-ek/src/lm_oled.c13
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/lpc17_oled.c13
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c9
-rw-r--r--nuttx/configs/sam4l-xplained/src/sam_ug2832hsweg04.c7
-rw-r--r--nuttx/configs/samd20-xplained/src/sam_ug2832hsweg04.c5
-rw-r--r--nuttx/configs/stm32f4discovery/src/stm32_ug2864ambag01.c5
-rw-r--r--nuttx/configs/stm32f4discovery/src/stm32_ug2864hsweg01.c5
-rw-r--r--nuttx/configs/zp214xpa/src/lpc2148_ug2864ambag01.c5
-rw-r--r--nuttx/graphics/Kconfig7
-rw-r--r--nuttx/graphics/nxmu/nx_start.c5
-rw-r--r--nuttx/include/nuttx/board.h23
-rw-r--r--nuttx/include/sys/boardctl.h29
15 files changed, 125 insertions, 39 deletions
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index 4fe6e0928..fab01136d 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -1596,6 +1596,10 @@ config BOARDCTL_ADCTEST
bool "Enable ADC test interfaces"
default n
+config BOARDCTL_GRAPHICS
+ bool "Enable custom graphics initialization interfaces"
+ default n
+
config BOARDCTL_IOCTL
bool "Board-specific boardctl() commands"
default n
diff --git a/nuttx/configs/boardctl.c b/nuttx/configs/boardctl.c
index 953b3e2d0..e8903f085 100755
--- a/nuttx/configs/boardctl.c
+++ b/nuttx/configs/boardctl.c
@@ -141,6 +141,26 @@ int boardctl(unsigned int cmd, uintptr_t arg)
break;
#endif
+#ifdef CONFIG_BOARDCTL_GRAPHICS
+ /* CMD: BOARDIOC_GRAPHICS_SETUP
+ * DESCRIPTION: Configure graphics that require special initialization
+ * procedures
+ * ARG: A pointer to an instance of struct boardioc_graphics_s
+ * CONFIGURATION: CONFIG_LIB_BOARDCTL && CONFIG_BOARDCTL_GRAPHICS
+ * DEPENDENCIES: Board logic must provide board_adc_setup()
+ */
+
+ case BOARDIOC_GRAPHICS_SETUP:
+ {
+ FAR struct boardioc_graphics_s *setup =
+ ( FAR struct boardioc_graphics_s *)arg;
+
+ setup->dev = board_graphics_setup(setup->devno);
+ ret = setup->dev ? OK : -ENODEV;
+ }
+ break;
+#endif
+
default:
{
#ifdef CONFIG_BOARDCTL_IOCTL
diff --git a/nuttx/configs/lm3s6965-ek/src/lm_oled.c b/nuttx/configs/lm3s6965-ek/src/lm_oled.c
index b2582ce82..7aa01e931 100644
--- a/nuttx/configs/lm3s6965-ek/src/lm_oled.c
+++ b/nuttx/configs/lm3s6965-ek/src/lm_oled.c
@@ -1,7 +1,7 @@
/****************************************************************************
* config/lm3s6965-ek/src/lm_oled.c
*
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,6 +43,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/p14201.h>
@@ -84,27 +85,27 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
/* Configure the OLED GPIOs */
- oledcs_dumpgpio("up_nxdrvinit: After OLEDCS setup");
- oleddc_dumpgpio("up_nxdrvinit: On entry");
+ oledcs_dumpgpio("board_graphics_setup: After OLEDCS setup");
+ oleddc_dumpgpio("board_graphics_setup: On entry");
tiva_configgpio(OLEDDC_GPIO); /* PC7: OLED display data/control select (D/Cn) */
tiva_configgpio(OLEDEN_GPIO); /* PC6: Enable +15V needed by OLED (EN+15V) */
- oleddc_dumpgpio("up_nxdrvinit: After OLEDDC/EN setup");
+ oleddc_dumpgpio("board_graphics_setup: After OLEDDC/EN setup");
/* Get the SSI port (configure as a Freescale SPI port) */
@@ -132,6 +133,7 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
return dev;
}
}
+
return NULL;
}
diff --git a/nuttx/configs/lm3s8962-ek/src/lm_oled.c b/nuttx/configs/lm3s8962-ek/src/lm_oled.c
index cc641adcb..b171881cb 100644
--- a/nuttx/configs/lm3s8962-ek/src/lm_oled.c
+++ b/nuttx/configs/lm3s8962-ek/src/lm_oled.c
@@ -1,7 +1,7 @@
/****************************************************************************
* config/lm3s8962-ek/src/lm_oled.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,6 +43,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/p14201.h>
@@ -84,27 +85,27 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
/* Configure the OLED GPIOs */
- oledcs_dumpgpio("up_nxdrvinit: After OLEDCS setup");
- oleddc_dumpgpio("up_nxdrvinit: On entry");
+ oledcs_dumpgpio("board_graphics_setup: After OLEDCS setup");
+ oleddc_dumpgpio("board_graphics_setup: On entry");
tiva_configgpio(OLEDDC_GPIO); /* PC7: OLED display data/control select (D/Cn) */
tiva_configgpio(OLEDEN_GPIO); /* PC6: Enable +15V needed by OLED (EN+15V) */
- oleddc_dumpgpio("up_nxdrvinit: After OLEDDC/EN setup");
+ oleddc_dumpgpio("board_graphics_setup: After OLEDDC/EN setup");
/* Get the SSI port (configure as a Freescale SPI port) */
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/lpc17_oled.c b/nuttx/configs/lpcxpresso-lpc1768/src/lpc17_oled.c
index 01692b65b..b14186f26 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/lpc17_oled.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/lpc17_oled.c
@@ -1,7 +1,7 @@
/****************************************************************************
* config/lpcxpresso-lpc1768/src/lpc17_oled.c
*
- * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,6 +43,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ug-9664hswag01.h>
@@ -98,14 +99,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
@@ -114,13 +115,13 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
* J43, J45 pin1-2 and J46 pin 1-2.
*/
- oledcs_dumpgpio("up_nxdrvinit: After OLED CS setup");
- oleddc_dumpgpio("up_nxdrvinit: On entry");
+ oledcs_dumpgpio("board_graphics_setup: After OLED CS setup");
+ oleddc_dumpgpio("board_graphics_setup: On entry");
(void)lpc17_configgpio(LPCXPRESSO_OLED_POWER); /* OLED 11V power */
(void)lpc17_configgpio(LPCXPRESSO_OLED_DC); /* OLED Command/Data */
- oleddc_dumpgpio("up_nxdrvinit: After OLED Power/DC setup");
+ oleddc_dumpgpio("board_graphics_setup: After OLED Power/DC setup");
/* Get the SPI1 port (configure as a Freescale SPI port) */
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c
index 4fa4d400d..180743ce3 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c
@@ -44,6 +44,7 @@
#include <errno.h>
#include <nuttx/arch.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/nokia6100.h>
@@ -176,24 +177,24 @@ void nokia_blinitialize(void)
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called NX initialization logic to configure the LCD.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
/* Configure the LCD GPIOs */
- lcd_dumpgpio("up_nxdrvinit: On entry");
+ lcd_dumpgpio("board_graphics_setup: On entry");
lpc17_configgpio(LPC1766STK_LCD_RST);
lpc17_configgpio(LPC1766STK_LCD_BL);
- lcd_dumpgpio("up_nxdrvinit: After GPIO setup");
+ lcd_dumpgpio("board_graphics_setup: After GPIO setup");
/* Reset the LCD */
diff --git a/nuttx/configs/sam4l-xplained/src/sam_ug2832hsweg04.c b/nuttx/configs/sam4l-xplained/src/sam_ug2832hsweg04.c
index 10000eb5e..9d5685550 100644
--- a/nuttx/configs/sam4l-xplained/src/sam_ug2832hsweg04.c
+++ b/nuttx/configs/sam4l-xplained/src/sam_ug2832hsweg04.c
@@ -1,7 +1,7 @@
/****************************************************************************
* config/sam4l-xplained/src/sam_ug2832hsweg04.c
*
- * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -80,6 +80,7 @@
#include <debug.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ssd1306.h>
@@ -126,14 +127,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
diff --git a/nuttx/configs/samd20-xplained/src/sam_ug2832hsweg04.c b/nuttx/configs/samd20-xplained/src/sam_ug2832hsweg04.c
index bc6fde097..52ac01971 100644
--- a/nuttx/configs/samd20-xplained/src/sam_ug2832hsweg04.c
+++ b/nuttx/configs/samd20-xplained/src/sam_ug2832hsweg04.c
@@ -110,6 +110,7 @@
#include <debug.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ssd1306.h>
@@ -156,14 +157,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
diff --git a/nuttx/configs/stm32f4discovery/src/stm32_ug2864ambag01.c b/nuttx/configs/stm32f4discovery/src/stm32_ug2864ambag01.c
index fdc6b88f3..ce735389a 100644
--- a/nuttx/configs/stm32f4discovery/src/stm32_ug2864ambag01.c
+++ b/nuttx/configs/stm32f4discovery/src/stm32_ug2864ambag01.c
@@ -41,6 +41,7 @@
#include <debug.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ug-2864ambag01.h>
@@ -105,14 +106,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
diff --git a/nuttx/configs/stm32f4discovery/src/stm32_ug2864hsweg01.c b/nuttx/configs/stm32f4discovery/src/stm32_ug2864hsweg01.c
index 3366b093d..27db6391a 100644
--- a/nuttx/configs/stm32f4discovery/src/stm32_ug2864hsweg01.c
+++ b/nuttx/configs/stm32f4discovery/src/stm32_ug2864hsweg01.c
@@ -41,6 +41,7 @@
#include <debug.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ssd1306.h>
@@ -105,14 +106,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
diff --git a/nuttx/configs/zp214xpa/src/lpc2148_ug2864ambag01.c b/nuttx/configs/zp214xpa/src/lpc2148_ug2864ambag01.c
index 398fc2c51..d74a035c0 100644
--- a/nuttx/configs/zp214xpa/src/lpc2148_ug2864ambag01.c
+++ b/nuttx/configs/zp214xpa/src/lpc2148_ug2864ambag01.c
@@ -41,6 +41,7 @@
#include <debug.h>
+#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ug-2864ambag01.h>
@@ -110,14 +111,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_nxdrvinit
+ * Name: board_graphics_setup
*
* Description:
* Called by NX initialization logic to configure the OLED.
*
****************************************************************************/
-FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno)
{
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
diff --git a/nuttx/graphics/Kconfig b/nuttx/graphics/Kconfig
index 984c42274..dec4ce5d6 100644
--- a/nuttx/graphics/Kconfig
+++ b/nuttx/graphics/Kconfig
@@ -675,9 +675,10 @@ config NXSTART_EXTERNINIT
---help---
Define to support external display initialization by platform-
specific code. This this option is defined, then nx_start() will
- call up_nxdrvinit(CONFIG_NXSTART_DEVNO) to initialize the graphics
- device. This option is necessary if display is used that cannot be
- initialized using the standard LCD or framebuffer interfaces.
+ call board_graphics_setup(CONFIG_NXSTART_DEVNO) to initialize the
+ graphics device. This option is necessary if display is used that
+ cannot be initialized using the standard LCD or framebuffer
+ interfaces.
config NXSTART_SERVERPRIO
int "NX Server priority"
diff --git a/nuttx/graphics/nxmu/nx_start.c b/nuttx/graphics/nxmu/nx_start.c
index f11d4c5de..589557013 100644
--- a/nuttx/graphics/nxmu/nx_start.c
+++ b/nuttx/graphics/nxmu/nx_start.c
@@ -45,6 +45,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/board.h>
#include <nuttx/kthread.h>
#include <nuttx/nx/nx.h>
@@ -96,10 +97,10 @@ int nx_server(int argc, char *argv[])
#if defined(CONFIG_NXSTART_EXTERNINIT)
/* Use external graphics driver initialization */
- dev = up_nxdrvinit(CONFIG_NXSTART_DEVNO);
+ dev = board_graphics_setup(CONFIG_NXSTART_DEVNO);
if (!dev)
{
- gdbg("ERROR: up_nxdrvinit failed, devno=%d\n", CONFIG_NXSTART_DEVNO);
+ gdbg("ERROR: board_graphics_setup 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 80ec312c6..643a164c0 100644
--- a/nuttx/include/nuttx/board.h
+++ b/nuttx/include/nuttx/board.h
@@ -208,6 +208,29 @@ void board_tsc_teardown(void);
int board_adc_setup(void);
/****************************************************************************
+ * Name: board_graphics_setup
+ *
+ * Description:
+ * If the driver for the graphics device on the platform some unusual
+ * initialization, then this board interface should be provided.
+ *
+ * This is an internal OS interface but may be invoked indirectly from
+ * application-level graphics logic. If CONFIG_LIB_BOARDCTL=y and
+ * CONFIG_BOARDCTL_GRAPHICS=y, then this functions will be invoked via the
+ * (non-standard) boardctl() interface using the commands
+ * BOARDIOC_GRAPHICS_SETUP command.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NX_LCDDRIVER
+struct lcd_dev_s;
+FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno);
+#else
+struct fb_vtable_s;
+FAR struct fb_vtable_s *board_graphics_setup(unsigned int devno);
+#endif
+
+/****************************************************************************
* Name: board_ioctl
*
* Description:
diff --git a/nuttx/include/sys/boardctl.h b/nuttx/include/sys/boardctl.h
index 8da574ec3..5b6741570 100644
--- a/nuttx/include/sys/boardctl.h
+++ b/nuttx/include/sys/boardctl.h
@@ -76,12 +76,19 @@
* CONFIGURATION: CONFIG_LIB_BOARDCTL && CONFIG_BOARDCTL_ADCTEST
* DEPENDENCIES: Board logic must provide board_adc_setup()
*
+ * CMD: BOARDIOC_GRAPHICS_SETUP
+ * DESCRIPTION: Configure graphics that require special initialization
+ * procedures
+ * ARG: A pointer to an instance of struct boardioc_graphics_s
+ * CONFIGURATION: CONFIG_LIB_BOARDCTL && CONFIG_BOARDCTL_GRAPHICS
+ * DEPENDENCIES: Board logic must provide board_adc_setup()
*/
#define BOARDIOC_INIT _BOARDIOC(0x0001)
#define BOARDIOC_TSCTEST_SETUP _BOARDIOC(0x0002)
#define BOARDIOC_TSCTEST_TEARDOWN _BOARDIOC(0x0003)
#define BOARDIOC_ADCTEST_SETUP _BOARDIOC(0x0004)
+#define BOARDIOC_GRAPHICS_SETUP _BOARDIOC(0x0005)
/* If CONFIG_BOARDCTL_IOCTL=y, then boad-specific commands will be support.
* In this case, all commands not recognized by boardctl() will be forwarded
@@ -90,12 +97,32 @@
* User defined board commands may begin with this value:
*/
-#define BOARDIOC_USER _BOARDIOC(0x0005)
+#define BOARDIOC_USER _BOARDIOC(0x0006)
/****************************************************************************
* Public Type Definitions
****************************************************************************/
+/* Structure used to pass arguments and get returned values from the
+ * BOARDIOC_GRAPHICS_SETUP command.
+ */
+
+#ifdef CONFIG_NX_LCDDRIVER
+struct lcd_dev_s; /* Forward reference */
+#else
+struct fb_vtable_s; /* Forward reference */
+#endif
+
+struct boardioc_graphics_s
+{
+ int devno; /* IN: Graphics device number */
+#ifdef CONFIG_NX_LCDDRIVER
+ FAR struct lcd_dev_s *dev; /* OUT: LCD driver instance */
+#else
+ FAR struct fb_vtable_s *dev; /* OUT: Framebuffer driver instance */
+#endif
+};
+
/****************************************************************************
* Public Function Prototypes
****************************************************************************/