summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-12-04 01:56:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-12-04 01:56:50 +0000
commit3d3a0af8b0d724f46656b6a9cb4a883f374558dc (patch)
treed132461991d0bd55066ab71526f7c5830a32308d
parent5076c4bb878881610884750c5a8fd43bdf99c471 (diff)
downloadpx4-nuttx-3d3a0af8b0d724f46656b6a9cb4a883f374558dc.tar.gz
px4-nuttx-3d3a0af8b0d724f46656b6a9cb4a883f374558dc.tar.bz2
px4-nuttx-3d3a0af8b0d724f46656b6a9cb4a883f374558dc.zip
P14201 driver now uses new SPI cmddata method
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3158 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog10
-rw-r--r--nuttx/Documentation/NXGraphicsSubsystem.html4
-rw-r--r--nuttx/Documentation/NuttX.html19
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html2
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_internal.h12
-rw-r--r--nuttx/configs/README.txt2
-rwxr-xr-xnuttx/configs/lm3s6965-ek/nx/defconfig8
-rwxr-xr-xnuttx/configs/lm3s6965-ek/src/up_oled.c28
-rwxr-xr-xnuttx/configs/lm3s8962-ek/nx/defconfig7
-rwxr-xr-xnuttx/configs/lm3s8962-ek/src/up_oled.c28
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/Makefile3
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/up_lcd.c143
-rwxr-xr-xnuttx/configs/sam3u-ek/nsh/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/nx/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/ostest/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/src/up_lcd.c2
-rw-r--r--nuttx/drivers/README.txt2
-rwxr-xr-xnuttx/drivers/lcd/p14201.c27
-rwxr-xr-xnuttx/drivers/lcd/skeleton.c2
-rw-r--r--nuttx/examples/nx/nx_main.c2
-rw-r--r--nuttx/examples/nx/nx_server.c4
-rwxr-xr-xnuttx/graphics/nxglib/lcd/nxglib_copyrectangle.c2
-rwxr-xr-xnuttx/graphics/nxglib/lcd/nxglib_fillrectangle.c2
-rwxr-xr-xnuttx/graphics/nxglib/lcd/nxglib_filltrapezoid.c2
-rwxr-xr-xnuttx/graphics/nxglib/lcd/nxglib_moverectangle.c2
-rwxr-xr-xnuttx/include/nuttx/lcd/lcd.h (renamed from nuttx/include/nuttx/lcd.h)2
-rwxr-xr-xnuttx/include/nuttx/lcd/nokia6100.h112
-rwxr-xr-xnuttx/include/nuttx/lcd/p14201.h (renamed from nuttx/include/nuttx/p14201.h)25
-rw-r--r--nuttx/include/nuttx/nxglib.h2
-rw-r--r--nuttx/include/nuttx/spi.h4
30 files changed, 380 insertions, 84 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 91aa689d6..b13c6f02d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -1381,4 +1381,12 @@
* examples/nsh/nsh_netinit.c -- Fix NSH bug. If CONFIG_NET is selected, but
CONFIG_EXAMPLES_NSH_TELNETD is not selected, then the network is never
initialized and bad things happen if you try to ping.
-
+ * drivers/lcd -- Add header files for the Phillips PCF8833 LCD controller and
+ for the Epson S1D15G10 LCD controller. A driver for the Nokia 6100 LCD is
+ coming.
+ * include/nuttx/spi.h and almost all other SPI files -- Added an optional
+ cmddata() method to the SPI interface. Some devices require and additional
+ out-of-band bit to specify if the next word sent to the device is a command
+ or data. This is typical, for example, in "9-bit" displays where the 9th bit
+ is the CMD/DATA bit. The cmddata method provides selection of command or data.
+ * drivers/lcd/p14201.c -- Now used the cmddata() method of the SPI interface.
diff --git a/nuttx/Documentation/NXGraphicsSubsystem.html b/nuttx/Documentation/NXGraphicsSubsystem.html
index c128c220a..ac67c9614 100644
--- a/nuttx/Documentation/NXGraphicsSubsystem.html
+++ b/nuttx/Documentation/NXGraphicsSubsystem.html
@@ -265,7 +265,7 @@
</li>
<li>
Any LCD-like device than can accept raster line <i>runs</i> through a parallel or serial interface
- (see <code>include/nuttx/lcd.h</code>).
+ (see <code>include/nuttx/lcd/lcd.h</code>).
By default, NX is configured to use the frame buffer driver unless <code>CONFIG_NX_LCDDRIVER</code> is defined =y in your NuttX configuration file.
</li>
</ul>
@@ -2616,7 +2616,7 @@ int nxf_convert_32bpp(FAR uint32_t *dest, uint16_t height,
to know if the pixels pack from the MS to LS or from LS to MS
<dt><code>CONFIG_NX_LCDDRIVER</code>:
<dd>By default, NX builds to use a framebuffer driver (see <code>include/nuttx/fb.h</code>).
- If this option is defined, NX will build to use an LCD driver (see <code>include/nuttx/lcd.h</code>).
+ If this option is defined, NX will build to use an LCD driver (see <code>include/nuttx/lcd/lcd.h</code>).
</li>
</dl>
</ul>
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index beb581b9e..3a946b5d2 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: November 29, 2010</p>
+ <p>Last Updated: December 3, 2010</p>
</td>
</tr>
</table>
@@ -1997,11 +1997,20 @@ nuttx-5.15 2010-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
* arch/arm/src/lpc17xx/lpc17_ssp.c -- Fix compilation errors when SSP1 is
selected.
* configs/olimex-lpc1766stk/nsh -- Enable network and SD/MMC card support in
- NSH. Networking and telnetd interface functional. Still testing SPI-based
- SD/MMC.
- * examples/nsh/nsh_netinit.c -- Fix NSH bug. If CONFIG_NET is selected, but
- CONFIG_EXAMPLES_NSH_TELNETD is not selected, then the network is never
+ NSH. Networking and telnetd interface functional. Still testing SPI-based
+ SD/MMC.
+ * examples/nsh/nsh_netinit.c -- Fix NSH bug. If CONFIG_NET is selected, but
+ CONFIG_EXAMPLES_NSH_TELNETD is not selected, then the network is never
initialized and bad things happen if you try to ping.
+ * drivers/lcd -- Add header files for the Phillips PCF8833 LCD controller and
+ for the Epson S1D15G10 LCD controller. A driver for the Nokia 6100 LCD is
+ coming.
+ * include/nuttx/spi.h and almost all other SPI files -- Added an optional
+ cmddata() method to the SPI interface. Some devices require and additional
+ out-of-band bit to specify if the next word sent to the device is a command
+ or data. This is typical, for example, in "9-bit" displays where the 9th bit
+ is the CMD/DATA bit. The cmddata method provides selection of command or data.
+ * drivers/lcd/p14201.c -- Now used the cmddata() method of the SPI interface.
pascal-2.1 2010-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 9cf518cb5..7e3568225 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -3186,7 +3186,7 @@ build
<li>
<code>CONFIG_NX_LCDDRIVER</code>:
By default, NX builds to use a framebuffer driver (see <code>include/nuttx/fb.h</code>).
- If this option is defined, NX will build to use an LCD driver (see <code>include/nuttx/lcd.h</code>).
+ If this option is defined, NX will build to use an LCD driver (see <code>include/nuttx/lcd/lcd.h</code>).
</li>
<li>
<code>CONFIG_LCD_MAXPOWER</code>:
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_internal.h b/nuttx/arch/arm/src/lm3s/lm3s_internal.h
index 43bcf2d6f..ab96fd081 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_internal.h
+++ b/nuttx/arch/arm/src/lm3s/lm3s_internal.h
@@ -303,13 +303,13 @@
# define GPIO_SSI0_FSS (GPIO_FUNC_PFIO | GPIO_PORTA | 3) /* PA3: SSI0 frame (SSI0Fss) */
# define GPIO_SSI0_RX (GPIO_FUNC_PFINPUT | GPIO_PORTA | 4) /* PA4: SSI0 receive (SSI0Rx) */
# define GPIO_SSI0_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTA | 5) /* PA5: SSI0 transmit (SSI0Tx) */
-# define GPIO_TMR1_CCP (GPIO_FUNC_PFIO | GPIO_PORTA | 6) /* PA6: Capture/Compare/PWM0 (CCP1) */
+# define GPIO_TMR1_CCP (GPIO_FUNC_PFIO | GPIO_PORTA | 6) /* PA6: Capture/Compare/PWM0 (CCP1) */
# define GPIO_PWM1_2 (GPIO_FUNC_PFOUTPUT | GPIO_PORTB | 0) /* PB0: PWM Generator 1, PWM2 */
# define GPIO_PWM1_3 (GPIO_FUNC_PFOUTPUT | GPIO_PORTB | 1) /* PB1: PWM Generator 1, PWM3 */
# define GPIO_I2C0_SCL (GPIO_FUNC_PFOUTPUT | GPIO_PORTB | 2) /* PB2: I2C0 clock (I2C0SCL) */
# define GPIO_I2C0_SDA (GPIO_FUNC_PFODIO | GPIO_PORTB | 3) /* PB3: I2C0 data (I2C0SDA) */
# define GPIO_CMP0_NIN (GPIO_FUNC_PFINPUT | GPIO_PORTB | 4) /* PB4: Analog comparator 0 negative input (C0-) */
-# define GPIO_CMP0_OUT (GPIO_FUNC_PFOUTPUT | GPIO_PORTB | 5) /* PB5: Analog comparator 0 output (C0o) ( differs) */
+# define GPIO_CMP0_OUT (GPIO_FUNC_PFOUTPUT | GPIO_PORTB | 5) /* PB5: Analog comparator 0 output (C0o) (differs) */
# define GPIO_CMP0_PIN (GPIO_FUNC_PFINPUT | GPIO_PORTB | 6) /* PB6: Analog comparator 0 positive input (C0+) */
# define GPIO_JTAG_TRST (GPIO_FUNC_PFINPUT | GPIO_PORTB | 7) /* PB7: JTAG ~TRST */
# define GPIO_JTAG_TCK (GPIO_FUNC_PFINPUT | GPIO_PORTC | 0) /* PC0: JTAG/SWD CLK */
@@ -320,14 +320,14 @@
# define GPIO_JTAG_TDO (GPIO_FUNC_PFOUTPUT | GPIO_PORTC | 3) /* PC3: JTAG TDO */
# define GPIO_JTAG_SWO (GPIO_FUNC_PFOUTPUT | GPIO_PORTC | 3) /* PC3: JTAG SWO */
# define GPIO_QEI0_PHA (GPIO_FUNC_PFINPUT | GPIO_PORTC | 4) /* PC4: QEI module 0 phase A. */
-# define GPIO_QEI0_PHB (GPIO_FUNC_PFINPUT | GPIO_PORTC | 6) /* PC6: QEI module 0 phase B. */
-# define GPIO_CAN0_RX (GPIO_FUNC_PFINPUT | GPIO_PORTD | 0) /* PD0: CAN module RX */
+# define GPIO_QEI0_PHB (GPIO_FUNC_PFINPUT | GPIO_PORTC | 6) /* PC6: QEI module 0 phase B. */
+# define GPIO_CAN0_RX (GPIO_FUNC_PFINPUT | GPIO_PORTD | 0) /* PD0: CAN module RX */
# define GPIO_CAN0_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTD | 1) /* PD1: CAN module TX */
# define GPIO_UART1_RX (GPIO_FUNC_PFINPUT | GPIO_PORTD | 2) /* PD2: UART 1 receive (U1Rx) */
# define GPIO_UART1_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTD | 3) /* PD3: UART 1 transmit (U1Tx) */
# define GPIO_TMR0_CCP (GPIO_FUNC_PFIO | GPIO_PORTD | 4) /* PD4: Capture/Compare/PWM0 (CCP0) */
# define GPIO_PWM_FAULT (GPIO_FUNC_PFINPUT | GPIO_PORTD | 6) /* PD6: PWM Fault */
-# define GPIO_QEI0_IDX (GPIO_FUNC_PFIO | GPIO_PORTD | 7) /* PC7: /* PD0: QEI module 0 index. ) */
+# define GPIO_QEI0_IDX (GPIO_FUNC_PFIO | GPIO_PORTD | 7) /* PC7: QEI module 0 index */
# define GPIO_PWM2_4 (GPIO_FUNC_PFOUTPUT | GPIO_PORTE | 0) /* PE0: PWM Generator 2, PWM4 */
# define GPIO_PWM2_5 (GPIO_FUNC_PFOUTPUT | GPIO_PORTE | 1) /* PE1: PWM Generator 1, PWM5 */
# define GPIO_QEI1_PHB (GPIO_FUNC_PFINPUT | GPIO_PORTE | 2) /* PE2: QEI module 1 phase B. */
@@ -476,7 +476,7 @@ EXTERN int lm3s_ethinitialize(int intf);
/****************************************************************************
* The external functions, lm3s_spiselect, lm3s_spistatus, and
* lm3s_spicmddata must be provided by board-specific logic. These are
- * implementations of the select, status, and cmddaa methods of the SPI
+ * implementations of the select, status, and cmddata methods of the SPI
* interface defined by struct spi_ops_s (see include/nuttx/spi.h).
* All other methods (including up_spiinitialize()) are provided by common
* logic. To use this common SPI logic on your board:
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index bda94884e..b7d20065a 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -739,7 +739,7 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_NX_LCDDRIVER
By default, NX builds to use a framebuffer driver (see
include/nuttx/fb.h). If this option is defined, NX will
- build to use an LCD driver (see include/nuttx/lcd.h).
+ build to use an LCD driver (see include/nuttx/lcd/lcd.h).
CONFIG_LCD_MAXPOWER - The full-on power setting for an LCD
device.
CONFIG_LCD_MAXCONTRAST - The maximum contrast value for an
diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig
index f1c020a00..5b9c03e2e 100755
--- a/nuttx/configs/lm3s6965-ek/nx/defconfig
+++ b/nuttx/configs/lm3s6965-ek/nx/defconfig
@@ -215,6 +215,11 @@ CONFIG_RAW_BINARY=y
CONFIG_HAVE_LIBM=n
#
+# General SPI interface configuration
+#
+CONFIG_SPI_CMDDATA=y
+
+#
# General OS setup
#
# CONFIG_APP_DIR - Identifies the relative path to the directory
@@ -526,7 +531,7 @@ CONFIG_NET_RESOLV_ENTRIES=4
# CONFIG_NX_LCDDRIVER
# By default, NX builds to use a framebuffer driver (see
# include/nuttx/fb.h). If this option is defined, NX will
-# build to use an LCD driver (see include/nuttx/lcd.h).
+# build to use an LCD driver (see include/nuttx/lcd/lcd.h).
# CONFIG_LCD_MAXPOWER - The full-on power setting for an LCD device.
# CONFIG_LCD_MAXCONTRAST - The maximum contrast value for an LCD device.
# CONFIG_NX_MOUSE
@@ -590,6 +595,7 @@ CONFIG_NX_BLOCKING=y
CONFIG_NX_MXSERVERMSGS=32
CONFIG_NX_MXCLIENTMSGS=16
+#
# RiT P14201 OLED Driver Configuration
#
# CONFIG_LCD_P14201 - Enable P14201 support
diff --git a/nuttx/configs/lm3s6965-ek/src/up_oled.c b/nuttx/configs/lm3s6965-ek/src/up_oled.c
index 0493ce475..e508de8de 100755
--- a/nuttx/configs/lm3s6965-ek/src/up_oled.c
+++ b/nuttx/configs/lm3s6965-ek/src/up_oled.c
@@ -45,8 +45,8 @@
#include <errno.h>
#include <nuttx/spi.h>
-#include <nuttx/lcd.h>
-#include <nuttx/p14201.h>
+#include <nuttx/lcd/lcd.h>
+#include <nuttx/lcd/p14201.h>
#include "lm3s_internal.h"
#include "lm3s6965ek_internal.h"
@@ -137,26 +137,36 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
}
/******************************************************************************
- * Name: rit_seldata
+ * Name: lm3s_spicmddata
*
* Description:
* Set or clear the SD1329 D/Cn bit to select data (true) or command
* (false). This function must be provided by platform-specific logic.
+ * This is an implementation of the cmddata method of the SPI
+ * interface defined by struct spi_ops_s (see include/nuttx/spi.h).
*
* Input Parameters:
*
- * devno - A value in the range of 0 throuh CONFIG_P14201_NINTERFACES-1.
- * This allows support for multiple OLED devices.
- * data - true: select data; false: select command
+ * spi - SPI device that controls the bus the device that requires the CMD/
+ * DATA selection.
+ * devid - If there are multiple devices on the bus, this selects which one
+ * to select cmd or data. NOTE: This design restricts, for example,
+ * one one SPI display per SPI bus.
+ * cmd - true: select command; false: select data
*
* Returned Value:
* None
*
******************************************************************************/
-void rit_seldata(unsigned int devno, bool data)
+int lm3s_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
- /* Set GPIO to 1 for data, 0 for command */
+ if (devid == SPIDEV_DISPLAY)
+ {
+ /* Set GPIO to 1 for data, 0 for command */
- lm3s_gpiowrite(OLEDDC_GPIO, data);
+ lm3s_gpiowrite(OLEDDC_GPIO, !cmd);
+ return OK;
+ }
+ return -ENODEV;
}
diff --git a/nuttx/configs/lm3s8962-ek/nx/defconfig b/nuttx/configs/lm3s8962-ek/nx/defconfig
index 4cbdb34b0..5cd426256 100755
--- a/nuttx/configs/lm3s8962-ek/nx/defconfig
+++ b/nuttx/configs/lm3s8962-ek/nx/defconfig
@@ -215,6 +215,11 @@ CONFIG_RAW_BINARY=y
CONFIG_HAVE_LIBM=n
#
+# General SPI interface configuration
+#
+CONFIG_SPI_CMDDATA=y
+
+#
# General OS setup
#
# CONFIG_APP_DIR - Identifies the relative path to the directory
@@ -526,7 +531,7 @@ CONFIG_NET_RESOLV_ENTRIES=4
# CONFIG_NX_LCDDRIVER
# By default, NX builds to use a framebuffer driver (see
# include/nuttx/fb.h). If this option is defined, NX will
-# build to use an LCD driver (see include/nuttx/lcd.h).
+# build to use an LCD driver (see include/nuttx/lcd/lcd.h).
# CONFIG_LCD_MAXPOWER - The full-on power setting for an LCD device.
# CONFIG_LCD_MAXCONTRAST - The maximum contrast value for an LCD device.
# CONFIG_NX_MOUSE
diff --git a/nuttx/configs/lm3s8962-ek/src/up_oled.c b/nuttx/configs/lm3s8962-ek/src/up_oled.c
index 1dd024356..55f768894 100755
--- a/nuttx/configs/lm3s8962-ek/src/up_oled.c
+++ b/nuttx/configs/lm3s8962-ek/src/up_oled.c
@@ -45,8 +45,8 @@
#include <errno.h>
#include <nuttx/spi.h>
-#include <nuttx/lcd.h>
-#include <nuttx/p14201.h>
+#include <nuttx/lcd/lcd.h>
+#include <nuttx/lcd/p14201.h>
#include "lm3s_internal.h"
#include "lm3s8962ek_internal.h"
@@ -137,26 +137,36 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
}
/******************************************************************************
- * Name: rit_seldata
+ * Name: lm3s_spicmddata
*
* Description:
* Set or clear the SD1329 D/Cn bit to select data (true) or command
* (false). This function must be provided by platform-specific logic.
+ * This is an implementation of the cmddata method of the SPI
+ * interface defined by struct spi_ops_s (see include/nuttx/spi.h).
*
* Input Parameters:
*
- * devno - A value in the range of 0 throuh CONFIG_P14201_NINTERFACES-1.
- * This allows support for multiple OLED devices.
- * data - true: select data; false: select command
+ * spi - SPI device that controls the bus the device that requires the CMD/
+ * DATA selection.
+ * devid - If there are multiple devices on the bus, this selects which one
+ * to select cmd or data. NOTE: This design restricts, for example,
+ * one one SPI display per SPI bus.
+ * cmd - true: select command; false: select data
*
* Returned Value:
* None
*
******************************************************************************/
-void rit_seldata(unsigned int devno, bool data)
+int lm3s_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
- /* Set GPIO to 1 for data, 0 for command */
+ if (devid == SPIDEV_DISPLAY)
+ {
+ /* Set GPIO to 1 for data, 0 for command */
- lm3s_gpiowrite(OLEDDC_GPIO, data);
+ lm3s_gpiowrite(OLEDDC_GPIO, !cmd);
+ return OK;
+ }
+ return -ENODEV;
}
diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile
index 4b4df1752..aa89ea9ad 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/Makefile
+++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile
@@ -45,6 +45,9 @@ endif
ifeq ($(CONFIG_APP_DIR),examples/usbstorage)
CSRCS += up_usbstrg.c
endif
+ifeq ($(CONFIG_NX_LCDDRIVER),y)
+CSRCS += up_lcd.c
+endif
AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c b/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
new file mode 100755
index 000000000..4f2a9123e
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
@@ -0,0 +1,143 @@
+/****************************************************************************
+ * config/olimex-lpc1766stk/src/up_lcd.c
+ * arch/arm/src/board/up_lcd.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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
+ * POSSPBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/lcd/lcd.h>
+#include <nuttx/lcd/nokia6100.h>
+
+#include "lpc17_internal.h"
+#include "lpc17stk_internal.h"
+
+#ifdef defined(CONFIG_NX_LCDDRIVER) && defined(CONFIG_LCD_NOKIA6100) && defined(CONFIG_LPC17_SSP0)
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Define the CONFIG_LCD_NOKIADBG to enable detailed debug output (stuff you
+ * would never want to see unless you are debugging this file).
+ *
+ * Verbose debug must also be enabled
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_DEBUG_GRAPHICS
+#endif
+
+#ifndef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_LCD_NOKIADBG
+#endif
+
+#ifdef CONFIG_LCD_NOKIADBG
+# define lcddbg(format, arg...) vdbg(format, ##arg)
+# define lcd_dumpgpio(m) lm3s_dumpgpio(LPC1766STK_LCD_RST, m)
+#else
+# define lcddbg(x...)
+# define lcd_dumpgpio(m)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_nxdrvinit
+ *
+ * Description:
+ * Called NX initialization logic to configure the LCD.
+ *
+ ****************************************************************************/
+
+FAR struct lcd_dev_s *up_nxdrvinit(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");
+ lm3s_configgpio(LPC1766STK_LCD_RST);
+ lm3s_configgpio(LPC1766STK_LCD_BL);
+ lcd_dumpgpio("up_nxdrvinit: After GPIO setup");
+
+ /* Reset the LCD */
+
+ lpc17_gpiowrite(LPC1766STK_LCD_RST, false);
+ up_usdelay(10);
+ lpc17_gpiowrite(LPC1766STK_LCD_RST, true);
+ up_msdelay(5);
+
+ /* Get the SSP port (configure as a Freescale SPI port) */
+
+ spi = up_spiinitialize(0);
+ if (!spi)
+ {
+ glldbg("Failed to initialize SSP port 0\n");
+ }
+ else
+ {
+ /* Bind the SSP port to the LCD */
+
+ dev = nokia_lcdinitialize(spi, devno);
+ if (!dev)
+ {
+ glldbg("Failed to bind SSP port 0 to LCD %d: %d\n", devno);
+ }
+ else
+ {
+ gllvdbg("Bound SSP port 0 to LCD %d\n", devno);
+
+ /* And turn the LCD on (CONFIG_LCD_MAXPOWER should be 1) */
+
+ (void)dev->setpower(dev, CONFIG_LCD_MAXPOWER);
+ return dev;
+ }
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NX_LCDDRIVER && CONFIG_LCD_NOKIA6100 && CONFIG_LPC17_SSP0 */
diff --git a/nuttx/configs/sam3u-ek/nsh/defconfig b/nuttx/configs/sam3u-ek/nsh/defconfig
index 3bf81b9b4..54b1e368c 100755
--- a/nuttx/configs/sam3u-ek/nsh/defconfig
+++ b/nuttx/configs/sam3u-ek/nsh/defconfig
@@ -655,7 +655,7 @@ CONFIG_USBSTRG_REMOVABLE=y
# CONFIG_NX_LCDDRIVER
# By default, NX builds to use a framebuffer driver (see
# include/nuttx/fb.h). If this option is defined, NX will
-# build to use an LCD driver (see include/nuttx/lcd.h).
+# build to use an LCD driver (see include/nuttx/lcd/lcd.h).
# CONFIG_LCD_MAXPOWER - The full-on power setting for an LCD device.
# CONFIG_LCD_MAXCONTRAST - The maximum contrast value for an LCD device.
# CONFIG_NX_MOUSE
diff --git a/nuttx/configs/sam3u-ek/nx/defconfig b/nuttx/configs/sam3u-ek/nx/defconfig
index 06ed91880..c48cf66bd 100755
--- a/nuttx/configs/sam3u-ek/nx/defconfig
+++ b/nuttx/configs/sam3u-ek/nx/defconfig
@@ -664,7 +664,7 @@ CONFIG_USBSTRG_REMOVABLE=y
# CONFIG_NX_LCDDRIVER
# By default, NX builds to use a framebuffer driver (see
# include/nuttx/fb.h). If this option is defined, NX will
-# build to use an LCD driver (see include/nuttx/lcd.h).
+# build to use an LCD driver (see include/nuttx/lcd/lcd.h).
# CONFIG_LCD_MAXPOWER - The full-on power setting for an LCD device.
# CONFIG_LCD_MAXCONTRAST - The maximum contrast value for an LCD device.
# CONFIG_NX_MOUSE
diff --git a/nuttx/configs/sam3u-ek/ostest/defconfig b/nuttx/configs/sam3u-ek/ostest/defconfig
index fe9d96cba..475ab094c 100755
--- a/nuttx/configs/sam3u-ek/ostest/defconfig
+++ b/nuttx/configs/sam3u-ek/ostest/defconfig
@@ -653,7 +653,7 @@ CONFIG_USBSTRG_REMOVABLE=y
# CONFIG_NX_LCDDRIVER
# By default, NX builds to use a framebuffer driver (see
# include/nuttx/fb.h). If this option is defined, NX will
-# build to use an LCD driver (see include/nuttx/lcd.h).
+# build to use an LCD driver (see include/nuttx/lcd/lcd.h).
# CONFIG_LCD_MAXPOWER - The full-on power setting for an LCD device.
# CONFIG_LCD_MAXCONTRAST - The maximum contrast value for an LCD device.
# CONFIG_NX_MOUSE
diff --git a/nuttx/configs/sam3u-ek/src/up_lcd.c b/nuttx/configs/sam3u-ek/src/up_lcd.c
index 971d8d885..8b0a919f7 100755
--- a/nuttx/configs/sam3u-ek/src/up_lcd.c
+++ b/nuttx/configs/sam3u-ek/src/up_lcd.c
@@ -119,7 +119,7 @@
#include <debug.h>
#include <nuttx/arch.h>
-#include <nuttx/lcd.h>
+#include <nuttx/lcd/lcd.h>
#include <nuttx/rgbcolors.h>
#include <arch/irq.h>
diff --git a/nuttx/drivers/README.txt b/nuttx/drivers/README.txt
index 83098506d..1070bcaf9 100644
--- a/nuttx/drivers/README.txt
+++ b/nuttx/drivers/README.txt
@@ -37,7 +37,7 @@ bch/
lcd/
Drivers for parallel and serial LCD and OLED type devices. These
- drivers support interfaces as defined in include/nuttx/lcd.h
+ drivers support interfaces as defined in include/nuttx/lcd/lcd.h
mmcsd/
Support for MMC/SD block drivers. MMC/SD block drivers based on
diff --git a/nuttx/drivers/lcd/p14201.c b/nuttx/drivers/lcd/p14201.c
index 8bf45b3d2..9dd2e6da9 100755
--- a/nuttx/drivers/lcd/p14201.c
+++ b/nuttx/drivers/lcd/p14201.c
@@ -49,8 +49,8 @@
#include <nuttx/arch.h>
#include <nuttx/spi.h>
-#include <nuttx/lcd.h>
-#include <nuttx/p14201.h>
+#include <nuttx/lcd/lcd.h>
+#include <nuttx/lcd/p14201.h>
#include <arch/irq.h>
@@ -84,8 +84,15 @@
* CONFIG_LCD_P14201 - Enable P14201 support
* CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
* CONFIG_LCD_MAXPOWER must be 1
+ *
+ * Required SPI driver settings:
+ * CONFIG_SPI_CMDDATA - Include support for cmd/data selection.
*/
+#ifndef CONFIG_SPI_CMDDATA
+# error "CONFIG_SPI_CMDDATA must be defined in your NuttX configuration"
+#endif
+
/* The P14201 spec says that is supports SPI mode 0,0 only. However,
* somtimes you need to tinker with these things.
*/
@@ -167,8 +174,8 @@
/* Helper Macros **********************************************************************/
-#define rit_sndcmd(p,b,l) rit_sndbytes(p,b,l,false);
-#define rit_snddata(p,b,l) rit_sndbytes(p,b,l,true);
+#define rit_sndcmd(p,b,l) rit_sndbytes(p,b,l,true);
+#define rit_snddata(p,b,l) rit_sndbytes(p,b,l,false);
/* Debug ******************************************************************************/
@@ -207,7 +214,7 @@ static void rit_select(FAR struct spi_dev_s *spi);
static void rit_deselect(FAR struct spi_dev_s *spi);
#endif
static void rit_sndbytes(FAR struct rit_dev_s *priv, FAR const uint8_t *buffer,
- size_t buflen, bool data);
+ size_t buflen, bool cmd);
static void rit_sndcmds(FAR struct rit_dev_s *priv, FAR const uint8_t *table);
/* LCD Data Transfer Methods */
@@ -557,18 +564,18 @@ static void rit_deselect(FAR struct spi_dev_s *spi)
**************************************************************************************/
static void rit_sndbytes(FAR struct rit_dev_s *priv, FAR const uint8_t *buffer,
- size_t buflen, bool data)
+ size_t buflen, bool cmd)
{
FAR struct spi_dev_s *spi = priv->spi;
uint8_t tmp;
- ritdbg("buflen: %d data: %s [%02x %02x %02x]\n",
- buflen, data ? "YES" : "NO", buffer[0], buffer[1], buffer[2] );
+ ritdbg("buflen: %d cmd: %s [%02x %02x %02x]\n",
+ buflen, cmd ? "YES" : "NO", buffer[0], buffer[1], buffer[2] );
DEBUGASSERT(spi);
- /* Clear the D/Cn bit to enable command or data mode */
+ /* Clear/set the D/Cn bit to enable command or data mode */
- rit_seldata(0, data);
+ (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY, cmd);
/* Loop until the entire command/data block is transferred */
diff --git a/nuttx/drivers/lcd/skeleton.c b/nuttx/drivers/lcd/skeleton.c
index 1f9525afd..6f518e63c 100755
--- a/nuttx/drivers/lcd/skeleton.c
+++ b/nuttx/drivers/lcd/skeleton.c
@@ -48,7 +48,7 @@
#include <nuttx/arch.h>
#include <nuttx/spi.h>
-#include <nuttx/lcd.h>
+#include <nuttx/lcd/lcd.h>
#include "up_arch.h"
diff --git a/nuttx/examples/nx/nx_main.c b/nuttx/examples/nx/nx_main.c
index 1320862f3..d35ea4ff0 100644
--- a/nuttx/examples/nx/nx_main.c
+++ b/nuttx/examples/nx/nx_main.c
@@ -52,7 +52,7 @@
#include <debug.h>
#ifdef CONFIG_NX_LCDDRIVER
-# include <nuttx/lcd.h>
+# include <nuttx/lcd/lcd.h>
#else
# include <nuttx/fb.h>
#endif
diff --git a/nuttx/examples/nx/nx_server.c b/nuttx/examples/nx/nx_server.c
index 1f71bf900..8677c0008 100644
--- a/nuttx/examples/nx/nx_server.c
+++ b/nuttx/examples/nx/nx_server.c
@@ -50,7 +50,7 @@
#include <nuttx/nx.h>
#ifdef CONFIG_NX_LCDDRIVER
-# include <nuttx/lcd.h>
+# include <nuttx/lcd/lcd.h>
#else
# include <nuttx/fb.h>
#endif
@@ -149,4 +149,4 @@ int nx_servertask(int argc, char *argv[])
return 3;
}
-#endif /* CONFIG_NX_MULTIUSER */ \ No newline at end of file
+#endif /* CONFIG_NX_MULTIUSER */
diff --git a/nuttx/graphics/nxglib/lcd/nxglib_copyrectangle.c b/nuttx/graphics/nxglib/lcd/nxglib_copyrectangle.c
index 451fdbe21..084fe5cee 100755
--- a/nuttx/graphics/nxglib/lcd/nxglib_copyrectangle.c
+++ b/nuttx/graphics/nxglib/lcd/nxglib_copyrectangle.c
@@ -42,7 +42,7 @@
#include <stdint.h>
#include <assert.h>
-#include <nuttx/lcd.h>
+#include <nuttx/lcd/lcd.h>
#include <nuttx/nxglib.h>
#include "nxglib_bitblit.h"
diff --git a/nuttx/graphics/nxglib/lcd/nxglib_fillrectangle.c b/nuttx/graphics/nxglib/lcd/nxglib_fillrectangle.c
index 50ef7efbe..ddb7fce03 100755
--- a/nuttx/graphics/nxglib/lcd/nxglib_fillrectangle.c
+++ b/nuttx/graphics/nxglib/lcd/nxglib_fillrectangle.c
@@ -42,7 +42,7 @@
#include <sys/types.h>
#include <stdint.h>
-#include <nuttx/lcd.h>
+#include <nuttx/lcd/lcd.h>
#include <nuttx/nxglib.h>
#include "nxglib_bitblit.h"
diff --git a/nuttx/graphics/nxglib/lcd/nxglib_filltrapezoid.c b/nuttx/graphics/nxglib/lcd/nxglib_filltrapezoid.c
index e940d5e1a..c000febb7 100755
--- a/nuttx/graphics/nxglib/lcd/nxglib_filltrapezoid.c
+++ b/nuttx/graphics/nxglib/lcd/nxglib_filltrapezoid.c
@@ -42,7 +42,7 @@
#include <stdint.h>
#include <fixedmath.h>
-#include <nuttx/lcd.h>
+#include <nuttx/lcd/lcd.h>
#include <nuttx/nxglib.h>
#include "nxglib_bitblit.h"
diff --git a/nuttx/graphics/nxglib/lcd/nxglib_moverectangle.c b/nuttx/graphics/nxglib/lcd/nxglib_moverectangle.c
index c6ceb845c..daea90bf6 100755
--- a/nuttx/graphics/nxglib/lcd/nxglib_moverectangle.c
+++ b/nuttx/graphics/nxglib/lcd/nxglib_moverectangle.c
@@ -41,7 +41,7 @@
#include <stdint.h>
-#include <nuttx/lcd.h>
+#include <nuttx/lcd/lcd.h>
#include <nuttx/nxglib.h>
#include "nxglib_bitblit.h"
diff --git a/nuttx/include/nuttx/lcd.h b/nuttx/include/nuttx/lcd/lcd.h
index 03c859dae..9595b89ae 100755
--- a/nuttx/include/nuttx/lcd.h
+++ b/nuttx/include/nuttx/lcd/lcd.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * include/nuttx/lcd.h
+ * include/nuttx/lcd/lcd.h
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/include/nuttx/lcd/nokia6100.h b/nuttx/include/nuttx/lcd/nokia6100.h
new file mode 100755
index 000000000..8c85e8d4e
--- /dev/null
+++ b/nuttx/include/nuttx/lcd/nokia6100.h
@@ -0,0 +1,112 @@
+/****************************************************************************
+ * include/nuttx/lcd/nokia6100.h
+ * Application interface to the Nokia 6100 LCD display
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_NOKIA6100_H
+#define __INCLUDE_NUTTX_NOKIA6100_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <stdbool.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Nokia 6100 Configuration Settings:
+ *
+ * CONFIG_NOKIA6100_SPIMODE - Controls the SPI mode
+ * CONFIG_NOKIA6100_FREQUENCY - Define to use a different bus frequency
+ * CONFIG_NOKIA6100_NINTERFACES - Specifies the number of physical Nokia 6100 devices that
+ * will be supported.
+ *
+ * Required LCD driver settings:
+ * CONFIG_LCD_NOKIA6100 - Enable Nokia 6100 support
+ * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
+ * CONFIG_LCD_MAXPOWER must be 1
+ */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/**************************************************************************************
+ * Name: nokia_lcdinitialize
+ *
+ * Description:
+ * Initialize the NOKIA6100 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 == sleep mode).
+ *
+ * Input Parameters:
+ *
+ * spi - A reference to the SPI driver instance.
+ * devno - A value in the range of 0 throuh CONFIG_NOKIA6100_NINTERFACES-1. This
+ * allows support for multiple LCD devices.
+ *
+ * Returned Value:
+ *
+ * On success, this function returns a reference to the LCD object for the specified
+ * LCD. NULL is returned on any failure.
+ *
+ **************************************************************************************/
+
+struct lcd_dev_s; /* see nuttx/lcd.h */
+struct spi_dev_s; /* see nuttx/spi.h */
+EXTERN FAR struct lcd_dev_s *nokia_lcdinitialize(FAR struct spi_dev_s *spi, unsigned int devno);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_NOKIA6100_H */
diff --git a/nuttx/include/nuttx/p14201.h b/nuttx/include/nuttx/lcd/p14201.h
index ed7943c84..d605551ab 100755
--- a/nuttx/include/nuttx/p14201.h
+++ b/nuttx/include/nuttx/lcd/p14201.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * include/nuttx/p14201.h
+ * include/nuttx/lcd/p14201.h
* Application interface to the RiT P14201 OLED driver
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
@@ -67,6 +67,9 @@
* CONFIG_LCD_P14201 - Enable P14201 support
* CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
* CONFIG_LCD_MAXPOWER must be 1
+ *
+ * Required SPI driver settings:
+ * CONFIG_SPI_CMDDATA - Include support for cmd/data selection.
*/
/* Some important "colors" */
@@ -118,26 +121,6 @@ struct lcd_dev_s; /* see nuttx/lcd.h */
struct spi_dev_s; /* see nuttx/spi.h */
EXTERN FAR struct lcd_dev_s *rit_initialize(FAR struct spi_dev_s *spi, unsigned int devno);
-/**************************************************************************************
- * Name: rit_seldata
- *
- * Description:
- * Set or clear the SD1329 D/Cn bit to select data (true) or command (false). This
- * function must be provided by platform-specific logic.
- *
- * Input Parameters:
- *
- * devno - A value in the range of 0 throuh CONFIG_P14201_NINTERFACES-1. This allows
- * support for multiple OLED devices.
- * data - true: select data; false: select command
- *
- * Returned Value:
- * None
- *
- **************************************************************************************/
-
-EXTERN void rit_seldata(unsigned int devno, bool data);
-
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/nuttx/nxglib.h b/nuttx/include/nuttx/nxglib.h
index ffd3d0ca7..db07b7743 100644
--- a/nuttx/include/nuttx/nxglib.h
+++ b/nuttx/include/nuttx/nxglib.h
@@ -47,7 +47,7 @@
#include <fixedmath.h>
#ifdef CONFIG_NX_LCDDRIVER
-# include <nuttx/lcd.h>
+# include <nuttx/lcd/lcd.h>
#else
# include <nuttx/fb.h>
#endif
diff --git a/nuttx/include/nuttx/spi.h b/nuttx/include/nuttx/spi.h
index a29fd0a78..39d360923 100644
--- a/nuttx/include/nuttx/spi.h
+++ b/nuttx/include/nuttx/spi.h
@@ -211,7 +211,7 @@
*
****************************************************************************/
-#ifndef CONFIG_SPI_CMDDATA
+#ifdef CONFIG_SPI_CMDDATA
# define SPI_CMDDATA(d,id,cmd) ((d)->ops->cmddata(d,id,cmd))
#endif
@@ -376,7 +376,7 @@ struct spi_ops_s
void (*setmode)(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
void (*setbits)(FAR struct spi_dev_s *dev, int nbits);
uint8_t (*status)(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
-#ifndef CONFIG_SPI_CMDDATA
+#ifdef CONFIG_SPI_CMDDATA
int (*cmddata)(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
uint16_t (*send)(FAR struct spi_dev_s *dev, uint16_t wd);