summaryrefslogtreecommitdiff
path: root/nuttx/configs/lpcxpresso-lpc1768
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-17 16:16:28 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-17 16:16:28 +0000
commitbdb3910fa1833282629470e039fe665fc0030527 (patch)
treea2afd3e989c74126e10f2046f268d508529caf7e /nuttx/configs/lpcxpresso-lpc1768
parent2b6d345ad32878d743958ce72ddb408469b8d3a1 (diff)
downloadpx4-nuttx-bdb3910fa1833282629470e039fe665fc0030527.tar.gz
px4-nuttx-bdb3910fa1833282629470e039fe665fc0030527.tar.bz2
px4-nuttx-bdb3910fa1833282629470e039fe665fc0030527.zip
Add support for LPCXpresso OLED
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3518 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/lpcxpresso-lpc1768')
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/README.txt71
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/include/board.h10
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/src/Makefile4
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h29
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/src/up_oled.c183
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c15
6 files changed, 295 insertions, 17 deletions
diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt
index ba65592f7..0b83aef8b 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/README.txt
+++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt
@@ -29,10 +29,10 @@ LCPXpresso LPC1768 Board
P0[3]/RXD0/AD0[6] J6-22
P0[4]/I2SRX-CLK/RD2/CAP2.0 J6-38 CAN_RX2
P0[5]/I2SRX-WS/TD2/CAP2.1 J6-39 CAN_TX2
- P0[6]/I2SRX_SDA/SSEL1/MAT2[0] J6-8 SSEL1
- P0[7]/I2STX_CLK/SCK1/MAT2[1] J6-7 SCK1
+ P0[6]/I2SRX_SDA/SSEL1/MAT2[0] J6-8 SSEL1, OLED CS
+ P0[7]/I2STX_CLK/SCK1/MAT2[1] J6-7 SCK1, OLED SCK
P0[8]/I2STX_WS/MISO1/MAT2[2] J6-6 MISO1
- P0[9]/I2STX_SDA/MOSI1/MAT2[3] J6-5 MOSI1
+ P0[9]/I2STX_SDA/MOSI1/MAT2[3] J6-5 MOSI1, OLED data in
P0[10] J6-40 TXD2/SDA2
P0[11] J6-41 RXD2/SCL2
P0[15]/TXD1/SCK0/SCK J6-13 TXD1/SCK0
@@ -84,7 +84,7 @@ LCPXpresso LPC1768 Board
P2[4]/PWM1.5/DSR1/TRACEDATA[1] J6-46 PWM1.5
P2[5]/PWM1[6]/DTR1/TRACEDATA[0] J6-47 PWM1.6
P2[6]/PCAP1[0]/RI1/TRACECLK J6-48
- P2[7]/RD2/RTS1 J6-49
+ P2[7]/RD2/RTS1 J6-49 OLED command/data
P2[8]/TD2/TXD2 J6-50
P2[9]/USB_CONNECT/RXD2 PAD19 USB Pullup N/A
P2[10]/EINT0/NMI J6-51
@@ -126,8 +126,8 @@ SD Slot
*J55 must be set to provide chip select PIO1_11 signal as the SD slot
chip select.
- USB Device
- ----------
+USB Device
+----------
Base-board J4/J6 LPC1768
Signal Pin Pin
@@ -160,6 +160,65 @@ SD Slot
*P2.9 Connect to a transistor driven USB-D+ pullup on the LPCXpresso board.
+96x64 White OLED with I2C/SPI interface
+---------------------------------------
+ The OLED display can be connected either to the SPI-bus or the I2C-bus.
+
+ Jumper Settings:
+
+ - For the SPI interface (default), insert jumpers in J42, J43, J45 pin1-2
+ and J46 pin 1-2.
+ - For I2C interface, insert jumpers in J45 pin 2-3, J46 pin 2-3 and J47.
+
+ In either case insert a jumper in J44 in order to allow PIO1_10 to control
+ the OLED-voltage.
+
+ Jumper Signal Control:
+
+ J42: Short: SPI Open: I2C (Default: inserted)
+
+ J44: Allow control of OLED voltage (Default: inserted)
+
+ PIO1_10-------->J44 ---------->FAN5331
+
+ Common Reset:
+
+ PIO0_0-RESET ---------------> RES#
+
+ J43: Select OLED chip select
+ J58: For embed (Default: not inserted)
+
+ PIO0_2--------------->J43 ---->CS#
+ PIO2_7--------->J58 ->J43 ---->D/C#
+ PIO0_8-MISO --------^
+
+ J45: Select SPI or I2C clock (Default: SPI clock)
+
+ PIO2_11-SCK---->J45 ----------> D0
+ PIO0_4-SCL------------^
+
+ J46: Select serial data input (Default: SPI MOSI)
+
+ PIO0_9-MOSI---->J46 ----------> D1
+ I2C_SDA---------------^
+
+ J47: Allow I2C bi-directional communications (Default: SPI unidirectional)
+
+ PIO0_5-SDA---->J47 ----------> D2
+
+ LPCXpresso Signals
+
+ ----------------------------+-------+-------------- ----------------------------------------
+ LPC1758 Pin | J4/6 | Base Board Description
+ ----------------------------+-------+-------------- ----------------------------------------
+ P2.1/PWM1.2/RXD1 | 43 | PIO1_10 FAN5331 Power Control (SHDN#)
+ RESET_N | 4 | PIO0_0-RESET OLED reset (RES#) -- Resets EVERYTHING
+ P0.6/I2SRX-SDA/SSEL1/MAT2.0 | 8 | PIO0_2 OLED chip select (CS#)
+ P2.7/RD2/RTS1 | 49 | PIO2_7 OLED command/data (D/C#)
+ P0.7/I2STX-CLK/SCK1/MAT2.1 | 7 | PIO2_11-SCK OLED clock (D0)
+ P0.9/I2STX-SDA/MOSI1/MAT2.3 | 5 | PIO0_9-MOSI OLED data in (D1)
+ ----------------------------+-------+-------------- ----------------------------------------
+
Development Environment
^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/configs/lpcxpresso-lpc1768/include/board.h b/nuttx/configs/lpcxpresso-lpc1768/include/board.h
index 2ebf941e2..fe4dc7144 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/include/board.h
+++ b/nuttx/configs/lpcxpresso-lpc1768/include/board.h
@@ -151,10 +151,10 @@
* P0[3]/RXD0/AD0[6] J6-22
* P0[4]/I2SRX-CLK/RD2/CAP2.0 J6-38 CAN_RX2
* P0[5]/I2SRX-WS/TD2/CAP2.1 J6-39 CAN_TX2
- * P0[6]/I2SRX_SDA/SSEL1/MAT2[0] J6-8 SSEL1
- * P0[7]/I2STX_CLK/SCK1/MAT2[1] J6-7 SCK1
+ * P0[6]/I2SRX_SDA/SSEL1/MAT2[0] J6-8 SSEL1, OLED CS
+ * P0[7]/I2STX_CLK/SCK1/MAT2[1] J6-7 SCK1, OLED SCK
* P0[8]/I2STX_WS/MISO1/MAT2[2] J6-6 MISO1
- * P0[9]/I2STX_SDA/MOSI1/MAT2[3] J6-5 MOSI1
+ * P0[9]/I2STX_SDA/MOSI1/MAT2[3] J6-5 MOSI1, OLED data in
* P0[10] J6-40 TXD2/SDA2
* P0[11] J6-41 RXD2/SCL2
* P0[15]/TXD1/SCK0/SCK J6-13 TXD1/SCK0
@@ -219,13 +219,13 @@
#define GPIO_ENET_MDIO GPIO_ENET_MDIO_1
/* P2[0]/PWM1.1/TXD1 J6-42 PWM1.1 / RGB LED / RS422 RX
- * P2[1]/PWM1.2/RXD1 J6-43 PWM1.2 / RGB LED / RS422 RX
+ * P2[1]/PWM1.2/RXD1 J6-43 PWM1.2 / OLED voltage / RGB LED / RS422 RX
* P2[2]/PWM1.3/CTS1/TRACEDATA[3] J6-44 PWM1.3
* P2[3]/PWM1.4/DCD1/TRACEDATA[2] J6-45 PWM1.4
* P2[4]/PWM1.5/DSR1/TRACEDATA[1] J6-46 PWM1.5
* P2[5]/PWM1[6]/DTR1/TRACEDATA[0] J6-47 PWM1.6
* P2[6]/PCAP1[0]/RI1/TRACECLK J6-48
- * P2[7]/RD2/RTS1 J6-49
+ * P2[7]/RD2/RTS1 J6-49 OLED command/data
* P2[8]/TD2/TXD2 J6-50
* P2[9]/USB_CONNECT/RXD2 PAD19 USB Pullup N/A
* P2[10]/EINT0/NMI J6-51
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile
index dddb65b7c..99f4d3623 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile
@@ -44,6 +44,10 @@ ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
+ifeq ($(CONFIG_NX_LCDDRIVER),y)
+CSRCS += up_oled.c
+endif
+
ifeq ($(CONFIG_USBSTRG),y)
CSRCS += up_usbstrg.c
endif
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h b/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h
index 9d9eb3863..d22161edc 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h
@@ -147,11 +147,11 @@
* CD PIO2_10 52 P2.11 (See LPCXPRESSO_SD_CD)
*/
-#define LPCXPRESSO_SD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT2 | GPIO_PIN2)
+#define LPCXPRESSO_SD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT2 | GPIO_PIN2)
#ifdef CONFIG_GPIO_IRQ
-# define LPCXPRESSO_SD_CD (GPIO_INTBOTH | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+# define LPCXPRESSO_SD_CD (GPIO_INTBOTH | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
#else
-# define LPCXPRESSO_SD_CD (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+# define LPCXPRESSO_SD_CD (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
#endif
/* USB:
@@ -179,13 +179,30 @@
* - The standard USB LED (P1.18) is not connected.
*/
-#define LPCXPRESSO_USB_CONNECT (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN21)
+#define LPCXPRESSO_USB_CONNECT (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN21)
#ifdef CONFIG_GPIO_IRQ
-# define LPCXPRESSO_USB_VBUSSENSE (GPIO_INTBOTH | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+# define LPCXPRESSO_USB_VBUSSENSE (GPIO_INTBOTH | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
#else
-# define LPCXPRESSO_USB_VBUSSENSE (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+# define LPCXPRESSO_USB_VBUSSENSE (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
#endif
+/* 96x64 White OLED with I2C/SPI interface
+ *
+ * ----------------------------+-------+-------------- -----------------------------
+ * LPC1758 Pin | J4/6 | Base Board Description
+ * ----------------------------+-------+-------------- -----------------------------
+ * P2.1/PWM1.2/RXD1 | 43 | PIO1_10 FAN5331 Power Control (SHDN#)
+ * P0.6/I2SRX-SDA/SSEL1/MAT2.0 | 8 | PIO0_2 OLED chip select (CS#)
+ * P2.7/RD2/RTS1 | 49 | PIO2_7 OLED command/data (D/C#)
+ * P0.7/I2STX-CLK/SCK1/MAT2.1 | 7 | PIO2_11-SCK OLED clock (D0)
+ * P0.9/I2STX-SDA/MOSI1/MAT2.3 | 5 | PIO0_9-MOSI OLED data in (D1)
+ * ----------------------------+-------+-------------- -----------------------------
+ */
+
+#define LPCXPRESSO_OLED_POWER (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT2 | GPIO_PIN1)
+#define LPCXPRESSO_OLED_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN6)
+#define LPCXPRESSO_OLED_DC (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN7)
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c
new file mode 100755
index 000000000..41ab01b82
--- /dev/null
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c
@@ -0,0 +1,183 @@
+/****************************************************************************
+ * config/lpcxpresso-lpc1768/src/up_oled.c
+ * arch/arm/src/board/up_oled.c
+ *
+ * Copyright (C) 2011 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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/p14201.h>
+
+#include "lpc17_internal.h"
+#include "lpcxpresso_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* This module is only built if CONFIG_NX_LCDDRIVER is selected. In this
+ * case, it would be an error if SSP1 is not also enabled.
+ */
+
+#ifndef CONFIG_LPC17_SSP1
+# error "The OLED driver required CONFIG_LPC17_SSP1 in the configuration"
+#endif
+
+/* Debug ********************************************************************/
+/* Define the CONFIG_LCD_RITDEBUG 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_RITDEBUG
+#endif
+
+#ifdef CONFIG_LCD_RITDEBUG
+# define ritdbg(format, arg...) vdbg(format, ##arg)
+# define oleddc_dumpgpio(m) lm3s_dumpgpio(LPCXPRESSO_OLED_POWER, m)
+# define oledcs_dumpgpio(m) lm3s_dumpgpio(LPCXPRESSO_OLED_CS, m)
+#else
+# define ritdbg(x...)
+# define oleddc_dumpgpio(m)
+# define oledcs_dumpgpio(m)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_nxdrvinit
+ *
+ * Description:
+ * Called by NX initialization logic to configure the OLED.
+ *
+ ****************************************************************************/
+
+FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+{
+ FAR struct spi_dev_s *spi;
+ FAR struct lcd_dev_s *dev;
+
+ /* Configure the OLED GPIOs. For the SPI interface, insert jumpers in J42,
+ * J43, J45 pin1-2 and J46 pin 1-2.
+ */
+
+ oledcs_dumpgpio("up_nxdrvinit: After OLED CS setup");
+ oleddc_dumpgpio("up_nxdrvinit: 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");
+
+ /* Get the SSI port (configure as a Freescale SPI port) */
+
+ spi = up_spiinitialize(1);
+ if (!spi)
+ {
+ glldbg("Failed to initialize SSI port 1\n");
+ }
+ else
+ {
+ /* Bind the SSI port to the OLED */
+
+ dev = rit_initialize(spi, devno);
+ if (!dev)
+ {
+ glldbg("Failed to bind SSI port 1 to OLED %d: %d\n", devno);
+ }
+ else
+ {
+ gllvdbg("Bound SSI port 1 to OLED %d\n", devno);
+
+ /* And turn the OLED on (CONFIG_LCD_MAXPOWER should be 1) */
+
+ (void)dev->setpower(dev, CONFIG_LCD_MAXPOWER);
+ return dev;
+ }
+ }
+ return NULL;
+}
+
+/******************************************************************************
+ * 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:
+ *
+ * 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
+ *
+ ******************************************************************************/
+
+int lm3s_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
+{
+ if (devid == SPIDEV_DISPLAY)
+ {
+ /* Set GPIO to 1 for data, 0 for command */
+
+ lm3s_gpiowrite(OLEDDC_GPIO, !cmd);
+ return OK;
+ }
+ return -ENODEV;
+}
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c
index b15d97358..6c81c7a0d 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c
@@ -115,6 +115,14 @@ void weak_function lpc17_sspinitialize(void)
#ifdef CONFIG_LPC17_SSP1
(void)lpc17_configgpio(LPCXPRESSO_SD_CS);
(void)lpc17_configgpio(LPCXPRESSO_SD_CD);
+
+ /* Configure chip select for the OLED. For the SPI interface, insert jumpers in
+ * J42, J43, J45 pin1-2 and J46 pin 1-2.
+ */
+
+#ifdef CONFIG_NX_LCDDRIVER
+ (void)lpc17_configgpio(LPCXPRESSO_OLED_CS);
+#endif
#endif
ssp_dumpgpio("lpc17_sspinitialize() Exit");
@@ -175,7 +183,14 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel
(void)lpc17_gpiowrite(LPCXPRESSO_SD_CS, !selected);
}
+#ifdef CONFIG_NX_LCDDRIVER
+ else if (devid == SPIDEV_DISPLAY)
+ {
+ /* Assert the CS pin to the OLED display */
+ (void)lpc17_gpiowrite(LPCXPRESSO_OLED_CS, !selected);
+ }
+#endif
ssp_dumpgpio("lpc17_spi1select() Exit");
}