aboutsummaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/Kconfig3
-rw-r--r--nuttx/drivers/input/Kconfig19
-rw-r--r--nuttx/drivers/lcd/Make.defs4
-rw-r--r--nuttx/drivers/lcd/README.txt78
-rw-r--r--nuttx/drivers/lcd/ug-2864ambag01.c8
-rw-r--r--nuttx/drivers/lcd/ug-2864hsweg01.c1218
-rw-r--r--nuttx/drivers/mmcsd/Kconfig6
-rw-r--r--nuttx/drivers/mtd/Make.defs3
-rw-r--r--nuttx/drivers/usbdev/composite.c4
-rw-r--r--nuttx/drivers/usbdev/pl2303.c20
-rw-r--r--nuttx/drivers/usbhost/Kconfig64
-rw-r--r--nuttx/drivers/usbhost/usbhost_hidkbd.c405
12 files changed, 1713 insertions, 119 deletions
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index 8302d21b7..3ced01b58 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -140,7 +140,8 @@ menuconfig SPI
bool "SPI Driver Support"
default n
---help---
- This selection enables building of the "upper-half" SPI driver.
+ This selection enables selection of common SPI options. This option
+ should be enabled by all platforms that support SPI interfaces.
See include/nuttx/spi.h for further SPI driver information.
if SPI
diff --git a/nuttx/drivers/input/Kconfig b/nuttx/drivers/input/Kconfig
index 1f345ee14..6da3a9f39 100644
--- a/nuttx/drivers/input/Kconfig
+++ b/nuttx/drivers/input/Kconfig
@@ -123,6 +123,25 @@ config STMPE811_I2C
endchoice
+config STMPE811_ACTIVELOW
+ bool "Active Low Interrupt"
+ default n
+ ---help---
+ The STMPE811 interrupt is provided by a discrete input (usually a
+ GPIO interrupt on most MCU architectures). This setting determines
+ whether the interrupt is active high (or rising edge triggered) or
+ active low (or falling edge triggered). Default: Active
+ high/rising edge.
+
+config STMPE811_EDGE
+ bool "Edge triggered Interrupt"
+ default n
+ ---help---
+ The STMPE811 interrupt is provided by a discrete input (usually a
+ GPIO interrupt on most MCU architectures). This setting determines
+ whether the interrupt is edge or level triggered. Default: Level
+ triggered.
+
config STMPE811_MULTIPLE
bool "Multiple STMPE811 Devices"
default n
diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs
index 1b445b6a7..067f76f4e 100644
--- a/nuttx/drivers/lcd/Make.defs
+++ b/nuttx/drivers/lcd/Make.defs
@@ -51,6 +51,10 @@ ifeq ($(CONFIG_LCD_UG2864AMBAG01),y)
CSRCS += ug-2864ambag01.c
endif
+ifeq ($(CONFIG_LCD_UG2864HSWEG01),y)
+ CSRCS += ug-2864hsweg01.c
+endif
+
ifeq ($(CONFIG_LCD_UG9664HSWAG01),y)
CSRCS += ug-9664hswag01.c
endif
diff --git a/nuttx/drivers/lcd/README.txt b/nuttx/drivers/lcd/README.txt
index 77ae536b2..0472043e6 100644
--- a/nuttx/drivers/lcd/README.txt
+++ b/nuttx/drivers/lcd/README.txt
@@ -119,47 +119,71 @@ that support additional LCDs. LCD drivers in the configuration directory
if they support some differ LCD interface (such as a parallel interface)
that makes then less re-usable:
- configs/compal_e99/src/ssd1783.c
+ SSD1783 Drivers:
- SSD1783
+ configs/compal_e99/src/ssd1783.c
- configs/hymini-stm32v/src/ssd1289.c. See also drivers/lcd/ssd1298.c
- above.
+ SSD1289 Drivers:
+
+ configs/hymini-stm32v/src/ssd1289.c. See also drivers/lcd/ssd1298.c
+ above.
+ configs/stm32f4discovery/src/up_ssd1289.c. This examples is the
+ bottom half for the SSD1289 driver at drivers/lcd/ssd1289.c
+ configs/hymini-stm32v/src/ssd1289.c. See also drivers/lcd/ssd1298.c
+ above.
+ configs/shenzhou/src/up_ssd1289.c
+
+ kwikstik-k40:
- SSD1289
+ configs/kwikstik-k40/src/up_lcd.c. Don't waste your time. This is
+ just a stub.
- configs/kwikstik-k40/src/up_lcd.c. Don't waste your time. This is
- just a stub.
+ Nokia LCD Drivers:
- configs/olimex-lpc1766stk/src/up_lcd.c. This examples is the
- bottom half for the SSD1289 driver at drivers/lcd/nokia6100.c.
- This was never completedly debugged ... there are probably issues
- with that nasty 9-bit SPI interfaces.
+ configs/olimex-lpc1766stk/src/up_lcd.c. This examples is the
+ bottom half for the driver at drivers/lcd/nokia6100.c.
+ This was never completedly debugged ... there are probably issues
+ with that nasty 9-bit SPI interfaces.
- configs/sam3u-ek/src/up_lcd.c
-
- The SAM3U-EK developement board features a TFT/Transmissive color
- LCD module with touch-screen, FTM280C12D, with integrated driver IC
- HX8346.
+ HX8346:
+
+ configs/sam3u-ek/src/up_lcd.c. The SAM3U-EK developement board features
+ a TFT/Transmissive color LCD module with touch-screen, FTM280C12D,
+ with integrated driver IC HX8346.
- configs/skp16c26/src/up_lcd.c. Untested alphanumeric LCD driver.
+ HX8347:
- configs/stm3210e-eval/src/up_lcd.c
+ configs/pic32mx7mmb/src/up_mio283qt2.c. This driver is for the MI0283QT-2
+ LCD from Multi-Inno Technology Co., Ltd. This LCD is based on the Himax
+ HX8347-D LCD controller.
+
+ ILI93xx and Similar:
- This driver supports the following LCDs:
+ configs/stm3210e-eval/src/up_lcd.c. This driver supports the following
+ LCDs:
- 1. Ampire AM-240320LTNQW00H
- 2. Orise Tech SPFD5408B
- 3. RenesasSP R61580
+ 1. Ampire AM-240320LTNQW00H
+ 2. Orise Tech SPFD5408B
+ 3. RenesasSP R61580
- configs/stm3220g-eval/src/up_lcd.c and configs/stm3240g-eval/src/up_lcd.c.
- AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) and
- AM-240320D5TOQW01H (LCD_ILI9325)
+ configs/stm3220g-eval/src/up_lcd.c and configs/stm3240g-eval/src/up_lcd.c.
+ AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) and
+ AM-240320D5TOQW01H (LCD_ILI9325)
+ configs/shenzhou/src/up_ili93xx.c. Another ILI93xx driver.
- configs/stm32f4discovery/src/up_ssd1289.c. This examples is the
- bottom half for the SSD1289 driver at drivers/lcd/ssd1289.c
+ OLEDs:
+
+ configs/stm32f4discovery/src/up_ug2864ambag01.c
+ configs/stm32f4discovery/src/up_ug2864hsweg01.c
+ configs/zp214xpa/src/up_ug2864ambag01.c
+
+ Alphnumeric LCD Displays:
+
+ configs/skp16c26/src/up_lcd.c. Untested alphanumeric LCD driver.
+ configs/pcblogic-pic32/src/up_lcd1602.c
graphics/
=========
See also the usage of the LCD driver in the graphics/ directory.
+
diff --git a/nuttx/drivers/lcd/ug-2864ambag01.c b/nuttx/drivers/lcd/ug-2864ambag01.c
index 2a47b38eb..6b3d6d5a8 100644
--- a/nuttx/drivers/lcd/ug-2864ambag01.c
+++ b/nuttx/drivers/lcd/ug-2864ambag01.c
@@ -428,7 +428,7 @@ static inline void ug2864ambag01_configspi(FAR struct spi_dev_s *spi)
SPI_SETMODE(spi, CONFIG_UG2864AMBAG01_SPIMODE);
SPI_SETBITS(spi, 8);
- SPI_SETFREQUENCY(spi, CONFIG_UG2864AMBAG01_FREQUENCY)
+ SPI_SETFREQUENCY(spi, CONFIG_UG2864AMBAG01_FREQUENCY);
}
#endif
@@ -1035,7 +1035,7 @@ FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsign
/* Configure the SPI */
- ug2864ambag01_configspi(spi)
+ ug2864ambag01_configspi(spi);
/* Lock and select device */
@@ -1148,8 +1148,8 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color)
/* Transfer one page of the selected color */
- (void)SPI_SNDBLOCK(priv->spi, &priv->fb[page * UG2864AMBAG01_XRES],
- UG2864AMBAG01_XRES);
+ (void)SPI_SNDBLOCK(priv->spi, &priv->fb[page * UG2864AMBAG01_XRES],
+ UG2864AMBAG01_XRES);
}
/* De-select and unlock the device */
diff --git a/nuttx/drivers/lcd/ug-2864hsweg01.c b/nuttx/drivers/lcd/ug-2864hsweg01.c
new file mode 100644
index 000000000..02a59b104
--- /dev/null
+++ b/nuttx/drivers/lcd/ug-2864hsweg01.c
@@ -0,0 +1,1218 @@
+/**************************************************************************************
+ * drivers/lcd/ug-2864hsweg01.c
+ * Driver for Univision UG-2864HSWEG01 OLED display (wih SSD1306 controller) in SPI
+ * mode
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References:
+ * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID:
+ * UG-2864HSWEG01, Doc No: SAS1-9046-B, Univision Technology Inc.
+ * 2. SSD1306, 128 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with
+ * Controller, Solomon Systech
+ *
+ * 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.
+ *
+ **************************************************************************************/
+/**************************************************************************************
+ * Device memory organization:
+ *
+ * +----------------------------+
+ * | Column |
+ * --------+----+---+---+---+-...-+-----+
+ * Page | 0 | 1 | 2 | 3 | ... | 127 |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 0 | D0 | X | | | | |
+ * | D1 | X | | | | |
+ * | D2 | X | | | | |
+ * | D3 | X | | | | |
+ * | D4 | X | | | | |
+ * | D5 | X | | | | |
+ * | D6 | X | | | | |
+ * | D7 | X | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 1 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 2 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 3 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 4 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 5 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 6 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ * Page 7 | | | | | | |
+ * --------+----+---+---+---+-...-+-----+
+ *
+ * -----------------------------------+---------------------------------------
+ * Landscape Display: | Reverse Landscape Display:
+ * --------+-----------------------+ | --------+---------------------------+
+ * | Column | | | Column |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 0 | 0 | 1 | 2 | | 127 | | Page 7 | 127 | 126 | 125 | | 0 |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 1 | V | | Page 6 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 2 | V | | Page 5 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 3 | V | | Page 4 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 4 | V | | Page 3 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 5 | V | | Page 2 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 6 | V | | Page 1 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * Page 7 | V | | Page 0 | ^ |
+ * --------+---+---+---+-...-+-----+ | --------+-----+-----+-----+-...-+---+
+ * -----------------------------------+---------------------------------------
+ *
+ * -----------------------------------+---------------------------------------
+ * Portrait Display: | Reverse Portrait Display:
+ * -----------+---------------------+ | -----------+---------------------+
+ * | Page | | | Page |
+ * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+
+ * Column 0 | 0 | 1 | 2 | | 7 | | Column 127 | 7 | 6 | 5 | | 0 |
+ * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+
+ * Column 1 | > > > > > | | Column 126 | |
+ * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+
+ * Column 2 | | | Column 125 | |
+ * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+
+ * ... | | | ... | |
+ * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+
+ * Column 127 | | | Column 0 | < < < < < |
+ * -----------+---+---+---+-...-+---+ | -----------+---+---+---+-...-+---+
+ * -----------------------------------+----------------------------------------
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/lcd/lcd.h>
+#include <nuttx/lcd/ug-2864hsweg01.h>
+
+#include <arch/irq.h>
+
+#ifdef CONFIG_LCD_UG2864HSWEG01
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+/* Configuration **********************************************************************/
+/* Limitations of the current configuration that I hope to fix someday */
+
+#if CONFIG_UG2864HSWEG01_NINTERFACES != 1
+# warning "This implementation supports only a single OLED device"
+# undef CONFIG_UG2864HSWEG01_NINTERFACES
+# define CONFIG_UG2864HSWEG01_NINTERFACES 1
+#endif
+
+#if defined(CONFIG_LCD_PORTRAIT) || defined(CONFIG_LCD_RPORTRAIT)
+# warning "No support yet for portrait modes"
+# define CONFIG_LCD_LANDSCAPE 1
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RLANDSCAPE
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_RLANDSCAPE)
+# warning "Reverse landscape mode is untested and, hence, probably buggy"
+#endif
+
+/* SSD1306 Commands *******************************************************************/
+
+#define SSD1306_SETCOLL(ad) (0x00 | ((ad) & 0x0f)) /* Set Lower Column Address: (00h - 0fh) */
+#define SSD1306_SETCOLH(ad) (0x10 | ((ad) & 0x0f)) /* Set Higher Column Address: (10h - 1fh) */
+#define SSD1306_STARTLINE(ln) (0x40 | ((ln) & 0x3f)) /* Set Display Start Line: (40h - 7fh) */
+#define SSD1306_CONTRAST_MODE (0x81) /* Set Contrast Control Register: (Double Bytes Command) */
+# define SSD1306_CONTRAST(c) (c)
+#define SSD1306_SEGREMAP(m) (0xa0 | ((m) & 0x01)) /* Set Segment Re-map: (a0h - a1h) */
+# define SSD1306_REMAPRIGHT SSD1306_SEGREMAP(0) /* Right rotation */
+# define SSD1306_REMAPPLEFT SSD1306_SEGREMAP(1) /* Left rotation */
+#define SSD1306_EDISPOFFON(s) (0xa4 | ((s) & 0x01)) /* Set Entire Display OFF/ON: (a4h - a5h) */
+# define SSD1306_EDISPOFF SSD1306_EDISPOFFON(0) /* Display off */
+# define SSD1306_EDISPON SSD1306_EDISPOFFON(1) /* Display on */
+#define SSD1306_NORMREV(s) (0xa6 | ((s) & 0x01)) /* Set Normal/Reverse Display: (a6h -a7h) */
+# define SSD1306_NORMAL SSD1306_NORMREV(0) /* Normal display */
+# define SSD1306_REVERSE SSD1306_NORMREV(1) /* Reverse display */
+#define SSD1306_MRATIO_MODE (0xa8) /* Set Multiplex Ration: (Double Bytes Command) */
+# define SSD1306_MRATIO(d) ((d) & 0x3f)
+#define SSD1306_DCDC_MODE (0xad) /* Set DC-DC OFF/ON: (Double Bytes Command) */
+# define SSD1306_DCDC_OFF (0x8a)
+# define SSD1306_DCDC_ON (0x8b)
+
+#define SSD1306_DISPOFFON(s) (0xae | ((s) & 0x01)) /* Display OFF/ON: (aeh - afh) */
+# define SSD1306_DISPOFF SSD1306_DISPOFFON(0) /* Display off */
+# define SSD1306_DISPON SSD1306_DISPOFFON(1) /* Display on */
+#define SSD1306_PAGEADDR(a) (0xb0 | ((a) & 0x0f)) /* Set Page Address: (b0h - b7h) */
+#define SSD1306_SCANDIR(d) (0xc0 | ((d) & 0x08)) /* Set Common Output Scan Direction: (c0h - c8h) */
+# define SSD1306_SCANFROMCOM0 SSD1306_SCANDIR(0x00) /* Scan from COM[0] to COM[n-1]*/
+# define SSD1306_SCANTOCOM0 SSD1306_SCANDIR(0x08) /* Scan from COM[n-1] to COM[0] */
+#define SSD1306_DISPOFFS_MODE (0xd3) /* Set Display Offset: (Double Bytes Command) */
+# define SSD1306_DISPOFFS(o) ((o) & 0x3f)
+#define SSD1306_CLKDIV_SET (0xd5) /* Set Display Clock Divide Ratio/Oscillator Frequency: (Double Bytes Command) */
+# define SSD1306_CLKDIV(f,d) ((((f) & 0x0f) << 4) | ((d) & 0x0f))
+#define SSD1306_CHRGPER_SET (0xd9) /* Set Dis-charge/Pre-charge Period: (Double Bytes Command) */
+# define SSD1306_CHRGPER(d,p) ((((d) & 0x0f) << 4) | ((p) & 0x0f))
+#define SSD1306_CMNPAD_CONFIG (0xda) /* Set Common pads hardware configuration: (Double Bytes Command) */
+# define SSD1306_CMNPAD(c) ((0x02) | ((c) & 0x10))
+#define SSD1306_VCOM_SET (0xdb) /* Set VCOM Deselect Level: (Double Bytes Command) */
+# define SSD1306_VCOM(v) (v)
+
+#define SSD1306_CHRPUMP_SET (0x8d) /* Charge Pump Setting */
+# define SSD1306_CHRPUMP_ON (0x14)
+# define SSD1306_CHRPUMP_OFF (0x10)
+
+#define SSD1306_RMWSTART (0xe0) /* Read-Modify-Write: (e0h) */
+#define SSD1306_NOP (0xe3) /* NOP: (e3h) */
+#define SSD1306_END (0xee) /* End: (eeh) */
+
+#define SSD1306_WRDATA(d) (d) /* Write Display Data */
+#define SSD1306_STATUS_BUSY (0x80) /* Read Status */
+#define SSD1306_STATUS_ONOFF (0x40)
+#define SSD1306_RDDATA(d) (d) /* Read Display Data */
+
+/* Color Properties *******************************************************************/
+/* Display Resolution
+ *
+ * The SSD1306 display controller can handle a resolution of 132x64. The UG-2864HSWEG01
+ * on the base board is 128x64.
+ */
+
+#define UG2864HSWEG01_DEV_XRES 128 /* Only 128 of 131 columns used */
+#define UG2864HSWEG01_DEV_YRES 64 /* 8 pages each 8 rows */
+#define UG2864HSWEG01_DEV_XOFFSET 2 /* Offset to logical column 0 */
+#define UG2864HSWEG01_DEV_PAGES 8 /* 8 pages */
+
+#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE)
+# define UG2864HSWEG01_XRES UG2864HSWEG01_DEV_XRES
+# define UG2864HSWEG01_YRES UG2864HSWEG01_DEV_YRES
+#else
+# define UG2864HSWEG01_XRES UG2864HSWEG01_DEV_YRES
+# define UG2864HSWEG01_YRES UG2864HSWEG01_DEV_XRES
+#endif
+
+/* Color depth and format */
+
+#define UG2864HSWEG01_BPP 1
+#define UG2864HSWEG01_COLORFMT FB_FMT_Y1
+
+/* Bytes per logical row and actual device row */
+
+#define UG2864HSWEG01_XSTRIDE (UG2864HSWEG01_XRES >> 3)
+#define UG2864HSWEG01_YSTRIDE (UG2864HSWEG01_YRES >> 3)
+
+/* Default contrast */
+
+#define UG2864HSWEG01_CONTRAST (128)
+
+/* The size of the shadow frame buffer or one row buffer.
+ *
+ * Frame buffer size: 128 columns x 64 rows / 8 bits-per-pixel
+ * Row size: 128 columns x 8 rows-per-page / 8 bits-per-pixel
+ */
+
+#define UG2864HSWEG01_FBSIZE (UG2864HSWEG01_XSTRIDE * UG2864HSWEG01_YRES)
+#define UG2864HSWEG01_ROWSIZE (UG2864HSWEG01_XSTRIDE)
+
+/* Bit helpers */
+
+#define LS_BIT (1 << 0)
+#define MS_BIT (1 << 7)
+
+/* Debug ******************************************************************************/
+
+#ifdef CONFIG_DEBUG_LCD
+# define lcddbg(format, arg...) dbg(format, ##arg)
+# define lcdvdbg(format, arg...) vdbg(format, ##arg)
+#else
+# define lcddbg(x...)
+# define lcdvdbg(x...)
+#endif
+
+/**************************************************************************************
+ * Private Type Definition
+ **************************************************************************************/
+
+/* This structure describes the state of this driver */
+
+struct ug2864hsweg01_dev_s
+{
+ struct lcd_dev_s dev; /* Publically visible device structure */
+
+ /* Private LCD-specific information follows */
+
+ FAR struct spi_dev_s *spi; /* Cached SPI device reference */
+ uint8_t contrast; /* Current contrast setting */
+ bool on; /* true: display is on */
+
+
+ /* The SSD1306 does not support reading from the display memory in SPI mode.
+ * Since there is 1 BPP and access is byte-by-byte, it is necessary to keep
+ * a shadow copy of the framebuffer memory. At 128x64, this amounts to 1KB.
+ */
+
+ uint8_t fb[UG2864HSWEG01_FBSIZE];
+};
+
+/**************************************************************************************
+ * Private Function Protototypes
+ **************************************************************************************/
+
+/* Low-level SPI helpers */
+
+#ifdef CONFIG_SPI_OWNBUS
+static inline void ug2864hsweg01_configspi(FAR struct spi_dev_s *spi);
+# define ug2864hsweg01_lock(spi)
+# define ug2864hsweg01_unlock(spi)
+#else
+# define ug2864hsweg01_configspi(spi)
+static void ug2864hsweg01_lock(FAR struct spi_dev_s *spi);
+static void ug2864hsweg01_unlock(FAR struct spi_dev_s *spi);
+#endif
+
+/* LCD Data Transfer Methods */
+
+static int ug2864hsweg01_putrun(fb_coord_t row, fb_coord_t col,
+ FAR const uint8_t *buffer, size_t npixels);
+static int ug2864hsweg01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels);
+
+/* LCD Configuration */
+
+static int ug2864hsweg01_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo);
+static int ug2864hsweg01_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 ug2864hsweg01_getpower(struct lcd_dev_s *dev);
+static int ug2864hsweg01_setpower(struct lcd_dev_s *dev, int power);
+static int ug2864hsweg01_getcontrast(struct lcd_dev_s *dev);
+static int ug2864hsweg01_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[UG2864HSWEG01_ROWSIZE];
+
+/* This structure describes the overall LCD video controller */
+
+static const struct fb_videoinfo_s g_videoinfo =
+{
+ .fmt = UG2864HSWEG01_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */
+ .xres = UG2864HSWEG01_XRES, /* Horizontal resolution in pixel columns */
+ .yres = UG2864HSWEG01_YRES, /* 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 = ug2864hsweg01_putrun, /* Put a run into LCD memory */
+ .getrun = ug2864hsweg01_getrun, /* Get a run from LCD memory */
+ .buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */
+ .bpp = UG2864HSWEG01_BPP, /* Bits-per-pixel */
+};
+
+/* This is the OLED driver instance (only a single device is supported for now) */
+
+static struct ug2864hsweg01_dev_s g_oleddev =
+{
+ .dev =
+ {
+ /* LCD Configuration */
+
+ .getvideoinfo = ug2864hsweg01_getvideoinfo,
+ .getplaneinfo = ug2864hsweg01_getplaneinfo,
+
+ /* LCD RGB Mapping -- Not supported */
+ /* Cursor Controls -- Not supported */
+
+ /* LCD Specific Controls */
+
+ .getpower = ug2864hsweg01_getpower,
+ .setpower = ug2864hsweg01_setpower,
+ .getcontrast = ug2864hsweg01_getcontrast,
+ .setcontrast = ug2864hsweg01_setcontrast,
+ },
+};
+
+/**************************************************************************************
+ * Private Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_configspi
+ *
+ * Description:
+ * Configure the SPI for use with the UG-2864HSWEG01
+ *
+ * Input Parameters:
+ * spi - Reference to the SPI driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ **************************************************************************************/
+
+#ifdef CONFIG_SPI_OWNBUS
+static inline void ug2864hsweg01_configspi(FAR struct spi_dev_s *spi)
+{
+ lcdvdbg("Mode: %d Bits: 8 Frequency: %d\n",
+ CONFIG_UG2864HSWEG01_SPIMODE, CONFIG_UG2864HSWEG01_FREQUENCY);
+
+ /* Configure SPI for the UG-2864HSWEG01. But only if we own the SPI bus. Otherwise,
+ * don't bother because it might change.
+ */
+
+ SPI_SETMODE(spi, CONFIG_UG2864HSWEG01_SPIMODE);
+ SPI_SETBITS(spi, 8);
+ SPI_SETFREQUENCY(spi, CONFIG_UG2864HSWEG01_FREQUENCY);
+}
+#endif
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_lock
+ *
+ * Description:
+ * Select the SPI, locking and re-configuring if necessary
+ *
+ * Input Parameters:
+ * spi - Reference to the SPI driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ **************************************************************************************/
+
+#ifndef CONFIG_SPI_OWNBUS
+static inline void ug2864hsweg01_lock(FAR struct spi_dev_s *spi)
+{
+ /* Lock the SPI bus if there are multiple devices competing for the SPI bus. */
+
+ SPI_LOCK(spi, true);
+
+ /* Now make sure that the SPI bus is configured for the UG-2864HSWEG01 (it
+ * might have gotten configured for a different device while unlocked)
+ */
+
+ SPI_SETMODE(spi, CONFIG_UG2864HSWEG01_SPIMODE);
+ SPI_SETBITS(spi, 8);
+ SPI_SETFREQUENCY(spi, CONFIG_UG2864HSWEG01_FREQUENCY);
+}
+#endif
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_unlock
+ *
+ * Description:
+ * De-select the SPI
+ *
+ * Input Parameters:
+ * spi - Reference to the SPI driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ **************************************************************************************/
+
+#ifndef CONFIG_SPI_OWNBUS
+static inline void ug2864hsweg01_unlock(FAR struct spi_dev_s *spi)
+{
+ /* De-select UG-2864HSWEG01 chip and relinquish the SPI bus. */
+
+ SPI_LOCK(spi, false);
+}
+#endif
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_putrun
+ *
+ * Description:
+ * This method can be used to write a partial raster line to the LCD.
+ *
+ * Input Parameters:
+ * 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)
+ *
+ **************************************************************************************/
+
+#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE)
+static int ug2864hsweg01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+ size_t npixels)
+{
+ /* Because of this line of code, we will only be able to support a single UG device */
+
+ FAR struct ug2864hsweg01_dev_s *priv = (FAR struct ug2864hsweg01_dev_s *)&g_oleddev;
+ FAR uint8_t *fbptr;
+ FAR uint8_t *ptr;
+ uint8_t devcol;
+ uint8_t fbmask;
+ uint8_t page;
+ uint8_t usrmask;
+ int pixlen;
+ uint8_t i;
+
+ lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels);
+ DEBUGASSERT(buffer);
+
+ /* Clip the run to the display */
+
+ pixlen = npixels;
+ if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)UG2864HSWEG01_XRES)
+ {
+ pixlen = (int)UG2864HSWEG01_XRES - (int)col;
+ }
+
+ /* Verify that some portion of the run remains on the display */
+
+ if (pixlen <= 0 || row > UG2864HSWEG01_YRES)
+ {
+ return OK;
+ }
+
+ /* Perform coordinate conversion for reverse landscape mode */
+
+#ifdef CONFIG_LCD_RLANDSCAPE
+ row = (UG2864HSWEG01_YRES-1) - row;
+ col = (UG2864HSWEG01_XRES-1) - col;
+#endif
+
+ /* Get the page number. The range of 64 lines is divided up into eight
+ * pages of 8 lines each.
+ */
+
+ page = row >> 3;
+
+ /* Update the shadow frame buffer memory. First determine the pixel
+ * position in the frame buffer memory. Pixels are organized like
+ * this:
+ *
+ * --------+---+---+---+---+-...-+-----+
+ * Segment | 0 | 1 | 2 | 3 | ... | 131 |
+ * --------+---+---+---+---+-...-+-----+
+ * D0 | | X | | | | |
+ * D1 | | X | | | | |
+ * D2 | | X | | | | |
+ * D3 | | X | | | | |
+ * D4 | | X | | | | |
+ * D5 | | X | | | | |
+ * D6 | | X | | | | |
+ * D7 | | X | | | | |
+ * --------+---+---+---+---+-...-+-----+
+ *
+ * So, in order to draw a white, horizontal line, at row 45. we
+ * would have to modify all of the bytes in page 45/8 = 5. We
+ * would have to set bit 45%8 = 5 in every byte in the page.
+ */
+
+ fbmask = 1 << (row & 7);
+ fbptr = &priv->fb[page * UG2864HSWEG01_XRES + col];
+#ifdef CONFIG_LCD_RLANDSCAPE
+ ptr = fbptr + pixlen - 1;
+#else
+ ptr = fbptr;
+#endif
+#ifdef CONFIG_NX_PACKEDMSFIRST
+ usrmask = MS_BIT;
+#else
+ usrmask = LS_BIT;
+#endif
+
+ for (i = 0; i < pixlen; i++)
+ {
+ /* Set or clear the corresponding bit */
+
+#ifdef CONFIG_LCD_RLANDSCAPE
+ if ((*buffer & usrmask) != 0)
+ {
+ *ptr-- |= fbmask;
+ }
+ else
+ {
+ *ptr-- &= ~fbmask;
+ }
+#else
+ if ((*buffer & usrmask) != 0)
+ {
+ *ptr++ |= fbmask;
+ }
+ else
+ {
+ *ptr++ &= ~fbmask;
+ }
+#endif
+
+ /* Inc/Decrement to the next source pixel */
+
+#ifdef CONFIG_NX_PACKEDMSFIRST
+ if (usrmask == LS_BIT)
+ {
+ buffer++;
+ usrmask = MS_BIT;
+ }
+ else
+ {
+ usrmask >>= 1;
+ }
+#else
+ if (usrmask == MS_BIT)
+ {
+ buffer++;
+ usrmask = LS_BIT;
+ }
+ else
+ {
+ usrmask <<= 1;
+ }
+#endif
+ }
+
+ /* Offset the column position to account for smaller horizontal
+ * display range.
+ */
+
+ devcol = col + UG2864HSWEG01_DEV_XOFFSET;
+
+ /* Lock and select device */
+
+ ug2864hsweg01_lock(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true);
+
+ /* Select command transfer */
+
+ SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true);
+
+ /* Set the starting position for the run */
+ /* Set the column address to the XOFFSET value */
+
+ SPI_SEND(priv->spi, SSD1306_SETCOLL(devcol & 0x0f));
+ SPI_SEND(priv->spi, SSD1306_SETCOLH(devcol >> 4));
+
+ /* Set the page address */
+
+ SPI_SEND(priv->spi, SSD1306_PAGEADDR(page));
+
+ /* Select data transfer */
+
+ SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false);
+
+ /* Then transfer all of the data */
+
+ (void)SPI_SNDBLOCK(priv->spi, fbptr, pixlen);
+
+ /* De-select and unlock the device */
+
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false);
+ ug2864hsweg01_unlock(priv->spi);
+ return OK;
+}
+#else
+# error "Configuration not implemented"
+#endif
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_getrun
+ *
+ * Description:
+ * This method can be used to read a partial raster line from the LCD:
+ *
+ * Description:
+ * This method can be used to write a partial raster line to 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)
+ *
+ **************************************************************************************/
+
+#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE)
+static int ug2864hsweg01_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels)
+{
+ /* Because of this line of code, we will only be able to support a single UG device */
+
+ FAR struct ug2864hsweg01_dev_s *priv = &g_oleddev;
+ FAR uint8_t *fbptr;
+ uint8_t page;
+ uint8_t fbmask;
+ uint8_t usrmask;
+ int pixlen;
+ uint8_t i;
+
+ lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels);
+ DEBUGASSERT(buffer);
+
+ /* Clip the run to the display */
+
+ pixlen = npixels;
+ if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)UG2864HSWEG01_XRES)
+ {
+ pixlen = (int)UG2864HSWEG01_XRES - (int)col;
+ }
+
+ /* Verify that some portion of the run is actually the display */
+
+ if (pixlen <= 0 || row > UG2864HSWEG01_YRES)
+ {
+ return -EINVAL;
+ }
+
+ /* Perform coordinate conversion for reverse landscape mode */
+
+#ifdef CONFIG_LCD_RLANDSCAPE
+ row = (UG2864HSWEG01_YRES-1) - row;
+ col = (UG2864HSWEG01_XRES-1) - col;
+#endif
+
+ /* Then transfer the display data from the shadow frame buffer memory */
+ /* Get the page number. The range of 64 lines is divided up into eight
+ * pages of 8 lines each.
+ */
+
+ page = row >> 3;
+
+ /* Update the shadow frame buffer memory. First determine the pixel
+ * position in the frame buffer memory. Pixels are organized like
+ * this:
+ *
+ * --------+---+---+---+---+-...-+-----+
+ * Segment | 0 | 1 | 2 | 3 | ... | 131 |
+ * --------+---+---+---+---+-...-+-----+
+ * D0 | | X | | | | |
+ * D1 | | X | | | | |
+ * D2 | | X | | | | |
+ * D3 | | X | | | | |
+ * D4 | | X | | | | |
+ * D5 | | X | | | | |
+ * D6 | | X | | | | |
+ * D7 | | X | | | | |
+ * --------+---+---+---+---+-...-+-----+
+ *
+ * So, in order to draw a white, horizontal line, at row 45. we
+ * would have to modify all of the bytes in page 45/8 = 5. We
+ * would have to set bit 45%8 = 5 in every byte in the page.
+ */
+
+ fbmask = 1 << (row & 7);
+#ifdef CONFIG_LCD_RLANDSCAPE
+ fbptr = &priv->fb[page * (UG2864HSWEG01_XRES-1) + col + pixlen];
+#else
+ fbptr = &priv->fb[page * UG2864HSWEG01_XRES + col];
+#endif
+#ifdef CONFIG_NX_PACKEDMSFIRST
+ usrmask = MS_BIT;
+#else
+ usrmask = LS_BIT;
+#endif
+
+ *buffer = 0;
+ for (i = 0; i < pixlen; i++)
+ {
+ /* Set or clear the corresponding bit */
+
+#ifdef CONFIG_LCD_RLANDSCAPE
+ uint8_t byte = *fbptr--;
+#else
+ uint8_t byte = *fbptr++;
+#endif
+ if ((byte & fbmask) != 0)
+ {
+ *buffer |= usrmask;
+ }
+
+ /* Inc/Decrement to the next destination pixel. Hmmmm. It looks like
+ * this logic could write past the end of the user buffer. Revisit
+ * this!
+ */
+
+#ifdef CONFIG_NX_PACKEDMSFIRST
+ if (usrmask == LS_BIT)
+ {
+ buffer++;
+ *buffer = 0;
+ usrmask = MS_BIT;
+ }
+ else
+ {
+ usrmask >>= 1;
+ }
+#else
+ if (usrmask == MS_BIT)
+ {
+ buffer++;
+ *buffer = 0;
+ usrmask = LS_BIT;
+ }
+ else
+ {
+ usrmask <<= 1;
+ }
+#endif
+ }
+
+ return OK;
+}
+#else
+# error "Configuration not implemented"
+#endif
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_getvideoinfo
+ *
+ * Description:
+ * Get information about the LCD video controller configuration.
+ *
+ **************************************************************************************/
+
+static int ug2864hsweg01_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo)
+{
+ DEBUGASSERT(dev && vinfo);
+ lcdvdbg("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: ug2864hsweg01_getplaneinfo
+ *
+ * Description:
+ * Get information about the configuration of each LCD color plane.
+ *
+ **************************************************************************************/
+
+static int ug2864hsweg01_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+ FAR struct lcd_planeinfo_s *pinfo)
+{
+ DEBUGASSERT(pinfo && planeno == 0);
+ lcdvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp);
+ memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s));
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_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 ug2864hsweg01_getpower(FAR struct lcd_dev_s *dev)
+{
+ FAR struct ug2864hsweg01_dev_s *priv = (FAR struct ug2864hsweg01_dev_s *)dev;
+ DEBUGASSERT(priv);
+
+ lcdvdbg("power: %s\n", priv->on ? "ON" : "OFF");
+ return priv->on ? CONFIG_LCD_MAXPOWER : 0;
+}
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_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 ug2864hsweg01_setpower(struct lcd_dev_s *dev, int power)
+{
+ struct ug2864hsweg01_dev_s *priv = (struct ug2864hsweg01_dev_s *)dev;
+ DEBUGASSERT(priv && (unsigned)power <= CONFIG_LCD_MAXPOWER && priv->spi);
+
+ lcdvdbg("power: %d [%d]\n", power, priv->on ? CONFIG_LCD_MAXPOWER : 0);
+
+ /* Lock and select device */
+
+ ug2864hsweg01_lock(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true);
+
+ if (power <= 0)
+ {
+ /* Turn the display off */
+
+ (void)SPI_SEND(priv->spi, SSD1306_DISPOFF);
+ priv->on = false;
+ }
+ else
+ {
+ /* Turn the display on */
+
+ (void)SPI_SEND(priv->spi, SSD1306_DISPON); /* Display on, dim mode */
+ priv->on = true;
+ }
+
+ /* De-select and unlock the device */
+
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false);
+ ug2864hsweg01_unlock(priv->spi);
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_getcontrast
+ *
+ * Description:
+ * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static int ug2864hsweg01_getcontrast(struct lcd_dev_s *dev)
+{
+ struct ug2864hsweg01_dev_s *priv = (struct ug2864hsweg01_dev_s *)dev;
+ DEBUGASSERT(priv);
+
+ lcdvdbg("contrast: %d\n", priv->contrast);
+ return priv->contrast;
+}
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_setcontrast
+ *
+ * Description:
+ * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static int ug2864hsweg01_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
+{
+ struct ug2864hsweg01_dev_s *priv = (struct ug2864hsweg01_dev_s *)dev;
+ unsigned int scaled;
+
+ lcdvdbg("contrast: %d\n", contrast);
+ DEBUGASSERT(priv);
+
+ /* Verify the contrast value */
+
+#ifdef CONFIG_DEBUG
+ if (contrast > CONFIG_LCD_MAXCONTRAST)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ /* Scale contrast: newcontrast = 255 * contrast / CONFIG_LCD_MAXCONTRAST
+ * Where contrast is in the range {1,255}
+ */
+
+#if CONFIG_LCD_MAXCONTRAST != 255
+ scaled = ((contrast << 8) - 1) / CONFIG_LCD_MAXCONTRAST;
+#else
+ scaled = contrast;
+#endif
+
+ /* Lock and select device */
+
+ ug2864hsweg01_lock(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true);
+
+ /* Select command transfer */
+
+ SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true);
+
+ /* Set the contrast */
+
+ (void)SPI_SEND(priv->spi, SSD1306_CONTRAST_MODE); /* Set contrast control register */
+ (void)SPI_SEND(priv->spi, SSD1306_CONTRAST(scaled)); /* Data 1: Set 1 of 256 contrast steps */
+ priv->contrast = contrast;
+
+ /* De-select and unlock the device */
+
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false);
+ ug2864hsweg01_unlock(priv->spi);
+ return OK;
+}
+
+/**************************************************************************************
+ * Public Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_initialize
+ *
+ * Description:
+ * Initialize the UG-2864HSWEG01 video hardware. The initial state of the
+ * OLED is fully initialized, display memory cleared, and the OLED 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 through CONFIG_UG2864HSWEG01_NINTERFACES-1.
+ * This allows support for multiple OLED devices.
+ *
+ * Returned Value:
+ *
+ * On success, this function returns a reference to the LCD object for
+ * the specified OLED. NULL is returned on any failure.
+ *
+ **************************************************************************************/
+
+FAR struct lcd_dev_s *ug2864hsweg01_initialize(FAR struct spi_dev_s *spi, unsigned int devno)
+{
+ FAR struct ug2864hsweg01_dev_s *priv = &g_oleddev;
+
+ lcdvdbg("Initializing\n");
+ DEBUGASSERT(spi && devno == 0);
+
+ /* Save the reference to the SPI device */
+
+ priv->spi = spi;
+
+ /* Configure the SPI */
+
+ ug2864hsweg01_configspi(spi);
+
+ /* Lock and select device */
+
+ ug2864hsweg01_lock(priv->spi);
+ SPI_SELECT(spi, SPIDEV_DISPLAY, true);
+
+ /* Select command transfer */
+
+ SPI_CMDDATA(spi, SPIDEV_DISPLAY, true);
+
+ /* Configure OLED SPI or I/O, must be delayed 1-10ms */
+
+ up_mdelay(5);
+
+ /* Configure the device */
+
+//#define OLED_WriteCmd(v) SPI_SEND(spi,v)
+//
+// /* Module manufacturers to provide initialization code 模块厂家提供初始化代码 */
+//
+// OLED_WriteCmd(0xAE); /* 关闭OLED面板显示(休眠) */
+// OLED_WriteCmd(0x00); /* 设置列地址低4bit */
+// OLED_WriteCmd(0x10); /* 设置列地址高4bit */
+// OLED_WriteCmd(0x40); /* 设置起始行地址(低5bit 0-63), 硬件相关*/
+//
+// OLED_WriteCmd(0x81); /* 设置对比度命令(双字节命令),第1个字节是命令,第2个字节是对比度参数0-255 */
+// OLED_WriteCmd(0xCF); /* 设置对比度参数 */
+//
+// OLED_WriteCmd(0xA1); /* A0 :列地址0映射到SEG0; A1 :列地址127映射到SEG0 */
+// OLED_WriteCmd(0xA6); /* A6 : 设置正常显示模式; A7 : 设置为反显模式 */
+//
+// OLED_WriteCmd(0xA8); /* 设置COM路数 */
+// OLED_WriteCmd(0x3F); /* 1 ->(63+1)路 */
+//
+// OLED_WriteCmd(0xD3); /* 设置显示偏移(双字节命令)*/
+// OLED_WriteCmd(0x00); /* 无偏移 */
+//
+// OLED_WriteCmd(0xD5); /* 设置显示时钟分频系数/振荡频率 */
+// OLED_WriteCmd(0x80); /* 设置分频系数,高4bit是分频系数,低4bit是振荡频率 */
+//
+// OLED_WriteCmd(0xD9); /* 设置预充电周期 */
+// OLED_WriteCmd(0xF1); /* [3:0],PHASE 1; [7:4],PHASE 2; */
+//
+// OLED_WriteCmd(0xDA); /* 设置COM脚硬件接线方式 */
+// OLED_WriteCmd(0x12);
+//
+// OLED_WriteCmd(0xDB); /* 设置 vcomh 电压倍率 */
+// OLED_WriteCmd(0x40); /* [6:4] 000 = 0.65 x VCC; 0.77 x VCC (RESET); 0.83 x VCC */
+//
+// OLED_WriteCmd(0x8D); /* 设置充电泵(和下个命令结合使用) */
+// OLED_WriteCmd(0x14); /* 0x14 使能充电泵, 0x10 是关闭 */
+// OLED_WriteCmd(0xAF); /* 打开OLED面板 */
+
+ SPI_SEND(spi, SSD1306_DISPOFF); /* Display off 0xAE*/
+ SPI_SEND(spi, SSD1306_SETCOLL(0)); /* Set lower column address 0x00 */
+ SPI_SEND(spi, SSD1306_SETCOLH(0)); /* Set higher column address 0x10 */
+ SPI_SEND(spi, SSD1306_STARTLINE(0)); /* Set display start line 0x40*/
+ /* SPI_SEND(spi, SSD1306_PAGEADDR(0));*//* Set page address (Can ignore)*/
+ SPI_SEND(spi, SSD1306_CONTRAST_MODE); /* Contrast control 0x81*/
+ SPI_SEND(spi ,SSD1306_CONTRAST(UG2864HSWEG01_CONTRAST)); /* Default contrast 0xCF */
+ SPI_SEND(spi, SSD1306_REMAPPLEFT); /* Set segment remap left 95 to 0 | 0xA1*/
+ /* SPI_SEND(spi, SSD1306_EDISPOFF); */ /* Normal display :off 0xA4 (Can ignore)*/
+ SPI_SEND(spi, SSD1306_NORMAL); /* Normal (un-reversed) display mode 0xA6 */
+ SPI_SEND(spi, SSD1306_MRATIO_MODE); /* Multiplex ratio 0xA8*/
+ SPI_SEND(spi, SSD1306_MRATIO(0x3f)); /* Duty = 1/64 */
+ /* SPI_SEND(spi, SSD1306_SCANTOCOM0);*/ /* Com scan direction: Scan from COM[n-1] to COM[0] (Can ignore)*/
+ SPI_SEND(spi, SSD1306_DISPOFFS_MODE); /* Set display offset 0xD3 */
+ SPI_SEND(spi, SSD1306_DISPOFFS(0));
+ SPI_SEND(spi, SSD1306_CLKDIV_SET); /* Set clock divider 0xD5*/
+ SPI_SEND(spi, SSD1306_CLKDIV(8,0)); /* 0x80*/
+
+ SPI_SEND(spi, SSD1306_CHRGPER_SET); /* ++Set pre-charge period 0xD9*/
+ SPI_SEND(spi, SSD1306_CHRGPER(0x0f,1)); /* 0xf1 or 0x22(Enhanced mode?) */
+
+ SPI_SEND(spi, SSD1306_CMNPAD_CONFIG); /* Set common pads / set com pins hardware configuration 0xDA*/
+ SPI_SEND(spi, SSD1306_CMNPAD(0x12)); /* 0x12 */
+
+ SPI_SEND(spi, SSD1306_VCOM_SET); /* set vcomh 0xDB*/
+ SPI_SEND(spi, SSD1306_VCOM(0x40));
+
+ SPI_SEND(spi, SSD1306_CHRPUMP_SET); /* ++Set Charge Pump enable/disable 0x8D ssd1306*/
+ SPI_SEND(spi, SSD1306_CHRPUMP_ON); /* 0x14 close 0x10 */
+
+ /*SPI_SEND(spi, SSD1306_DCDC_MODE); */ /* DC/DC control mode: on (SSD1306 Not supported) */
+ /*SPI_SEND(spi, SSD1306_DCDC_ON); */
+
+ SPI_SEND(spi, SSD1306_DISPON); /* display ON 0xAF */
+
+ /* De-select and unlock the device */
+
+ SPI_SELECT(spi, SPIDEV_DISPLAY, false);
+ ug2864hsweg01_unlock(priv->spi);
+
+ /* Clear the display */
+
+ up_mdelay(100);
+ ug2864hsweg01_fill(&priv->dev, UG_Y1_BLACK);
+ return &priv->dev;
+}
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_fill
+ *
+ * Description:
+ * This non-standard method can be used to clear the entire display by writing one
+ * color to the display. This is much faster than writing a series of runs.
+ *
+ * Input Parameters:
+ * priv - Reference to private driver structure
+ *
+ * Assumptions:
+ * Caller has selected the OLED section.
+ *
+ **************************************************************************************/
+
+void ug2864hsweg01_fill(FAR struct lcd_dev_s *dev, uint8_t color)
+{
+ FAR struct ug2864hsweg01_dev_s *priv = &g_oleddev;
+ unsigned int page;
+
+ /* Make an 8-bit version of the selected color */
+
+ if (color & 1)
+ {
+ color = 0xff;
+ }
+ else
+ {
+ color = 0;
+ }
+
+ /* Initialize the framebuffer */
+
+ memset(priv->fb, color, UG2864HSWEG01_FBSIZE);
+
+ /* Lock and select device */
+
+ ug2864hsweg01_lock(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true);
+
+ /* Visit each page */
+
+ for (page = 0; page < UG2864HSWEG01_DEV_PAGES; page++)
+ {
+ /* Select command transfer */
+
+ SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true);
+
+ /* Set the column address to the XOFFSET value */
+
+ SPI_SEND(priv->spi, SSD1306_SETCOLL(UG2864HSWEG01_DEV_XOFFSET));
+ SPI_SEND(priv->spi, SSD1306_SETCOLH(0));
+
+ /* Set the page address */
+
+ SPI_SEND(priv->spi, SSD1306_PAGEADDR(page));
+
+ /* Select data transfer */
+
+ SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false);
+
+ /* Transfer one page of the selected color */
+
+ (void)SPI_SNDBLOCK(priv->spi, &priv->fb[page * UG2864HSWEG01_XRES],
+ UG2864HSWEG01_XRES);
+ }
+
+ /* De-select and unlock the device */
+
+ SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false);
+ ug2864hsweg01_unlock(priv->spi);
+}
+
+#endif /* CONFIG_LCD_UG2864HSWEG01 */
diff --git a/nuttx/drivers/mmcsd/Kconfig b/nuttx/drivers/mmcsd/Kconfig
index c224f220a..2d9a04bbb 100644
--- a/nuttx/drivers/mmcsd/Kconfig
+++ b/nuttx/drivers/mmcsd/Kconfig
@@ -2,6 +2,7 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
config MMCSD_NSLOTS
int "Number of MMC/SD slots"
default 1
@@ -38,8 +39,9 @@ config MMCSD_HAVECARDDETECT
100% accurate
config MMCSD_SPI
- bool "MMC/SD spi transfer support"
+ bool "MMC/SD SPI transfer support"
default y
+ depends on SPI
config MMCSD_SPICLOCK
int "MMC/SD maximum SPI clock"
@@ -51,7 +53,7 @@ config MMCSD_SPICLOCK
config MMCSD_SDIO
bool "MMC/SD sdio transfer support"
- default y
+ default n
if MMCSD_SDIO
config SDIO_DMA
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index 7db7592d4..3102f1447 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -37,6 +37,8 @@
# Include MTD drivers
+ifeq ($(CONFIG_MTD),y)
+
CSRCS += at45db.c flash_eraseall.c ftl.c m25px.c rammtd.c ramtron.c
ifeq ($(CONFIG_MTD_AT24XX),y)
@@ -60,3 +62,4 @@ endif
DEPPATH += --dep-path mtd
VPATH += :mtd
+endif
diff --git a/nuttx/drivers/usbdev/composite.c b/nuttx/drivers/usbdev/composite.c
index 4cad8af86..530d64416 100644
--- a/nuttx/drivers/usbdev/composite.c
+++ b/nuttx/drivers/usbdev/composite.c
@@ -523,12 +523,12 @@ static int composite_setup(FAR struct usbdevclass_driver_s *driver,
{
/* Save the configuration and inform the constituent classes */
- ret = CLASS_SETUP(priv->dev1, dev, ctrl);
+ ret = CLASS_SETUP(priv->dev1, dev, ctrl, dataout, outlen);
dispatched = true;
if (ret >= 0)
{
- ret = CLASS_SETUP(priv->dev2, dev, ctrl);
+ ret = CLASS_SETUP(priv->dev2, dev, ctrl, dataout, outlen);
if (ret >= 0)
{
priv->config = value;
diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c
index 95f26c185..d10539fa7 100644
--- a/nuttx/drivers/usbdev/pl2303.c
+++ b/nuttx/drivers/usbdev/pl2303.c
@@ -333,7 +333,7 @@ static void usbclass_wrcomplete(FAR struct usbdev_ep_s *ep,
/* USB class device ********************************************************/
-static int usbclass_bind(FAR struct usbdevclass_driver_s *driver,
+static int usbclass_bind(FAR struct usbdevclass_driver_s *driver,
FAR struct usbdev_s *dev);
static void usbclass_unbind(FAR struct usbdevclass_driver_s *driver,
FAR struct usbdev_s *dev);
@@ -1295,7 +1295,7 @@ static int usbclass_bind(FAR struct usbdevclass_driver_s *driver,
priv->usbdev = dev;
/* Save the reference to our private data structure in EP0 so that it
- * can be recovered in ep0 completion events (Unless we are part of
+ * can be recovered in ep0 completion events (Unless we are part of
* a composite device and, in that case, the composite device owns
* EP0).
*/
@@ -1859,7 +1859,7 @@ static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
* re-enumerated.
*/
- DEV_CONNECT(dev);
+ DEV_CONNECT(dev);
}
/****************************************************************************
@@ -1878,7 +1878,7 @@ static int usbser_setup(FAR struct uart_dev_s *dev)
{
FAR struct pl2303_dev_s *priv;
- usbtrace(PL2303_CLASSASPI_SETUP, 0);
+ usbtrace(PL2303_CLASSAPI_SETUP, 0);
/* Sanity check */
@@ -1919,7 +1919,7 @@ static int usbser_setup(FAR struct uart_dev_s *dev)
static void usbser_shutdown(FAR struct uart_dev_s *dev)
{
- usbtrace(PL2303_CLASSASPI_SHUTDOWN, 0);
+ usbtrace(PL2303_CLASSAPI_SHUTDOWN, 0);
/* Sanity check */
@@ -1941,7 +1941,7 @@ static void usbser_shutdown(FAR struct uart_dev_s *dev)
static int usbser_attach(FAR struct uart_dev_s *dev)
{
- usbtrace(PL2303_CLASSASPI_ATTACH, 0);
+ usbtrace(PL2303_CLASSAPI_ATTACH, 0);
return OK;
}
@@ -1955,7 +1955,7 @@ static int usbser_attach(FAR struct uart_dev_s *dev)
static void usbser_detach(FAR struct uart_dev_s *dev)
{
- usbtrace(PL2303_CLASSASPI_DETACH, 0);
+ usbtrace(PL2303_CLASSAPI_DETACH, 0);
}
/****************************************************************************
@@ -1981,7 +1981,7 @@ static void usbser_rxint(FAR struct uart_dev_s *dev, bool enable)
FAR uart_dev_t *serdev;
irqstate_t flags;
- usbtrace(PL2303_CLASSASPI_RXINT, (uint16_t)enable);
+ usbtrace(PL2303_CLASSAPI_RXINT, (uint16_t)enable);
/* Sanity check */
@@ -2072,7 +2072,7 @@ static void usbser_txint(FAR struct uart_dev_s *dev, bool enable)
{
FAR struct pl2303_dev_s *priv;
- usbtrace(PL2303_CLASSASPI_TXINT, (uint16_t)enable);
+ usbtrace(PL2303_CLASSAPI_TXINT, (uint16_t)enable);
/* Sanity checks */
@@ -2117,7 +2117,7 @@ static bool usbser_txempty(FAR struct uart_dev_s *dev)
{
FAR struct pl2303_dev_s *priv = (FAR struct pl2303_dev_s*)dev->priv;
- usbtrace(PL2303_CLASSASPI_TXEMPTY, 0);
+ usbtrace(PL2303_CLASSAPI_TXEMPTY, 0);
#if CONFIG_DEBUG
if (!priv)
diff --git a/nuttx/drivers/usbhost/Kconfig b/nuttx/drivers/usbhost/Kconfig
index 35695d750..531e94442 100644
--- a/nuttx/drivers/usbhost/Kconfig
+++ b/nuttx/drivers/usbhost/Kconfig
@@ -2,6 +2,7 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
config USBHOST_NPREALLOC
int "Number of pre-allocated class instances"
default 4
@@ -29,64 +30,85 @@ config USBHOST_ISOC_DISABLE
On some architectures, selecting this setting will reduce driver size
by disabling isochronous endpoint support
+config USBHOST_MSC
+ bool "Mass Storage Class Support"
+ default n
+ depends on !BULK_DISABLE
+ ---help---
+ Enable support for the keyboard class driver. This also depends on
+ NFILE_DESCRIPTORS > 0 && SCHED_WORKQUEUE=y
+
config USBHOST_HIDKBD
- bool "HID keyboad class support"
+ bool "HID Keyboard Class Support"
default n
- depends on !USBHOST_INT_DISABLE && SCHED_WORKQUEUE && !DISABLE_SIGNALS
+ depends on !INT_DISABLE
+ ---help---
+ Enable support for the keyboard class driver. This also depends on
+ SCHED_WORKQUEUE && !DISABLE_SIGNALS
if USBHOST_HIDKBD
config HIDKBD_POLLUSEC
- bool ""
- default n
+ int "Keyboard Poll Rate (MSEC)"
+ default 100000
---help---
- Device poll rate in microseconds. Default: 100 milliseconds.
+ Device poll rate in microseconds. Default: 100,000 microseconds.
config HIDKBD_DEFPRIO
- bool ""
- default n
+ int "Polling Thread Priority"
+ default 50
---help---
Priority of the polling thread. Default: 50.
config HIDKBD_STACKSIZE
- bool ""
- default n
+ int "Polling thread stack size"
+ default 1024
---help---
Stack size for polling thread. Default: 1024
config HIDKBD_BUFSIZE
- bool ""
- default n
+ int "Scancode Buffer Size"
+ default 64
---help---
Scancode buffer size. Default: 64.
config HIDKBD_NPOLLWAITERS
- bool ""
- default n
+ int "Max Number of Waiters for Poll Event"
+ default 2
+ depends on !DISABLE_POLL
---help---
If the poll() method is enabled, this defines the maximum number
of threads that can be waiting for keyboard events. Default: 2.
config HIDKBD_RAWSCANCODES
- bool ""
+ bool "Use Raw Scan Codes"
+ default n
+ ---help---
+ If set to y no conversions will be made on the raw keyboard scan
+ codes. This option is useful during testing. Default: ASCII conversion.
+
+config HIDKBD_ENCODED
+ bool "Enocode Special Keys"
default n
+ depends on !HIDKBD_RAWSCANCODES && LIB_KBDCODEC
---help---
- If set to y no conversion will be made on the raw keyboard scan
- codes. Default: ASCII conversion.
+ Encode special key press events in the user buffer. In this case,
+ the user end must decode the encoded special key values using the
+ interfaces defined in include/nuttx/input/kbd_codec.h. These
+ special keys include such things as up/down arrows, home and end
+ keys, etc. If this not defined, only 7-bit print-able and control
+ ASCII characters will be provided to the user.
config HIDKBD_ALLSCANCODES
- bool ""
+ bool "Use All Scancodes"
default n
---help---
If set to y all 231 possible scancodes will be converted to
something. Default: 104 key US keyboard.
config HIDKBD_NODEBOUNCE
- bool ""
+ bool "Disable Debounce"
default n
---help---
If set to y normal debouncing is disabled. Default:
Debounce enabled (No repeat keys).
- USB host mass storage class driver. Requires USBHOST=y,
- config USBHOST_BULK_DISABLE=n, NFILE_DESCRIPTORS > 0,
- and SCHED_WORKQUEUE=y
endif
diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c
index e69d68e7b..d6a9ceda3 100644
--- a/nuttx/drivers/usbhost/usbhost_hidkbd.c
+++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbhost/usbhost_hidkbd.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -62,6 +62,11 @@
#include <nuttx/usb/usbhost.h>
#include <nuttx/usb/hid.h>
+#ifdef CONFIG_HIDKBD_ENCODED
+# include <nuttx/streams.h>
+# include <nuttx/input/kbd_codec.h>
+#endif
+
/* Don't compile if prerequisites are not met */
#if defined(CONFIG_USBHOST) && !defined(CONFIG_USBHOST_INT_DISABLE) && CONFIG_NFILE_DESCRIPTORS > 0
@@ -126,6 +131,22 @@
# endif
#endif
+/* We cant support encoding of special characters of unless the Keyboard
+ * CODEC is enabled.
+ */
+
+#ifndef CONFIG_LIB_KBDCODEC
+# undef CONFIG_HIDKBD_ENCODED
+#endif
+
+/* If we are using raw scancodes, then we cannot support encoding of
+ * special characters either.
+ */
+
+#ifdef CONFIG_HIDKBD_RAWSCANCODES
+# undef CONFIG_HIDKBD_ENCODED
+#endif
+
/* Driver support ***********************************************************/
/* This format is used to construct the /dev/kbd[n] device driver path. It
* defined here so that it will be used consistently in all places.
@@ -144,6 +165,23 @@
#define USBHOST_MAX_CREFS 0x7fff
+/* Debug ********************************************************************/
+/* Both CONFIG_DEBUG_INPUT and CONFIG_DEBUG_USB could apply to this file.
+ * We assume here that CONFIG_DEBUG_INPUT might be enabled separately, but
+ * CONFIG_DEBUG_USB implies both.
+ */
+
+#ifndef CONFIG_DEBUG_INPUT
+# undef idbg
+# define idbg udbg
+# undef illdbg
+# define illdbg ulldbg
+# undef ivdbg
+# define ivdbg uvdbg
+# undef illvdbg
+# define illvdbg ullvdbg
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -209,6 +247,16 @@ struct usbhost_state_s
uint8_t kbdbuffer[CONFIG_HIDKBD_BUFSIZE];
};
+/* This type is used for encoding special characters */
+
+#ifdef CONFIG_HIDKBD_ENCODED
+struct usbhost_outstream_s
+{
+ struct lib_outstream_s stream;
+ FAR struct usbhost_state_s *priv;
+};
+#endif
+
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -240,7 +288,15 @@ static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *dev
/* Keyboard polling thread */
static void usbhost_destroy(FAR void *arg);
+static void usbhost_putbuffer(FAR struct usbhost_state_s *priv, uint8_t keycode);
+#ifdef CONFIG_HIDKBD_ENCODED
+static void usbhost_putstream(FAR struct lib_outstream_s *this, int ch);
+#endif
static inline uint8_t usbhost_mapscancode(uint8_t scancode, uint8_t modifier);
+#ifdef CONFIG_HIDKBD_ENCODED
+static inline void usbhost_encodescancode(FAR struct usbhost_state_s *priv,
+ uint8_t scancode, uint8_t modifier);
+#endif
static int usbhost_kbdpoll(int argc, char *argv[]);
/* Helpers for usbhost_connect() */
@@ -346,6 +402,121 @@ static struct usbhost_state_s *g_priv; /* Data passed to thread */
*/
#ifndef CONFIG_HIDKBD_RAWSCANCODES
+#ifdef CONFIG_HIDKBD_ENCODED
+
+/* The first and last scancode values with encode-able values */
+
+#define FIRST_ENCODING USBHID_KBDUSE_ENTER /* 0x28 Keyboard Return (ENTER) */
+#ifndef CONFIG_HIDKBD_ALLSCANCODES
+# define LAST_ENCODING USBHID_KBDUSE_POWER /* 0x66 Keyboard Power */
+#else
+# define LAST_ENCODING USBHID_KBDUSE_KPDHEXADECIMAL /* 0xdd Keypad Hexadecimal */
+#endif
+
+#define USBHID_NUMENCODINGS (LAST_ENCODING - FIRST_ENCODING + 1)
+
+static const uint8_t encoding[USBHID_NUMENCODINGS] =
+{
+ /* 0x28-0x2f: Enter,escape,del,back-tab,space,_,+,{ */
+
+ KEYCODE_ENTER, 0, KEYCODE_FWDDEL, KEYCODE_BACKDEL, 0, 0, 0, 0,
+
+ /* 0x30-0x37: },|,Non-US tilde,:,",grave tilde,<,> */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0x38-0x3f: /,CapsLock,F1,F2,F3,F4,F5,F6 */
+
+ 0, KEYCODE_CAPSLOCK, KEYCODE_F1, KEYCODE_F2, KEYCODE_F3, KEYCODE_F4, KEYCODE_F5, KEYCODE_F6,
+
+ /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */
+
+ KEYCODE_F7, KEYCODE_F8, KEYCODE_F9, KEYCODE_F10, KEYCODE_F11, KEYCODE_F12, KEYCODE_PRTSCRN, KEYCODE_SCROLLLOCK,
+
+ /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */
+
+ KEYCODE_PAUSE, KEYCODE_INSERT, KEYCODE_HOME, KEYCODE_PAGEUP, KEYCODE_FWDDEL, KEYCODE_END, KEYCODE_PAGEDOWN, KEYCODE_RIGHT,
+
+ /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */
+
+ KEYCODE_LEFT, KEYCODE_DOWN, KEYCODE_UP, KEYCODE_NUMLOCK, 0, 0, 0, 0,
+
+ /* 0x58-0x5f: Enter,1-7 */
+
+ KEYCODE_ENTER, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0x60-0x66: 8-9,0,.,Non-US \,Application,Power */
+
+ 0, 0, 0, 0, 0, 0, KEYCODE_POWER,
+
+#ifdef CONFIG_HIDKBD_ALLSCANCODES
+
+ 0, /* 0x67 = */
+
+ /* 0x68-0x6f: F13,F14,F15,F16,F17,F18,F19,F20 */
+
+ KEYCODE_F13, KEYCODE_F14, KEYCODE_F15, KEYCODE_F16, KEYCODE_F17, KEYCODE_F18, KEYCODE_F19, KEYCODE_F20,
+
+ /* 0x70-0x77: F21,F22,F23,F24,Execute,Help,Menu,Select */
+
+ KEYCODE_F21, KEYCODE_F22, KEYCODE_F23, KEYCODE_F24, KEYCODE_EXECUTE, KEYCODE_HELP, KEYCODE_MENU, KEYCODE_SELECT,
+
+ /* 0x78-0x7f: Stop,Again,Undo,Cut,Copy,Paste,Find,Mute */
+
+ KEYCODE_STOP, KEYCODE_AGAIN, KEYCODE_UNDO, KEYCODE_CUT, KEYCODE_COPY, KEYCODE_PASTE, KEYCODE_FIND, KEYCODE_MUTE,
+
+ /* 0x80-0x87: VolUp,VolDown,LCapsLock,lNumLock,LScrollLock,,,=,International1 */
+
+ KEYCODE_VOLUP, KEYCODE_VOLDOWN, KEYCODE_LCAPSLOCK, KEYCODE_LNUMLOCK, KEYCODE_LSCROLLLOCK, 0, 0, 0,
+
+ /* 0x88-0x8f: International 2-9 */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0x90-0x97: LAN 1-8 */
+
+ KEYCODE_LANG1, KEYCODE_LANG2, KEYCODE_LANG3, KEYCODE_LANG4, KEYCODE_LANG5, KEYCODE_LANG6, KEYCODE_LANG7, KEYCODE_LANG8,
+
+ /* 0x98-0x9f: LAN 9,Erase,SysReq,Cancel,Clear,Prior,Return,Separator */
+
+ 0, 0, KEYCODE_SYSREQ, KEYCODE_CANCEL, KEYCODE_CLEAR, 0, KEYCODE_ENTER, 0,
+
+ /* 0xa0-0xa7: Out,Oper,Clear,CrSel,Excel,(reserved) */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0xa8-0xaf: (reserved) */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0xb0-0xb7: 00,000,ThouSeparator,DecSeparator,CurrencyUnit,SubUnit,(,) */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0xb8-0xbf: {,},tab,backspace,A-D */
+
+ 0, 0, 0, KEYCODE_BACKDEL, 0, 0, 0, 0,
+
+ /* 0xc0-0xc7: E-F,XOR,^,%,<,>,& */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0xc8-0xcf: &&,|,||,:,#, ,@,! */
+
+ 0, 0, 0, 0, 0, 0, 0, 0,
+
+ /* 0xd0-0xd7: Memory Store,Recall,Clear,Add,Subtract,Muliply,Divide,+/- */
+
+ KEYCODE_MEMSTORE, KEYCODE_MEMRECALL, KEYCODE_MEMCLEAR, KEYCODE_MEMADD, KEYCODE_MEMSUB, KEYCODE_MEMMUL, KEYCODE_MEMDIV, KEYCODE_NEGATE,
+
+ /* 0xd8-0xdd: Clear,ClearEntry,Binary,Octal,Decimal,Hexadecimal */
+
+ KEYCODE_CLEAR, KEYCODE_CLEARENTRY, KEYCODE_BINARY, KEYCODE_OCTAL, KEYCODE_DECIMAL, KEYCODE_HEXADECIMAL
+#endif
+};
+
+#endif
+
static const uint8_t ucmap[USBHID_NUMSCANCODES] =
{
0, 0, 0, 0, 'A', 'B', 'C', 'D', /* 0x00-0x07: Reserved, errors, A-D */
@@ -354,12 +525,12 @@ static const uint8_t ucmap[USBHID_NUMSCANCODES] =
'U', 'V', 'W', 'X', 'Y', 'Z', '!', '@', /* 0x18-0x1f: U-Z,!,@ */
'#', '$', '%', '^', '&', '*', '(', ')', /* 0x20-0x27: #,$,%,^,&,*,(,) */
'\n', '\033', '\177', 0, ' ', '_', '+', '{', /* 0x28-0x2f: Enter,escape,del,back-tab,space,_,+,{ */
- '}', '|', 0, ':', '"', 0, '<', '>', /* 0x30-0x37: },|,Non-US tilde,:,",grave tidle,<,> */
+ '}', '|', 0, ':', '"', '~', '<', '>', /* 0x30-0x37: },|,Non-US tilde,:,",grave tilde,<,> */
'?', 0, 0, 0, 0, 0, 0, 0, /* 0x38-0x3f: /,CapsLock,F1,F2,F3,F4,F5,F6 */
- 0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,sScrollLock */
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */
0, 0, 0, 0, '/', '*', '-', '+', /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */
- '\n', '1', '2', '3', '4', '4', '6', '7', /* 0x58-0x5f: Enter,1-7 */
+ '\n', '1', '2', '3', '4', '5', '6', '7', /* 0x58-0x5f: Enter,1-7 */
'8', '9', '0', '.', 0, 0, 0, '=', /* 0x60-0x67: 8-9,0,.,Non-US \,Application,Power,= */
#ifdef CONFIG_HIDKBD_ALLSCANCODES
0, 0, 0, 0, 0, 0, 0, 0, /* 0x68-0x6f: F13,F14,F15,F16,F17,F18,F19,F20 */
@@ -368,7 +539,7 @@ static const uint8_t ucmap[USBHID_NUMSCANCODES] =
0, 0, 0, 0, 0, ',', 0, 0, /* 0x80-0x87: VolUp,VolDown,LCapsLock,lNumLock,LScrollLock,,,=,International1 */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x88-0x8f: International 2-9 */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x90-0x97: LAN 1-8 */
- 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Ease,SysReq,Cancel,Clear,Prior,Return,Separator */
+ 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Erase,SysReq,Cancel,Clear,Prior,Return,Separator */
0, 0, 0, 0, 0, 0, 0, 0, /* 0xa0-0xa7: Out,Oper,Clear,CrSel,Excel,(reserved) */
0, 0, 0, 0, 0, 0, 0, 0, /* 0xa8-0xaf: (reserved) */
0, 0, 0, 0, 0, 0, '(', ')', /* 0xb0-0xb7: 00,000,ThouSeparator,DecSeparator,CurrencyUnit,SubUnit,(,) */
@@ -389,12 +560,12 @@ static const uint8_t lcmap[USBHID_NUMSCANCODES] =
'u', 'v', 'w', 'x', 'y', 'z', '1', '2', /* 0x18-0x1f: u-z,1-2 */
'3', '4', '5', '6', '7', '8', '9', '0', /* 0x20-0x27: 3-9,0 */
'\n', '\033', '\177', '\t', ' ', '-', '=', '[', /* 0x28-0x2f: Enter,escape,del,tab,space,-,=,[ */
- ']', '\\', '\234', ';', '\'', 0, ',', '.', /* 0x30-0x37: ],\,Non-US pound,;,',grave accent,,,. */
+ ']', '\\', '\234', ';', '\'', '`', ',', '.', /* 0x30-0x37: ],\,Non-US pound,;,',grave accent,,,. */
'/', 0, 0, 0, 0, 0, 0, 0, /* 0x38-0x3f: /,CapsLock,F1,F2,F3,F4,F5,F6 */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */
0, 0, 0, 0, '/', '*', '-', '+', /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */
- '\n', '1', '2', '3', '4', '4', '6', '7', /* 0x58-0x5f: Enter,1-7 */
+ '\n', '1', '2', '3', '4', '5', '6', '7', /* 0x58-0x5f: Enter,1-7 */
'8', '9', '0', '.', 0, 0, 0, '=', /* 0x60-0x67: 8-9,0,.,Non-US \,Application,Power,= */
#ifdef CONFIG_HIDKBD_ALLSCANCODES
0, 0, 0, 0, 0, 0, 0, 0, /* 0x68-0x6f: F13,F14,F15,F16,F17,F18,F19,F20 */
@@ -403,7 +574,7 @@ static const uint8_t lcmap[USBHID_NUMSCANCODES] =
0, 0, 0, 0, 0, ',', 0, 0, /* 0x80-0x87: VolUp,VolDown,LCapsLock,lNumLock,LScrollLock,,,=,International1 */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x88-0x8f: International 2-9 */
0, 0, 0, 0, 0, 0, 0, 0, /* 0x90-0x97: LAN 1-8 */
- 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Ease,SysReq,Cancel,Clear,Prior,Return,Separator */
+ 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Erase,SysReq,Cancel,Clear,Prior,Return,Separator */
0, 0, 0, 0, 0, 0, 0, 0, /* 0xa0-0xa7: Out,Oper,Clear,CrSel,Excel,(reserved) */
0, 0, 0, 0, 0, 0, 0, 0, /* 0xa8-0xaf: (reserved) */
0, 0, 0, 0, 0, 0, '(', ')', /* 0xb0-0xb7: 00,000,ThouSeparator,DecSeparator,CurrencyUnit,SubUnit,(,) */
@@ -638,6 +809,88 @@ static void usbhost_destroy(FAR void *arg)
}
/****************************************************************************
+ * Name: usbhost_putbuffer
+ *
+ * Description:
+ * Add one character to the user buffer.
+ *
+ * Input Parameters:
+ * priv - Driver internal state
+ * keycode - The value to add to the user buffer
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_putbuffer(FAR struct usbhost_state_s *priv,
+ uint8_t keycode)
+{
+ register unsigned int head;
+ register unsigned int tail;
+
+ /* Copy the next keyboard character into the user buffer. */
+
+ head = priv->headndx;
+ priv->kbdbuffer[head] = keycode;
+
+ /* Increment the head index */
+
+ if (++head >= CONFIG_HIDKBD_BUFSIZE)
+ {
+ head = 0;
+ }
+
+ /* If the buffer is full, then increment the tail index to make space. Is
+ * it better to lose old keystrokes or new?
+ */
+
+ tail = priv->tailndx;
+ if (tail == head)
+ {
+ if (++tail >= CONFIG_HIDKBD_BUFSIZE)
+ {
+ tail = 0;
+ }
+
+ /* Save the updated tail index */
+
+ priv->tailndx = tail;
+ }
+
+ /* Save the updated head index */
+
+ priv->headndx = head;
+}
+
+/****************************************************************************
+ * Name: usbhost_putstream
+ *
+ * Description:
+ * A wrapper for usbhost_putc that is compatibile with the lib_outstream_s
+ * putc methos.
+ *
+ * Input Parameters:
+ * stream - The struct lib_outstream_s reference
+ * ch - The character to add to the user buffer
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_HIDKBD_ENCODED
+static void usbhost_putstream(FAR struct lib_outstream_s *stream, int ch)
+{
+ FAR struct usbhost_outstream_s *privstream = (FAR struct usbhost_outstream_s *)stream;
+
+ DEBUGASSERT(privstream && privstream->priv);
+ usbhost_putbuffer(privstream->priv, (uint8_t)ch);
+ stream->nput++;
+}
+#endif
+
+/****************************************************************************
* Name: usbhost_mapscancode
*
* Description:
@@ -680,6 +933,58 @@ static inline uint8_t usbhost_mapscancode(uint8_t scancode, uint8_t modifier)
}
/****************************************************************************
+ * Name: usbhost_encodescancode
+ *
+ * Description:
+ * Check if the key has a special function encoding and, if it does, add
+ * the encoded value to the user buffer.
+ *
+ * Input Parameters:
+ * priv - Driver internal state
+ * scancode - Scan code to be mapped.
+ * modifier - Ctrl,Alt,Shift,GUI modifier bits
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_HIDKBD_ENCODED
+static inline void usbhost_encodescancode(FAR struct usbhost_state_s *priv,
+ uint8_t scancode, uint8_t modifier)
+{
+ uint8_t encoded;
+
+ /* Check if the raw scancode is in a valid range */
+
+ if (scancode >= FIRST_ENCODING && scancode <= LAST_ENCODING)
+ {
+ /* Yes the value is within range */
+
+ encoded = encoding[scancode - FIRST_ENCODING];
+ ivdbg(" scancode: %02x modifier: %02x encoded: %d\n",
+ scancode, modifier, encoded);
+
+ if (encoded)
+ {
+ struct usbhost_outstream_s usbstream;
+
+ /* And it does correspond to a special function key */
+
+ usbstream.stream.put = usbhost_putstream;
+ usbstream.stream.nput = 0;
+ usbstream.priv = priv;
+
+ /* Add the special function value to the user buffer */
+
+ kbd_specpress((enum kbd_keycode_e)encoded,
+ (FAR struct lib_outstream_s *)&usbstream);
+ }
+ }
+}
+#endif
+
+/****************************************************************************
* Name: usbhost_kbdpoll
*
* Description:
@@ -704,6 +1009,8 @@ static int usbhost_kbdpoll(int argc, char *argv[])
unsigned int npolls = 0;
#endif
unsigned int nerrors = 0;
+ bool empty = true;
+ bool newstate;
int ret;
uvdbg("Started\n");
@@ -717,17 +1024,18 @@ static int usbhost_kbdpoll(int argc, char *argv[])
* running.
*/
- priv = g_priv;
- DEBUGASSERT(priv != NULL);
+ priv = g_priv;
+ DEBUGASSERT(priv != NULL);
- priv->polling = true;
- priv->crefs++;
- usbhost_givesem(&g_syncsem);
- sleep(1);
+ priv->polling = true;
+ priv->crefs++;
+ usbhost_givesem(&g_syncsem);
+ sleep(1);
/* Loop here until the device is disconnected */
uvdbg("Entering poll loop\n");
+
while (!priv->disconnected)
{
/* Make sure that we have exclusive access to the private data
@@ -784,17 +1092,12 @@ static int usbhost_kbdpoll(int argc, char *argv[])
else if (priv->open)
{
struct usbhid_kbdreport_s *rpt = (struct usbhid_kbdreport_s *)priv->tbuffer;
- unsigned int head;
- unsigned int tail;
- uint8_t ascii;
+ uint8_t keycode;
int i;
/* Add the newly received keystrokes to our internal buffer */
usbhost_takesem(&priv->exclsem);
- head = priv->headndx;
- tail = priv->tailndx;
-
for (i = 0; i < 6; i++)
{
/* Is this key pressed? But not pressed last time?
@@ -828,15 +1131,15 @@ static int usbhost_kbdpoll(int argc, char *argv[])
* or cursor controls in this version of the driver.
*/
- ascii = usbhost_mapscancode(rpt->key[i], rpt->modifier);
- uvdbg("Key %d: %02x ASCII:%c modifier: %02x\n",
- i, rpt->key[i], ascii ? ascii : ' ', rpt->modifier);
+ keycode = usbhost_mapscancode(rpt->key[i], rpt->modifier);
+ ivdbg("Key %d: %02x keycode:%c modifier: %02x\n",
+ i, rpt->key[i], keycode ? keycode : ' ', rpt->modifier);
/* Zero at this point means that the key does not map to a
* printable character.
*/
- if (ascii != 0)
+ if (keycode != 0)
{
/* Handle control characters. Zero after this means
* a valid, NUL character.
@@ -844,36 +1147,28 @@ static int usbhost_kbdpoll(int argc, char *argv[])
if ((rpt->modifier & (USBHID_MODIFER_LCTRL|USBHID_MODIFER_RCTRL)) != 0)
{
- ascii &= 0x1f;
+ keycode &= 0x1f;
}
/* Copy the next keyboard character into the user
* buffer.
*/
- priv->kbdbuffer[head] = ascii;
-
- /* Increment the head index */
-
- if (++head >= CONFIG_HIDKBD_BUFSIZE)
- {
- head = 0;
- }
+ usbhost_putbuffer(priv, keycode);
+ }
- /* If the buffer is full, then increment the tail
- * index to make space. Is it better to lose old
- * keystrokes or new?
- */
+ /* The zero might, however, map to a special keyboard action (such as a
+ * cursor movement or function key). Attempt to encode the special key.
+ */
- if (tail == head)
- {
- if (++tail >= CONFIG_HIDKBD_BUFSIZE)
- {
- tail = 0;
- }
- }
+#ifdef CONFIG_HIDKBD_ENCODED
+ else
+ {
+ usbhost_encodescancode(priv, rpt->key[i], rpt->modifier);
}
+#endif
}
+
/* Save the scancode (or lack thereof) for key debouncing on
* next keyboard report.
*/
@@ -883,9 +1178,10 @@ static int usbhost_kbdpoll(int argc, char *argv[])
#endif
}
- /* Did we just transition from no data available to data available? */
+ /* Is there data available? */
- if (head != tail && priv->headndx == priv->tailndx)
+ newstate = (priv->headndx == priv->tailndx);
+ if (!newstate)
{
/* Yes.. Is there a thread waiting for keyboard data now? */
@@ -897,15 +1193,18 @@ static int usbhost_kbdpoll(int argc, char *argv[])
priv->waiting = false;
}
- /* And wake up any threads waiting for the POLLIN event */
+ /* Did we just transition from no data available to data
+ * available? If so, wake up any threads waiting for the
+ * POLLIN event.
+ */
- usbhost_pollnotify(priv);
+ if (empty)
+ {
+ usbhost_pollnotify(priv);
+ }
}
- /* Update the head/tail indices */
-
- priv->headndx = head;
- priv->tailndx = tail;
+ empty = newstate;
usbhost_givesem(&priv->exclsem);
}
@@ -958,6 +1257,7 @@ static int usbhost_kbdpoll(int argc, char *argv[])
usbhost_givesem(&priv->exclsem);
}
+
return 0;
}
@@ -1861,6 +2161,7 @@ static ssize_t usbhost_read(FAR struct file *filep, FAR char *buffer, size_t len
/* Wait for data to be available */
uvdbg("Waiting...\n");
+
priv->waiting = true;
usbhost_givesem(&priv->exclsem);
usbhost_takesem(&priv->waitsem);