aboutsummaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-09-14 21:33:19 -0700
committerpx4dev <px4@purgatory.org>2012-09-14 21:33:19 -0700
commita3f21d914038f249e5e141b31410cc8554d94623 (patch)
tree59e60563503a42fce283149f0ca265c21faa19e2 /nuttx/drivers
parent53fe61a6211a86597834d5d8d7e90187f84717b0 (diff)
parentcfa24e37d6f153dbb5c7e2e0de6484719ea4a9b0 (diff)
downloadpx4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.tar.gz
px4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.tar.bz2
px4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.zip
Merge branch 'NuttX/master'
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/Kconfig157
-rw-r--r--nuttx/drivers/analog/Make.defs2
-rw-r--r--nuttx/drivers/analog/dac.c2
-rw-r--r--nuttx/drivers/input/Make.defs2
-rw-r--r--nuttx/drivers/input/ads7843e.c4
-rw-r--r--nuttx/drivers/input/stmpe811_base.c2
-rw-r--r--nuttx/drivers/input/stmpe811_tsc.c2
-rw-r--r--nuttx/drivers/input/tsc2007.c4
-rw-r--r--nuttx/drivers/lcd/nokia6100.c2
-rw-r--r--nuttx/drivers/lcd/pcf8833.h302
-rw-r--r--nuttx/drivers/lcd/s1d15g10.h280
-rw-r--r--nuttx/drivers/lcd/skeleton.c2
-rw-r--r--nuttx/drivers/lcd/ssd1305.h422
-rw-r--r--nuttx/drivers/lcd/ug-9664hswag01.c2
-rw-r--r--nuttx/drivers/mmcsd/Kconfig2
-rw-r--r--nuttx/drivers/mmcsd/Make.defs2
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_csd.h2
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_debug.c2
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_internal.h2
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_sdio.c4
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_sdio.h678
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.h2
-rw-r--r--nuttx/drivers/mtd/at45db.c2
-rw-r--r--nuttx/drivers/mtd/flash_eraseall.c2
-rw-r--r--nuttx/drivers/mtd/ftl.c2
-rw-r--r--nuttx/drivers/mtd/skeleton.c2
-rw-r--r--nuttx/drivers/mtd/sst25.c2
-rw-r--r--nuttx/drivers/net/Kconfig8
-rw-r--r--nuttx/drivers/net/Make.defs6
-rw-r--r--nuttx/drivers/net/cs89x0.c2
-rw-r--r--nuttx/drivers/net/cs89x0.h652
-rw-r--r--nuttx/drivers/net/dm90x0.c2
-rw-r--r--nuttx/drivers/net/enc28j60.c355
-rw-r--r--nuttx/drivers/net/enc28j60.h4
-rw-r--r--nuttx/drivers/power/pm_activity.c2
-rw-r--r--nuttx/drivers/power/pm_update.c4
-rw-r--r--nuttx/drivers/rwbuffer.c4
-rw-r--r--nuttx/drivers/sensors/Make.defs2
-rw-r--r--nuttx/drivers/sensors/lm75.c2
-rw-r--r--nuttx/drivers/sercomm/Make.defs2
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/sercomm/README.txt0
-rw-r--r--nuttx/drivers/serial/Kconfig810
-rw-r--r--nuttx/drivers/serial/uart_16550.c74
-rw-r--r--nuttx/drivers/usbdev/Kconfig139
-rw-r--r--nuttx/drivers/usbhost/Make.defs2
-rw-r--r--nuttx/drivers/usbhost/usbhost_findclass.c2
-rw-r--r--nuttx/drivers/usbhost/usbhost_hidkbd.c4
-rw-r--r--nuttx/drivers/usbhost/usbhost_registerclass.c2
-rw-r--r--nuttx/drivers/usbhost/usbhost_registry.c2
-rw-r--r--nuttx/drivers/usbhost/usbhost_registry.h2
-rw-r--r--nuttx/drivers/usbhost/usbhost_skeleton.c6
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c2
-rw-r--r--nuttx/drivers/wireless/Make.defs2
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/wireless/cc1101/cc1101.c0
54 files changed, 2488 insertions, 1493 deletions
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index f89862650..294566d01 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -3,15 +3,13 @@
# see misc/tools/kconfig-language.txt.
#
-comment "Device Driver Configuration"
-
config DEV_NULL
bool "Enable /dev/null"
default y
config DEV_ZERO
bool "Enable /dev/zero"
- default y
+ default n
config LOOP
bool "Enable loop device"
@@ -22,15 +20,15 @@ config LOOP
loteardown() in include/nuttx/fs/fs.h.
config RAMDISK
- bool "RAM disk support"
+ bool "RAM Disk Support"
default n
---help---
Can be used to set up a block of memory or (read-only) FLASH as
a block driver that can be mounted as a files system. See
include/nuttx/ramdisk.h.
-config CAN
- bool "CAN support"
+menuconfig CAN
+ bool "CAN Driver Support"
default n
---help---
This selection enables building of the "upper-half" CAN driver.
@@ -65,8 +63,8 @@ config CAN_LOOPBACK
endif
-config PWM
- bool "PWM support"
+menuconfig PWM
+ bool "PWM Driver Support"
default n
---help---
This selection enables building of the "upper-half" PWM driver.
@@ -74,7 +72,7 @@ config PWM
if PWM
config PWM_PULSECOUNT
- bool "PWM pulse count support"
+ bool "PWM Pulse Count Support"
default n
---help---
Some hardware will support generation of a fixed number of pulses. This
@@ -84,19 +82,46 @@ config PWM_PULSECOUNT
endif
-config I2C
- bool "I2C support"
- default y
+menuconfig I2C
+ bool "I2C Driver Support"
+ default n
---help---
This selection enables building of the "upper-half" I2C driver.
See include/nuttx/i2c.h for further I2C driver information.
-if I2C
-endif
+config I2C_SLAVE
+ bool "I2C Slave"
+ default n
+ depends on I2C
-config SPI
- bool "SPI support"
- default y
+config I2C_TRANSFER
+ bool "Support the I2C transfer() method"
+ default n
+ depends on I2C
+
+config I2C_WRITEREAD
+ bool "Support the I2C writeread() method"
+ default n
+ depends on I2C
+
+config I2C_POLLED
+ bool "Polled I2C (no interrupts)"
+ default n
+ depends on I2C
+
+config I2C_TRACE
+ bool "Enable I2C trace debug"
+ default n
+ depends on I2C
+
+config I2C_NTRACE
+ bool "Enable I2C trace debug"
+ default n
+ depends on I2C_TRACE
+
+menuconfig SPI
+ bool "SPI Driver Support"
+ default n
---help---
This selection enables building of the "upper-half" SPI driver.
See include/nuttx/spi.h for further SPI driver information.
@@ -104,7 +129,7 @@ config SPI
if SPI
config SPI_OWNBUS
bool "SPI single device"
- default y
+ default n
---help---
Set if there is only one active device on the SPI bus. No locking or SPI
configuration will be performed. It is not necessary for clients to lock,
@@ -126,9 +151,62 @@ config SPI_CMDDATA
endif
-config WATCHDOG
- bool "Watchdog timer support"
- default y
+menuconfig RTC
+ bool "RTC Driver Support"
+ default n
+ ---help---
+ This selection enables configuration of a real time clock (RTCdriver.
+ See include/nuttx/rtc.h for further watchdog timer driver information.
+ Most RTC drivers are MCU specific and may require other specific settings.
+
+config RTC_DATETIME
+ bool "Date/Time RTC Support"
+ default n
+ depends on RTC
+ ---help---
+ There are two general types of RTC: (1) A simple battery backed counter
+ that keeps the time when power is down, and (2) a full date / time RTC the
+ provides the date and time information, often in BCD format. If
+ RTC_DATETIME is selected, it specifies this second kind of RTC. In this
+ case, the RTC is used to "seed" the normal NuttX timer and the NuttX system
+ timer provides for higher resolution time.
+
+config RTC_HIRES
+ bool "Hi-Res RTC Support"
+ default n
+ depends on RTC && !RTC_DATETIME
+ ---help---
+ If RTC_DATETIME not selected, then the simple, battery backed counter is
+ used. There are two different implementations of such simple counters
+ based on the time resolution of the counter: The typical RTC keeps time
+ to resolution of 1 second, usually supporting a 32-bit time_t value. In
+ this case, the RTC is used to "seed" the normal NuttX timer and the NuttX
+ timer provides for higherresoution time.
+
+ If RTC_HIRES is enabled in the NuttX configuration, then the RTC provides
+ higher resolution time and completely replaces the system timer for purpose
+ of date and time.
+
+config RTC_FREQUENCY
+ int "Hi-Res RTC frequency"
+ default 1
+ depends on RTC && !RTC_DATETIME && RTC_HIRES
+ ---help---
+ If RTC_HIRES is defined, then the frequency of the high resolution RTC
+ must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is assumed
+ to be one Hz.
+
+config RTC_ALARM
+ bool "RTC Alarm Support"
+ default n
+ depends on RTC
+ ---help---
+ Enable if the RTC hardware supports setting of an alarm. A callback
+ function will be executed when the alarm goes off.
+
+menuconfig WATCHDOG
+ bool "Watchdog Timer Support"
+ default n
---help---
This selection enables building of the "upper-half" watchdog timer driver.
See include/nuttx/watchdog.h for further watchdog timer driver information.
@@ -137,7 +215,7 @@ if WATCHDOG
endif
menuconfig ANALOG
- bool "Analog Device(ADC/DAC) support"
+ bool "Analog Device(ADC/DAC) Support"
default n
---help---
This directory holds implementations of analog device drivers.
@@ -149,8 +227,8 @@ if ANALOG
source drivers/analog/Kconfig
endif
-config BCH
- bool "BCH support"
+menuconfig BCH
+ bool "Block-to-Character (BCH) Support"
default n
---help---
Contains logic that may be used to convert a block driver into
@@ -163,8 +241,8 @@ source drivers/bch/Kconfig
endif
menuconfig INPUT
- bool "Input device support"
- default y
+ bool "Input Device Support"
+ default n
---help---
This directory holds implementations of input device drivers.
This includes such things as touchscreen and keypad drivers.
@@ -175,7 +253,7 @@ source drivers/input/Kconfig
endif
menuconfig LCD
- bool "LCD support"
+ bool "LCD Driver Support"
default n
select NX_LCDDRIVER
---help---
@@ -191,7 +269,7 @@ source drivers/lcd/Kconfig
endif
menuconfig MMCSD
- bool "MMC/SD support"
+ bool "MMC/SD Driver Support"
default n
---help---
Support for MMC/SD block drivers. MMC/SD block drivers based on
@@ -201,9 +279,9 @@ menuconfig MMCSD
if MMCSD
source drivers/mmcsd/Kconfig
endif
-
+
menuconfig MTD
- bool "Memory Technology Device (MTD) support"
+ bool "Memory Technology Device (MTD) Support"
default n
---help---
Memory Technology Device (MTD) drivers. Some simple drivers for
@@ -220,8 +298,9 @@ source drivers/mtd/Kconfig
endif
menuconfig NETDEVICES
- bool "Network Device support"
+ bool "Network Device Support"
default n
+ depends on NET
---help---
Network interface drivers. See also include/nuttx/net/net.h
@@ -250,7 +329,7 @@ config PM
drivers are not active.
menuconfig POWER
- bool "Power management device support"
+ bool "Power Management Support"
default n
---help---
Enable building of power-related devices (battery monitors, chargers, etc).
@@ -260,7 +339,7 @@ source drivers/power/Kconfig
endif
menuconfig SENSORS
- bool "Sensors support"
+ bool "Sensor Device Support"
default n
---help---
Drivers for various sensors
@@ -270,7 +349,7 @@ source drivers/sensors/Kconfig
endif
menuconfig SERCOMM_CONSOLE
- bool "Osmocom-bb serial console"
+ bool "Osmocom-bb Sercomm Driver Support"
default n
---help---
Sercomm is the transport used by osmocom-bb that runs on top of serial.
@@ -287,7 +366,7 @@ source drivers/sercomm/Kconfig
endif
menuconfig SERIAL
- bool "Serial support"
+ bool "Serial Driver Support"
default y
---help---
Front-end character drivers for chip-specific UARTs. This provide
@@ -299,7 +378,7 @@ source drivers/serial/Kconfig
endif
menuconfig USBDEV
- bool "USB device support"
+ bool "USB Device Driver Support"
default n
---help---
USB device drivers. See also include/nuttx/usb/usbdev.h
@@ -309,7 +388,7 @@ source drivers/usbdev/Kconfig
endif
menuconfig USBHOST
- bool "USB Host support"
+ bool "USB Host Driver Support"
default n
---help---
USB host drivers. See also include/nuttx/usb/usbhost.h
@@ -319,7 +398,7 @@ source drivers/usbhost/Kconfig
endif
menuconfig WIRELESS
- bool "Wireless support"
+ bool "Wireless Device Support"
default n
---help---
Drivers for various wireless devices.
@@ -328,6 +407,8 @@ if WIRELESS
source drivers/wireless/Kconfig
endif
+comment "System Logging Device Options"
+
source drivers/syslog/Kconfig
diff --git a/nuttx/drivers/analog/Make.defs b/nuttx/drivers/analog/Make.defs
index 10b0db478..d94e39758 100644
--- a/nuttx/drivers/analog/Make.defs
+++ b/nuttx/drivers/analog/Make.defs
@@ -2,7 +2,7 @@
# drivers/analog/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/analog/dac.c b/nuttx/drivers/analog/dac.c
index 9371e3414..e1fc3049f 100644
--- a/nuttx/drivers/analog/dac.c
+++ b/nuttx/drivers/analog/dac.c
@@ -8,7 +8,7 @@
* Derived from drivers/can.c
*
* Copyright (C) 2008-2009Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/input/Make.defs b/nuttx/drivers/input/Make.defs
index aaf08b827..6dbae268e 100644
--- a/nuttx/drivers/input/Make.defs
+++ b/nuttx/drivers/input/Make.defs
@@ -2,7 +2,7 @@
# drivers/input/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c
index 750b91ff2..e08a7a728 100644
--- a/nuttx/drivers/input/ads7843e.c
+++ b/nuttx/drivers/input/ads7843e.c
@@ -521,7 +521,7 @@ static int ads7843e_schedule(FAR struct ads7843e_dev_s *priv)
*/
DEBUGASSERT(priv->work.worker == NULL);
- ret = work_queue(&priv->work, ads7843e_worker, priv, 0);
+ ret = work_queue(HPWORK, &priv->work, ads7843e_worker, priv, 0);
if (ret != 0)
{
illdbg("Failed to queue work: %d\n", ret);
@@ -1179,7 +1179,7 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
* availability conditions.
*/
- ret = work_queue(&priv->work, ads7843e_worker, priv, 0);
+ ret = work_queue(HPWORK, &priv->work, ads7843e_worker, priv, 0);
if (ret != 0)
{
idbg("Failed to queue work: %d\n", ret);
diff --git a/nuttx/drivers/input/stmpe811_base.c b/nuttx/drivers/input/stmpe811_base.c
index 72af1575a..f37c24622 100644
--- a/nuttx/drivers/input/stmpe811_base.c
+++ b/nuttx/drivers/input/stmpe811_base.c
@@ -195,7 +195,7 @@ static int stmpe811_interrupt(int irq, FAR void *context)
* action should be required to protect the work queue.
*/
- ret = work_queue(&priv->work, stmpe811_worker, priv, 0);
+ ret = work_queue(HPWORK, &priv->work, stmpe811_worker, priv, 0);
if (ret != 0)
{
illdbg("Failed to queue work: %d\n", ret);
diff --git a/nuttx/drivers/input/stmpe811_tsc.c b/nuttx/drivers/input/stmpe811_tsc.c
index e2ab2827d..c7f8b473b 100644
--- a/nuttx/drivers/input/stmpe811_tsc.c
+++ b/nuttx/drivers/input/stmpe811_tsc.c
@@ -783,7 +783,7 @@ static void stmpe811_timeout(int argc, uint32_t arg1, ...)
* action should be required to protect the work queue.
*/
- ret = work_queue(&priv->timeout, stmpe811_timeoutworker, priv, 0);
+ ret = work_queue(HPWORK, &priv->timeout, stmpe811_timeoutworker, priv, 0);
if (ret != 0)
{
illdbg("Failed to queue work: %d\n", ret);
diff --git a/nuttx/drivers/input/tsc2007.c b/nuttx/drivers/input/tsc2007.c
index 07acb5371..163118b95 100644
--- a/nuttx/drivers/input/tsc2007.c
+++ b/nuttx/drivers/input/tsc2007.c
@@ -775,7 +775,7 @@ static int tsc2007_interrupt(int irq, FAR void *context)
*/
DEBUGASSERT(priv->work.worker == NULL);
- ret = work_queue(&priv->work, tsc2007_worker, priv, 0);
+ ret = work_queue(HPWORK, &priv->work, tsc2007_worker, priv, 0);
if (ret != 0)
{
illdbg("Failed to queue work: %d\n", ret);
@@ -1316,7 +1316,7 @@ int tsc2007_register(FAR struct i2c_dev_s *dev,
* availability conditions.
*/
- ret = work_queue(&priv->work, tsc2007_worker, priv, 0);
+ ret = work_queue(HPWORK, &priv->work, tsc2007_worker, priv, 0);
if (ret != 0)
{
idbg("Failed to queue work: %d\n", ret);
diff --git a/nuttx/drivers/lcd/nokia6100.c b/nuttx/drivers/lcd/nokia6100.c
index d450e05db..7354b8a91 100644
--- a/nuttx/drivers/lcd/nokia6100.c
+++ b/nuttx/drivers/lcd/nokia6100.c
@@ -3,7 +3,7 @@
* Nokia 6100 LCD Display Driver
*
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
* "Nokia 6100 LCD Display Driver," Revision 1, James P. Lynch ("Nokia 6100 LCD
diff --git a/nuttx/drivers/lcd/pcf8833.h b/nuttx/drivers/lcd/pcf8833.h
index b0a7e14d4..36dc65ac3 100644
--- a/nuttx/drivers/lcd/pcf8833.h
+++ b/nuttx/drivers/lcd/pcf8833.h
@@ -1,152 +1,152 @@
-/**************************************************************************************
- * drivers/lcd/pcf8833.h
- * Definitions for the Phillips PCF8833 LCD controller
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * References: "Data Sheet, PCF8833 STN RGB 132x132x3 driver," Phillips, 2003 Feb 14.
- *
- * 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 __DRIVERS_LCD_PCF8833_H
-#define __DRIVERS_LCD_PCF8833_H
-
-/**************************************************************************************
- * Included Files
- **************************************************************************************/
-
-/**************************************************************************************
- * Pre-processor Definitions
- **************************************************************************************/
-/* Pixel format codes */
-
-#define PCF8833_FMT_8BPS (2)
-#define PCF8833_FMT_12BPS (3)
-#define PCF8833_FMT_16BPS (5)
-
-/* LCD Commands */
-
-#define PCF8833_NOP 0x00 /* No operation; Data: none */
-#define PCF8833_SWRESET 0x01 /* Software reset ; Data: none */
-#define PCF8833_BSTROFF 0x02 /* Booster voltage off; Data: none */
-#define PCF8833_BSTRON 0x03 /* Booster voltage on; Data: none */
-#define PCF8833_RDDIDIF 0x04 /* Read display identification; Data: none */
-#define PCF8833_RDDST 0x09 /* Read display status; Data: none */
-#define PCF8833_SLEEPIN 0x10 /* Sleep_IN; Data: none */
-#define PCF8833_SLEEPOUT 0x11 /* Sleep_OUT; Data: none */
-#define PCF8833_PTLON 0x12 /* Partial mode on; Data: none */
-#define PCF8833_NORON 0x13 /* Normal Display mode on; Data: none */
-#define PCF8833_INVOFF 0x20 /* Display inversion off; Data: none */
-#define PCF8833_INVON 0x21 /* Display inversion on; Data: none */
-#define PCF8833_DALO 0x22 /* All pixel off; Data: none */
-#define PCF8833_DAL 0x23 /* All pixel on; Data: none */
-#define PCF8833_SETCON 0x25 /* Set contrast; Data: (1) contrast */
-#define PCF8833_DISPOFF 0x28 /* Display off; Data: none */
-#define PCF8833_DISPON 0x29 /* Display on; Data: none */
-#define PCF8833_CASET 0x2a /* Column address set; Data: (1) X start (2) X end */
-#define PCF8833_PASET 0x2b /* Page address set Data: (1) Y start (2) Y end */
-#define PCF8833_RAMWR 0x2c /* Memory write; Data: (1) write data */
-#define PCF8833_RGBSET 0x2d /* Colour set; Data: (1-8) red tones, (9-16) green tones, (17-20) blue tones */
-#define PCF8833_PTLAR 0x30 /* Partial area; Data: (1) start address (2) end address */
-#define PCF8833_VSCRDEF 0x33 /* Vertical scroll definition; Data: (1) top fixed, (2) scrol area, (3) bottom fixed */
-#define PCF8833_TEOFF 0x34 /* Tearing line off; Data: none */
-#define PCF8833_TEON 0x35 /* Tearing line on; Data: (1) don't care */
-#define PCF8833_MADCTL 0x36 /* Memory data access control; Data: (1) access control settings */
-#define PCF8833_SEP 0x37 /* Set Scroll Entry Point; Data: (1) scroll entry point */
-#define PCF8833_IDMOFF 0x38 /* Idle mode off; Data: none */
-#define PCF8833_IDMON 0x39 /* Idle mode on; Data: none */
-#define PCF8833_COLMOD 0x3a /* Interface pixel format; Data: (1) color interface format */
-#define PCF8833_SETVOP 0xb0 /* Set VOP; Data: (1) VOP5-8 (2) VOP0-4 */
-#define PCF8833_BRS 0xb4 /* Bottom Row Swap; Data: none */
-#define PCF8833_TRS 0xb6 /* Top Row Swap; Data: none */
-#define PCF8833_FINV 0xb9 /* Super Frame INVersion; Data: none */
-#define PCF8833_DOR 0xba /* Data ORder; Data: none */
-#define PCF8833_TCDFE 0xbd /* Enable/disable DF temp comp; Data: none */
-#define PCF8833_TCVOPE 0xbf /* Enable or disable VOP temp comp; Data: none */
-#define PCF8833_EC 0xc0 /* Internal or external oscillator; Data: none */
-#define PCF8833_SETMUL 0xc2 /* Set multiplication factor; Data: (1) Multiplication factor */
-#define PCF8833_TCVOPAB 0xc3 /* Set TCVOP slopes A and B; Data: (1) SLB and SLA */
-#define PCF8833_TCVOPCD 0xc4 /* Set TCVOP slopes C and D; Data: (1) SLD and SLC */
-#define PCF8833_TCDF 0xc5 /* Set divider frequency; Data: Divider factor in region (1) A (2) B (3) C (4) D */
-#define PCF8833_DF8COLOR 0xc6 /* Set divider frequency 8-colour mode; Data: (1) DF80-6 */
-#define PCF8833_SETBS 0xc7 /* Set bias system; Data: (1) Bias systems */
-#define PCF8833_RDTEMP 0xc8 /* Temperature read back; Data: none */
-#define PCF8833_NLI 0xc9 /* N-Line Inversion; Data: (1) NLI time slots invervsion */
-#define PCF8833_RDID1 0xda /* Read ID1; Data: none */
-#define PCF8833_RDID2 0xdb /* Read ID2; Data: none */
-#define PCF8833_RDID3 0xdc /* Read ID3; Data: none */
-#define PCF8833_SFD 0xef /* Select factory defaults; Data: none */
-#define PCF8833_ECM 0xf0 /* Enter Calibration mode; Data: (1) Calibration control settings */
-#define PCF8833_OTPSHTIN 0xf1 /* Shift data in OTP shift registers; Data: Any number of bytes */
-
-/* Memory data access control (MADCTL) bit definitions */
-
-#define MADCTL_RGB (1 << 3) /* Bit 3: BGR */
-#define MADCTL_LAO (1 << 4) /* Bit 4: Line address order bottom to top */
-#define MADCTL_V (1 << 5) /* Bit 5: Vertical RAM write; in Y direction */
-#define MADCTL_MX (1 << 6) /* Bit 6: Mirror X */
-#define MADCTL_MY (1 << 7) /* Bit 7: Mirror Y */
-
-/* PCF8833 status register bit definitions */
-/* CMD format: RDDST command followed by four status bytes: */
-/* Byte 1: D31 d30 D29 D28 D27 D26 --- --- */
-
-#define PCF8833_ST_RGB (1 << 2) /* Bit 2: D26 - RGB/BGR order */
-#define PCF8833_ST_LINEADDR (1 << 3) /* Bit 3: D27 - Line address order */
-#define PCF8833_ST_ADDRMODE (1 << 4) /* Bit 4: D28 - Vertical/horizontal addressing mode */
-#define PCF8833_ST_XADDR (1 << 5) /* Bit 5: D29 - X address order */
-#define PCF8833_ST_YADDR (1 << 6) /* Bit 6: D30 - Y address order */
-#define PCF8833_ST_BOOSTER (1 << 7) /* Bit 7: D31 - Booster voltage status */
-
-/* Byte 2: --- D22 D21 D20 D19 D18 D17 D16 */
-
-#define PCF8833_ST_NORMAL (1 << 0) /* Bit 0: D16 - Normal display mode */
-#define PCF8833_ST_SLEEPIN (1 << 1) /* Bit 1: D17 - Sleep in selected */
-#define PCF8833_ST_PARTIAL (1 << 2) /* Bit 2: D18 - Partial mode on */
-#define PCF8833_ST_IDLE (1 << 3) /* Bit 3: D19 - Idle mode selected */
-#define PCF8833_ST_PIXELFMT_SHIFT (4) /* Bits 4-6: D20-D22 - Interface pixel format */
-#define PCF8833_ST_PIXELFMT_MASK (7 << PCF8833_ST_PIXELFMT_SHIFT)
-# define PCF8833_ST_PIXELFMT_8BPS (PCF8833_FMT_8BPS << PCF8833_ST_PIXELFMT_SHIFT)
-# define PCF8833_ST_PIXELFMT_12BPS (PCF8833_FMT_12BPS << PCF8833_ST_PIXELFMT_SHIFT)
-# define PCF8833_ST_PIXELFMT_16BPS (PCF8833_FMT_16BPS << PCF8833_ST_PIXELFMT_SHIFT)
-
-/* Byte 3: D15 -- D13 D12 D11 D10 D9 --- */
-
-#define PCF8833_ST_TEARING (1 << 1) /* Bit 1: D9 - Tearing effect on */
-#define PCF8833_ST_DISPLAYON (1 << 2) /* Bit 2: D10 - Display on */
-#define PCF8833_ST_PIXELSOFF (1 << 3) /* Bit 3: D11 - All pixels off */
-#define PCF8833_ST_PIXELSON (1 << 4) /* Bit 4: D12 - All pixels on */
-#define PCF8833_ST_INV (1 << 5) /* Bit 5: D13 - Display inversion */
-#define PCF8833_ST_VSCROLL (1 << 7) /* Bit 6: D15 - Vertical scroll mode */
-
-/* Byte 4: All zero */
-
+/**************************************************************************************
+ * drivers/lcd/pcf8833.h
+ * Definitions for the Phillips PCF8833 LCD controller
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References: "Data Sheet, PCF8833 STN RGB 132x132x3 driver," Phillips, 2003 Feb 14.
+ *
+ * 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 __DRIVERS_LCD_PCF8833_H
+#define __DRIVERS_LCD_PCF8833_H
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+/* Pixel format codes */
+
+#define PCF8833_FMT_8BPS (2)
+#define PCF8833_FMT_12BPS (3)
+#define PCF8833_FMT_16BPS (5)
+
+/* LCD Commands */
+
+#define PCF8833_NOP 0x00 /* No operation; Data: none */
+#define PCF8833_SWRESET 0x01 /* Software reset ; Data: none */
+#define PCF8833_BSTROFF 0x02 /* Booster voltage off; Data: none */
+#define PCF8833_BSTRON 0x03 /* Booster voltage on; Data: none */
+#define PCF8833_RDDIDIF 0x04 /* Read display identification; Data: none */
+#define PCF8833_RDDST 0x09 /* Read display status; Data: none */
+#define PCF8833_SLEEPIN 0x10 /* Sleep_IN; Data: none */
+#define PCF8833_SLEEPOUT 0x11 /* Sleep_OUT; Data: none */
+#define PCF8833_PTLON 0x12 /* Partial mode on; Data: none */
+#define PCF8833_NORON 0x13 /* Normal Display mode on; Data: none */
+#define PCF8833_INVOFF 0x20 /* Display inversion off; Data: none */
+#define PCF8833_INVON 0x21 /* Display inversion on; Data: none */
+#define PCF8833_DALO 0x22 /* All pixel off; Data: none */
+#define PCF8833_DAL 0x23 /* All pixel on; Data: none */
+#define PCF8833_SETCON 0x25 /* Set contrast; Data: (1) contrast */
+#define PCF8833_DISPOFF 0x28 /* Display off; Data: none */
+#define PCF8833_DISPON 0x29 /* Display on; Data: none */
+#define PCF8833_CASET 0x2a /* Column address set; Data: (1) X start (2) X end */
+#define PCF8833_PASET 0x2b /* Page address set Data: (1) Y start (2) Y end */
+#define PCF8833_RAMWR 0x2c /* Memory write; Data: (1) write data */
+#define PCF8833_RGBSET 0x2d /* Colour set; Data: (1-8) red tones, (9-16) green tones, (17-20) blue tones */
+#define PCF8833_PTLAR 0x30 /* Partial area; Data: (1) start address (2) end address */
+#define PCF8833_VSCRDEF 0x33 /* Vertical scroll definition; Data: (1) top fixed, (2) scrol area, (3) bottom fixed */
+#define PCF8833_TEOFF 0x34 /* Tearing line off; Data: none */
+#define PCF8833_TEON 0x35 /* Tearing line on; Data: (1) don't care */
+#define PCF8833_MADCTL 0x36 /* Memory data access control; Data: (1) access control settings */
+#define PCF8833_SEP 0x37 /* Set Scroll Entry Point; Data: (1) scroll entry point */
+#define PCF8833_IDMOFF 0x38 /* Idle mode off; Data: none */
+#define PCF8833_IDMON 0x39 /* Idle mode on; Data: none */
+#define PCF8833_COLMOD 0x3a /* Interface pixel format; Data: (1) color interface format */
+#define PCF8833_SETVOP 0xb0 /* Set VOP; Data: (1) VOP5-8 (2) VOP0-4 */
+#define PCF8833_BRS 0xb4 /* Bottom Row Swap; Data: none */
+#define PCF8833_TRS 0xb6 /* Top Row Swap; Data: none */
+#define PCF8833_FINV 0xb9 /* Super Frame INVersion; Data: none */
+#define PCF8833_DOR 0xba /* Data ORder; Data: none */
+#define PCF8833_TCDFE 0xbd /* Enable/disable DF temp comp; Data: none */
+#define PCF8833_TCVOPE 0xbf /* Enable or disable VOP temp comp; Data: none */
+#define PCF8833_EC 0xc0 /* Internal or external oscillator; Data: none */
+#define PCF8833_SETMUL 0xc2 /* Set multiplication factor; Data: (1) Multiplication factor */
+#define PCF8833_TCVOPAB 0xc3 /* Set TCVOP slopes A and B; Data: (1) SLB and SLA */
+#define PCF8833_TCVOPCD 0xc4 /* Set TCVOP slopes C and D; Data: (1) SLD and SLC */
+#define PCF8833_TCDF 0xc5 /* Set divider frequency; Data: Divider factor in region (1) A (2) B (3) C (4) D */
+#define PCF8833_DF8COLOR 0xc6 /* Set divider frequency 8-colour mode; Data: (1) DF80-6 */
+#define PCF8833_SETBS 0xc7 /* Set bias system; Data: (1) Bias systems */
+#define PCF8833_RDTEMP 0xc8 /* Temperature read back; Data: none */
+#define PCF8833_NLI 0xc9 /* N-Line Inversion; Data: (1) NLI time slots invervsion */
+#define PCF8833_RDID1 0xda /* Read ID1; Data: none */
+#define PCF8833_RDID2 0xdb /* Read ID2; Data: none */
+#define PCF8833_RDID3 0xdc /* Read ID3; Data: none */
+#define PCF8833_SFD 0xef /* Select factory defaults; Data: none */
+#define PCF8833_ECM 0xf0 /* Enter Calibration mode; Data: (1) Calibration control settings */
+#define PCF8833_OTPSHTIN 0xf1 /* Shift data in OTP shift registers; Data: Any number of bytes */
+
+/* Memory data access control (MADCTL) bit definitions */
+
+#define MADCTL_RGB (1 << 3) /* Bit 3: BGR */
+#define MADCTL_LAO (1 << 4) /* Bit 4: Line address order bottom to top */
+#define MADCTL_V (1 << 5) /* Bit 5: Vertical RAM write; in Y direction */
+#define MADCTL_MX (1 << 6) /* Bit 6: Mirror X */
+#define MADCTL_MY (1 << 7) /* Bit 7: Mirror Y */
+
+/* PCF8833 status register bit definitions */
+/* CMD format: RDDST command followed by four status bytes: */
+/* Byte 1: D31 d30 D29 D28 D27 D26 --- --- */
+
+#define PCF8833_ST_RGB (1 << 2) /* Bit 2: D26 - RGB/BGR order */
+#define PCF8833_ST_LINEADDR (1 << 3) /* Bit 3: D27 - Line address order */
+#define PCF8833_ST_ADDRMODE (1 << 4) /* Bit 4: D28 - Vertical/horizontal addressing mode */
+#define PCF8833_ST_XADDR (1 << 5) /* Bit 5: D29 - X address order */
+#define PCF8833_ST_YADDR (1 << 6) /* Bit 6: D30 - Y address order */
+#define PCF8833_ST_BOOSTER (1 << 7) /* Bit 7: D31 - Booster voltage status */
+
+/* Byte 2: --- D22 D21 D20 D19 D18 D17 D16 */
+
+#define PCF8833_ST_NORMAL (1 << 0) /* Bit 0: D16 - Normal display mode */
+#define PCF8833_ST_SLEEPIN (1 << 1) /* Bit 1: D17 - Sleep in selected */
+#define PCF8833_ST_PARTIAL (1 << 2) /* Bit 2: D18 - Partial mode on */
+#define PCF8833_ST_IDLE (1 << 3) /* Bit 3: D19 - Idle mode selected */
+#define PCF8833_ST_PIXELFMT_SHIFT (4) /* Bits 4-6: D20-D22 - Interface pixel format */
+#define PCF8833_ST_PIXELFMT_MASK (7 << PCF8833_ST_PIXELFMT_SHIFT)
+# define PCF8833_ST_PIXELFMT_8BPS (PCF8833_FMT_8BPS << PCF8833_ST_PIXELFMT_SHIFT)
+# define PCF8833_ST_PIXELFMT_12BPS (PCF8833_FMT_12BPS << PCF8833_ST_PIXELFMT_SHIFT)
+# define PCF8833_ST_PIXELFMT_16BPS (PCF8833_FMT_16BPS << PCF8833_ST_PIXELFMT_SHIFT)
+
+/* Byte 3: D15 -- D13 D12 D11 D10 D9 --- */
+
+#define PCF8833_ST_TEARING (1 << 1) /* Bit 1: D9 - Tearing effect on */
+#define PCF8833_ST_DISPLAYON (1 << 2) /* Bit 2: D10 - Display on */
+#define PCF8833_ST_PIXELSOFF (1 << 3) /* Bit 3: D11 - All pixels off */
+#define PCF8833_ST_PIXELSON (1 << 4) /* Bit 4: D12 - All pixels on */
+#define PCF8833_ST_INV (1 << 5) /* Bit 5: D13 - Display inversion */
+#define PCF8833_ST_VSCROLL (1 << 7) /* Bit 6: D15 - Vertical scroll mode */
+
+/* Byte 4: All zero */
+
#endif /* __DRIVERS_LCD_PCF8833_H */ \ No newline at end of file
diff --git a/nuttx/drivers/lcd/s1d15g10.h b/nuttx/drivers/lcd/s1d15g10.h
index df2dd8be2..9b5f7738f 100644
--- a/nuttx/drivers/lcd/s1d15g10.h
+++ b/nuttx/drivers/lcd/s1d15g10.h
@@ -1,141 +1,141 @@
-/**************************************************************************************
- * drivers/lcd/s1d15g10.h
- * Definitions for the Epson S1D15G0 LCD controller
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * References: S1D15G0D08B000, Seiko Epson Corportation, 2002.
- *
- * 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 __DRIVERS_LCD_S1D15G10_H
-#define __DRIVERS_LCD_S1D15G10_H
-
-/**************************************************************************************
- * Included Files
- **************************************************************************************/
-
-/**************************************************************************************
- * Pre-processor Definitions
- **************************************************************************************/
-
-/* Epson S1D15G10 Command Set */
-
-#define S1D15G10_DISON 0xaf /* Display on; Data: none */
-#define S1D15G10_DISOFF 0xae /* Display off; Data: none */
-#define S1D15G10_DISNOR 0xa6 /* Normal display; Data: none */
-#define S1D15G10_DISINV 0xa7 /* Inverse display; Data: none */
-#define S1D15G10_COMSCN 0xbb /* Common scan direction; Data: (1) common scan direction */
-#define S1D15G10_DISCTL 0xca /* Display control; Data: Data: (1) CL div, F1/2 pat, (2) duty, (3) FR inverse (4) dispersion */
-#define S1D15G10_SLPIN 0x95 /* Sleep in; Data: none */
-#define S1D15G10_SLPOUT 0x94 /* Sleep out; Data: none */
-#define S1D15G10_PASET 0x75 /* Page address set; Data: (1) start page, (2) end page */
-#define S1D15G10_CASET 0x15 /* Column address set; Data: (1) start addr, (2) end addr */
-#define S1D15G10_DATCTL 0xbc /* Data scan direction, etc.; Data: (1) inverse, scan dir (2) RGB, (3) gray-scale */
-#define S1D15G10_RGBSET8 0xce /* 256-color position set; Data: (1-8) red tones, (9-16) green tones, (17-20) blue tones */
-#define S1D15G10_RAMWR 0x5c /* Writing to memory; Data: (1) write data */
-#define S1D15G10_RAMRD 0x5d /* Reading from memory; Data: (1) read data */
-#define S1D15G10_PTLIN 0xa8 /* Partial display in; Data: (1) start addr, (2) end addr */
-#define S1D15G10_PTLOUT 0xa9 /* Partial display out; Data: none */
-#define S1D15G10_RMWIN 0xe0 /* Read and modify write; Data: none */
-#define S1D15G10_RMWOUT 0xee /* End; Data: none */
-#define S1D15G10_ASCSET 0xaa /* Area scroll set; Data: (1) top addr, (2) bottom addr, (3) Num blocks, (4) scroll mode */
-#define S1D15G10_SCSTART 0xab /* Scroll start set; Data: (1) start block addr */
-#define S1D15G10_OSCON 0xd1 /* Internal oscillation on; Data: none */
-#define S1D15G10_OSCOFF 0xd2 /* Internal oscillation off; Data: none */
-#define S1D15G10_PWRCTR 0x20 /* Power control; Data: (1) LCD drive power */
-#define S1D15G10_VOLCTR 0x81 /* Electronic volume control; Data: (1) volume value, (2) resistance ratio */
-#define S1D15G10_VOLUP 0xd6 /* Increment electronic control by 1; Data: none */
-#define S1D15G10_VOLDOWN 0xd7 /* Decrement electronic control by 1; Data: none */
-#define S1D15G10_TMPGRD 0x82 /* Temperature gradient set; Data: (1-14) temperature gradient */
-#define S1D15G10_EPCTIN 0xcd /* Control EEPROM; Data: (1) read/write */
-#define S1D15G10_EPCOUT 0xcc /* Cancel EEPROM control; Data: none */
-#define S1D15G10_EPMWR 0xfc /* Write into EEPROM; Data: none */
-#define S1D15G10_EPMRD 0xfd /* Read from EEPROM; Data: none */
-#define S1D15G10_EPSRRD1 0x7c /* Read register 1; Data: none */
-#define S1D15G10_EPSRRD2 0x7d /* Read regiser 2; Data: none */
-#define S1D15G10_NOP 0x25 /* NOP intruction (0x45?); Data: none */
-#define S1D15G10_STREAD 0x20 /* Status read; Data: none */
-
-/* Display control (DISCTL) bit definitions */
-
-#define DISCTL_PERIOD_SHIFT (0) /* P1: Bits 0-1, F1 and F2 drive-pattern switching period */
-#define DISCTL_PERIOD_MASK (3 << DISCTL_PERIOD_SHIFT)
-# define DISCTL_PERIOD_8 (0 << DISCTL_PERIOD_SHIFT)
-# define DISCTL_PERIOD_4 (1 << DISCTL_PERIOD_SHIFT)
-# define DISCTL_PERIOD_16 (2 << DISCTL_PERIOD_SHIFT)
-# define DISCTL_PERIOD_FLD (3 << DISCTL_PERIOD_SHIFT)
-#define DISCTL_CLDIV_SHIFT (2) /* P1: Bits 2-4, Clock divider */
-#define DISCTL_CLDIV_MASK (7 << DISCTL_CLDIV_SHIFT)
-# define DISCTL_CLDIV_2 (0 << DISCTL_CLDIV_SHIFT)
-# define DISCTL_CLDIV_4 (1 << DISCTL_CLDIV_SHIFT)
-# define DISCTL_CLDIV_8 (2 << DISCTL_CLDIV_SHIFT)
-# define DISCTL_CLDIV_NONE (3 << DISCTL_CLDIV_SHIFT)
-
-/* Power control (PWRCTR) bit definitions */
-
-#define PWCTR_REFVOLTAGE (1 << 0) /* P1: Bit 0, Turn on reference voltage generation circuit. */
-#define PWCTR_REGULATOR (1 << 1) /* P1: Bit 1, Turn on voltage regulator and circuit voltage follower. */
-#define PWCTR_BOOSTER2 (1 << 2) /* P1: Bit 2, Turn on secondary booster/step-down circuit. */
-#define PWCTR_BOOSTER1 (1 << 3) /* P1: Bit 3, Turn on primary booster circuit. */
-#define PWCTR_EXTR (1 << 4) /* P1: Bit 4, Use external resistance to adjust voltage. */
-
-/* Data control (DATCTL) bit definitions */
-
-#define DATCTL_PGADDR_INV (1 << 0) /* P1: Bit 0, Inverse display of the page address. */
-#define DATCTL_COLADDR_REV (1 << 1) /* P1: Bit 1, Reverse turn of column address. */
-#define DATCTL_ADDR_PGDIR (1 << 2) /* P1: Bit 2, Address-scan direction in page (vs column) direction. */
-
-#define DATCTL_BGR (1 << 0) /* P2: Bit0, RGB->BGR */
-
-#define DATCTL_8GRAY (1) /* P3: Bits 0-2 = 001, 8 gray-scale */
-#define DATCTL_16GRAY_A (2) /* P3: Bits 0-2 = 010, 16 gray-scale display type A */
-#define DATCTL_16GRAY_B (4) /* P3: Bits 0-2 = 100, 16 gray-scale display type B */
-
-/* Status register bit definions (after reset or NOP) */
-
-#define S1D15G10_SR_PARTIAL (1 << 0) /* Bit 0: Partial display */
-#define S1D15G10_SR_NORMAL (1 << 1) /* Bit 1: Normal (vs. inverse) display */
-#define S1D15G10_SR_EEPROM (1 << 2) /* Bit 2: EEPROM access */
-#define S1D15G10_SR_DISPON (1 << 3) /* Bit 3: Display on */
-#define S1D15G10_SR_COLSCAN (1 << 4) /* Bit 4: Column (vs. page) scan direction */
-#define S1D15G10_SR_RMW (1 << 5) /* Bit 5: Read modify write */
-#define S1D15G10_SR_SCROLL (3 << 6) /* Bits 6-7: Area scroll mode */
-
-/* Status register bit definions (after EPSRRD1) */
-
-#define S1D15G10_SR_VOLUME 0x3f /* Bits 0-5: Electronic volume control values */
-
-/* Status register bit definions (after EPSRRD2) */
-
-#define S1D15G10_SR_RRATIO 0x07 /* Bits 0-2: Built-in resistance ratio */
-
+/**************************************************************************************
+ * drivers/lcd/s1d15g10.h
+ * Definitions for the Epson S1D15G0 LCD controller
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References: S1D15G0D08B000, Seiko Epson Corportation, 2002.
+ *
+ * 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 __DRIVERS_LCD_S1D15G10_H
+#define __DRIVERS_LCD_S1D15G10_H
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+
+/* Epson S1D15G10 Command Set */
+
+#define S1D15G10_DISON 0xaf /* Display on; Data: none */
+#define S1D15G10_DISOFF 0xae /* Display off; Data: none */
+#define S1D15G10_DISNOR 0xa6 /* Normal display; Data: none */
+#define S1D15G10_DISINV 0xa7 /* Inverse display; Data: none */
+#define S1D15G10_COMSCN 0xbb /* Common scan direction; Data: (1) common scan direction */
+#define S1D15G10_DISCTL 0xca /* Display control; Data: Data: (1) CL div, F1/2 pat, (2) duty, (3) FR inverse (4) dispersion */
+#define S1D15G10_SLPIN 0x95 /* Sleep in; Data: none */
+#define S1D15G10_SLPOUT 0x94 /* Sleep out; Data: none */
+#define S1D15G10_PASET 0x75 /* Page address set; Data: (1) start page, (2) end page */
+#define S1D15G10_CASET 0x15 /* Column address set; Data: (1) start addr, (2) end addr */
+#define S1D15G10_DATCTL 0xbc /* Data scan direction, etc.; Data: (1) inverse, scan dir (2) RGB, (3) gray-scale */
+#define S1D15G10_RGBSET8 0xce /* 256-color position set; Data: (1-8) red tones, (9-16) green tones, (17-20) blue tones */
+#define S1D15G10_RAMWR 0x5c /* Writing to memory; Data: (1) write data */
+#define S1D15G10_RAMRD 0x5d /* Reading from memory; Data: (1) read data */
+#define S1D15G10_PTLIN 0xa8 /* Partial display in; Data: (1) start addr, (2) end addr */
+#define S1D15G10_PTLOUT 0xa9 /* Partial display out; Data: none */
+#define S1D15G10_RMWIN 0xe0 /* Read and modify write; Data: none */
+#define S1D15G10_RMWOUT 0xee /* End; Data: none */
+#define S1D15G10_ASCSET 0xaa /* Area scroll set; Data: (1) top addr, (2) bottom addr, (3) Num blocks, (4) scroll mode */
+#define S1D15G10_SCSTART 0xab /* Scroll start set; Data: (1) start block addr */
+#define S1D15G10_OSCON 0xd1 /* Internal oscillation on; Data: none */
+#define S1D15G10_OSCOFF 0xd2 /* Internal oscillation off; Data: none */
+#define S1D15G10_PWRCTR 0x20 /* Power control; Data: (1) LCD drive power */
+#define S1D15G10_VOLCTR 0x81 /* Electronic volume control; Data: (1) volume value, (2) resistance ratio */
+#define S1D15G10_VOLUP 0xd6 /* Increment electronic control by 1; Data: none */
+#define S1D15G10_VOLDOWN 0xd7 /* Decrement electronic control by 1; Data: none */
+#define S1D15G10_TMPGRD 0x82 /* Temperature gradient set; Data: (1-14) temperature gradient */
+#define S1D15G10_EPCTIN 0xcd /* Control EEPROM; Data: (1) read/write */
+#define S1D15G10_EPCOUT 0xcc /* Cancel EEPROM control; Data: none */
+#define S1D15G10_EPMWR 0xfc /* Write into EEPROM; Data: none */
+#define S1D15G10_EPMRD 0xfd /* Read from EEPROM; Data: none */
+#define S1D15G10_EPSRRD1 0x7c /* Read register 1; Data: none */
+#define S1D15G10_EPSRRD2 0x7d /* Read regiser 2; Data: none */
+#define S1D15G10_NOP 0x25 /* NOP intruction (0x45?); Data: none */
+#define S1D15G10_STREAD 0x20 /* Status read; Data: none */
+
+/* Display control (DISCTL) bit definitions */
+
+#define DISCTL_PERIOD_SHIFT (0) /* P1: Bits 0-1, F1 and F2 drive-pattern switching period */
+#define DISCTL_PERIOD_MASK (3 << DISCTL_PERIOD_SHIFT)
+# define DISCTL_PERIOD_8 (0 << DISCTL_PERIOD_SHIFT)
+# define DISCTL_PERIOD_4 (1 << DISCTL_PERIOD_SHIFT)
+# define DISCTL_PERIOD_16 (2 << DISCTL_PERIOD_SHIFT)
+# define DISCTL_PERIOD_FLD (3 << DISCTL_PERIOD_SHIFT)
+#define DISCTL_CLDIV_SHIFT (2) /* P1: Bits 2-4, Clock divider */
+#define DISCTL_CLDIV_MASK (7 << DISCTL_CLDIV_SHIFT)
+# define DISCTL_CLDIV_2 (0 << DISCTL_CLDIV_SHIFT)
+# define DISCTL_CLDIV_4 (1 << DISCTL_CLDIV_SHIFT)
+# define DISCTL_CLDIV_8 (2 << DISCTL_CLDIV_SHIFT)
+# define DISCTL_CLDIV_NONE (3 << DISCTL_CLDIV_SHIFT)
+
+/* Power control (PWRCTR) bit definitions */
+
+#define PWCTR_REFVOLTAGE (1 << 0) /* P1: Bit 0, Turn on reference voltage generation circuit. */
+#define PWCTR_REGULATOR (1 << 1) /* P1: Bit 1, Turn on voltage regulator and circuit voltage follower. */
+#define PWCTR_BOOSTER2 (1 << 2) /* P1: Bit 2, Turn on secondary booster/step-down circuit. */
+#define PWCTR_BOOSTER1 (1 << 3) /* P1: Bit 3, Turn on primary booster circuit. */
+#define PWCTR_EXTR (1 << 4) /* P1: Bit 4, Use external resistance to adjust voltage. */
+
+/* Data control (DATCTL) bit definitions */
+
+#define DATCTL_PGADDR_INV (1 << 0) /* P1: Bit 0, Inverse display of the page address. */
+#define DATCTL_COLADDR_REV (1 << 1) /* P1: Bit 1, Reverse turn of column address. */
+#define DATCTL_ADDR_PGDIR (1 << 2) /* P1: Bit 2, Address-scan direction in page (vs column) direction. */
+
+#define DATCTL_BGR (1 << 0) /* P2: Bit0, RGB->BGR */
+
+#define DATCTL_8GRAY (1) /* P3: Bits 0-2 = 001, 8 gray-scale */
+#define DATCTL_16GRAY_A (2) /* P3: Bits 0-2 = 010, 16 gray-scale display type A */
+#define DATCTL_16GRAY_B (4) /* P3: Bits 0-2 = 100, 16 gray-scale display type B */
+
+/* Status register bit definions (after reset or NOP) */
+
+#define S1D15G10_SR_PARTIAL (1 << 0) /* Bit 0: Partial display */
+#define S1D15G10_SR_NORMAL (1 << 1) /* Bit 1: Normal (vs. inverse) display */
+#define S1D15G10_SR_EEPROM (1 << 2) /* Bit 2: EEPROM access */
+#define S1D15G10_SR_DISPON (1 << 3) /* Bit 3: Display on */
+#define S1D15G10_SR_COLSCAN (1 << 4) /* Bit 4: Column (vs. page) scan direction */
+#define S1D15G10_SR_RMW (1 << 5) /* Bit 5: Read modify write */
+#define S1D15G10_SR_SCROLL (3 << 6) /* Bits 6-7: Area scroll mode */
+
+/* Status register bit definions (after EPSRRD1) */
+
+#define S1D15G10_SR_VOLUME 0x3f /* Bits 0-5: Electronic volume control values */
+
+/* Status register bit definions (after EPSRRD2) */
+
+#define S1D15G10_SR_RRATIO 0x07 /* Bits 0-2: Built-in resistance ratio */
+
#endif /* __DRIVERS_LCD_S1D15G10_H */ \ No newline at end of file
diff --git a/nuttx/drivers/lcd/skeleton.c b/nuttx/drivers/lcd/skeleton.c
index 1cb8b5955..83aa92018 100644
--- a/nuttx/drivers/lcd/skeleton.c
+++ b/nuttx/drivers/lcd/skeleton.c
@@ -2,7 +2,7 @@
* drivers/lcd/skeleton.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/lcd/ssd1305.h b/nuttx/drivers/lcd/ssd1305.h
index 87c955de4..34678fa80 100644
--- a/nuttx/drivers/lcd/ssd1305.h
+++ b/nuttx/drivers/lcd/ssd1305.h
@@ -1,211 +1,211 @@
-/**************************************************************************************
- * drivers/lcd/ssd1305.h
- * Definitions for the Solomon Systech SSD1305 132x64 Dot Matrix OLED/PLED
- * Segment/Common Driver with C
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * References: SSD1305.pdf, "Solomon Systech SSD1305 132x64 Dot Matrix OLED/PLED
- * Segment/Common Driver with Controller," Solomon Systech Limited,
- * http://www.solomon-systech.com, May, 2008.
- *
- * 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 __DRIVERS_LCD_SSD1305_H
-#define __DRIVERS_LCD_SSD1305_H
-
-/**************************************************************************************
- * Included Files
- **************************************************************************************/
-
-/**************************************************************************************
- * Pre-processor Definitions
- **************************************************************************************/
-/* General Definitions ******************************************************/
-
-#define SSD1305_COLORA 0
-#define SSD1305_COLORB 1
-#define SSD1305_COLORC 2
-#define SSD1305_COLORD 3
-
-/* Fundamental Commands *****************************************************/
-#define SSD1305_SETCOLL 0x00 /* 0x00-0x0f: Set lower column address */
-# define SSD1305_COLL_MASK 0x0f
-#define SSD1305_SETCOLH 0x10 /* 0x10-0x1f: Set higher column address */
-# define SSD1305_COLH_MASK 0x0f
-#define SSD1305_ADDRMODE 0x20 /* 0x20: Set memory address mode */
-# define SSD1305_ADDRMODE_HOR 0x00 /* Data 1: Set horizontal address mode */
-# define SSD1305_ADDRMODE_VIRT 0x01 /* Data 1: Set virtal address mode */
-# define SSD1305_ADDRMODE_PAGE 0x02 /* Data 1: Set page address mode */
-#define SSD1305_SETCOLADDR 0x21 /* 0x21: Set column address */
- /* Data 1: Column start address: 0-131 */
- /* Data 2: Column end address: 0-131 */
-#define SSD1305_SETPAGEADDR 0x22 /* 0x22: Set page address */
- /* Data 1: Page start address: 0x00-0x7d */
- /* Data 2: Page end address: 0x00-0x7d */
-#define SSD1305_SETSTARTLINE 0x40 /* 0x40-7f: Set display start line */
-# define SSD1305_STARTLINE_MASK 0x3f
-
-#define SSD1305_SETCONTRAST 0x81 /* 0x81: Set contrast control */
- /* Data 1: Set 1 of 256 contrast steps */
-#define SSD1305_SETBRIGHTNESS 0x82 /* 0x82: Set brightness */
- /* Data 1: Set 1 of 256 contrast steps */
-#define SSD1305_SETLUT 0x91 /* 0x01: Set lookup table */
- /* Data 1: Pulse width: 31-63 */
- /* Data 2: Color A: 31-63 */
- /* Data 3: Color B: 31-63 */
- /* Data 4: Color C: 31-63 */
-#define SSD1305_SETBANKCOLOR1 0x92 /* 0x92: Set bank 1-16 color */
-# define SSD1305_SETBANK1(c) (c) /* Data 1, Bits 0-1: Bank 1 color */
-# define SSD1305_SETBANK2(c) (c << 2) /* Data 1, Bits 2-3: Bank 2 color */
-# define SSD1305_SETBANK3(c) (c << 4) /* Data 1, Bits 4-5: Bank 3 color */
-# define SSD1305_SETBANK4(c) (c << 6) /* Data 1, Bits 6-7: Bank 4 color */
-# define SSD1305_SETBANK5(c) (c) /* Data 2, Bits 0-1: Bank 5 color */
-# define SSD1305_SETBANK6(c) (c << 2) /* Data 2, Bits 2-3: Bank 6 color */
-# define SSD1305_SETBANK7(c) (c << 4) /* Data 2, Bits 4-5: Bank 7 color */
-# define SSD1305_SETBANK8(c) (c << 6) /* Data 2, Bits 6-7: Bank 8 color */
-# define SSD1305_SETBANK9(c) (c) /* Data 3, Bits 0-1: Bank 9 color */
-# define SSD1305_SETBANK10(c) (c << 2) /* Data 3, Bits 2-3: Bank 10 color */
-# define SSD1305_SETBANK11(c) (c << 4) /* Data 3, Bits 4-5: Bank 11 color */
-# define SSD1305_SETBANK12(c) (c << 6) /* Data 3, Bits 6-7: Bank 12 color */
-# define SSD1305_SETBANK13(c) (c) /* Data 4, Bits 0-1: Bank 13 color */
-# define SSD1305_SETBANK14(c) (c << 2) /* Data 4, Bits 2-3: Bank 14 color */
-# define SSD1305_SETBANK15(c) (c << 4) /* Data 4, Bits 4-5: Bank 15 color */
-# define SSD1305_SETBANK16(c) (c << 6) /* Data 4, Bits 6-7: Bank 16 color */
-#define SSD1305_SETBANKCOLOR2 0x93 /* 0x93: Set bank 17-32 color */
-# define SSD1305_SETBANK17(c) (c) /* Data 1, Bits 0-1: Bank 17 color */
-# define SSD1305_SETBANK18(c) (c << 2) /* Data 1, Bits 2-3: Bank 18 color */
-# define SSD1305_SETBANK19(c) (c << 4) /* Data 1, Bits 4-5: Bank 19 color */
-# define SSD1305_SETBANK20(c) (c << 6) /* Data 1, Bits 6-7: Bank 20 color */
-# define SSD1305_SETBANK21(c) (c) /* Data 2, Bits 0-1: Bank 21 color */
-# define SSD1305_SETBANK22(c) (c << 2) /* Data 2, Bits 2-3: Bank 22 color */
-# define SSD1305_SETBANK23(c) (c << 4) /* Data 2, Bits 4-5: Bank 23 color */
-# define SSD1305_SETBANK24(c) (c << 6) /* Data 2, Bits 6-7: Bank 24 color */
-# define SSD1305_SETBANK25(c) (c) /* Data 3, Bits 0-1: Bank 25 color */
-# define SSD1305_SETBANK26(c) (c << 2) /* Data 3, Bits 2-3: Bank 26 color */
-# define SSD1305_SETBANK27(c) (c << 4) /* Data 3, Bits 4-5: Bank 27 color */
-# define SSD1305_SETBANK28(c) (c << 6) /* Data 3, Bits 6-7: Bank 28 color */
-# define SSD1305_SETBANK29(c) (c) /* Data 4, Bits 0-1: Bank 29 color */
-# define SSD1305_SETBANK30(c) (c << 2) /* Data 4, Bits 2-3: Bank 30 color */
-# define SSD1305_SETBANK31(c) (c << 4) /* Data 4, Bits 4-5: Bank 31 color */
-# define SSD1305_SETBANK32(c) (c << 6) /* Data 4, Bits 6-7: Bank 32 color */
-#define SSD1305_MAPCOL0 0xa0 /* 0xa0: Column address 0 is mapped to SEG0 */
-#define SSD1305_MAPCOL131 0xa1 /* 0xa1: Column address 131 is mapped to SEG0 */
-#define SSD1305_DISPRAM 0xa4 /* 0xa4: Resume to RAM content display */
-#define SSD1305_DISPENTIRE 0xa5 /* 0xa5: Entire display ON */
-#define SSD1305_DISPNORMAL 0xa6 /* 0xa6: Normal display */
-#define SSD1305_DISPINVERTED 0xa7 /* 0xa7: Inverse display */
-
-#define SSD1305_SETMUX 0xa8 /* 0xa8: Set Multiplex Ratio*/
- /* Data 1: MUX ratio -1: 15-63 */
-#define SSD1305_DIMMODE 0xab /* 0xab: Dim mode setting */
- /* Data 1: Reserverd, must be zero */
- /* Data 2: Contrast for bank1: 0-255 */
- /* Data 3: Brightness for color bank: 0-255 */
-#define SSD1305_MSTRCONFIG 0xad /* 0xad: Master configuration */
-# define SSD1305_MSTRCONFIG_EXTVCC 0x8e /* Data 1: Select external Vcc */
-#define SSD1305_DISPONDIM 0xac /* 0xac: Display ON in dim mode */
-#define SSD1305_DISPOFF 0xae /* 0xae: Display OFF (sleep mode) */
-#define SSD1305_DISPON 0xaf /* 0xaf: Display ON in normal mode */
-#define SSD1305_SETPAGESTART 0xb0 /* 0xb0-b7: Set page start address */
-# define SSD1305_PAGESTART_MASK 0x07
-#define SSD1305_SETCOMNORMAL 0xc0 /* 0xc0: Set COM output, normal mode */
-#define SSD1305_SETCOMREMAPPED 0xc8 /* 0xc8: Set COM output, remapped mode */
-
-#define SSD1305_SETOFFSET 0xd3 /* 0xd3: Set display offset */
- /* Data 1: Vertical shift by COM: 0-63 */
-#define SSD1305_SETDCLK 0xd5 /* 0xd5: Set display clock divide ratio/oscillator */
-# define SSD1305_DCLKDIV_SHIFT (0) /* Data 1, Bits 0-3: DCLK divide ratio/frequency*/
-# define SSD1305_DCLKDIV_MASK 0x0f
-# define SSD1305_DCLKFREQ_SHIFT (4) /* Data 1, Bits 4-7: DCLK divide oscillator frequency */
-# define SSD1305_DCLKFREQ_MASK 0xf0
-#define SSD1305_SETCOLORMODE 0xd8 /* 0xd: Set area color and low power display modes */
-# define SSD1305_COLORMODE_MONO 0x00 /* Data 1, Bits 4-5: 00=monochrome */
-# define SSD1305_COLORMODE_COLOR 0x30 /* Data 1, Bits 4-5: 11=area color enable */
-# define SSD1305_POWERMODE_NORMAL 0x00 /* Data 1, Bits 0,2: 00=normal power mode */
-# define SSD1305_POWERMODE_LOW 0x05 /* Data 1, Bits 0,2: 11=low power display mode */
-#define SSD1305_SETPRECHARGE 0xd9 /* 0xd9: Set pre-charge period */
-# define SSD1305_PHASE1_SHIFT (0) /* Data 1, Bits 0-3: Phase 1 period of up to 15 DCLK clocks */
-# define SSD1305_PHASE1_MASK 0x0f
-# define SSD1305_PHASE2_SHIFT (4) /* Data 1, Bits 4-7: Phase 2 period of up to 15 DCLK clocks */
-# define SSD1305_PHASE2_MASK 0xf0
-#define SSD1305_SETCOMCONFIG 0xda /* 0xda: Set COM configuration */
-# define SSD1305_COMCONFIG_SEQ 0x02 /* Data 1, Bit 4: 0=Sequential COM pin configuration */
-# define SSD1305_COMCONFIG_ALT 0x12 /* Data 1, Bit 4: 1=Alternative COM pin configuration */
-# define SSD1305_COMCONFIG_NOREMAP 0x02 /* Data 1, Bit 5: 0=Disable COM Left/Right remap */
-# define SSD1305_COMCONFIG_REMAP 0x22 /* Data 1, Bit 5: 1=Enable COM Left/Right remap */
-#define SSD1305_SETVCOMHDESEL 0xdb /* 0xdb: Set VCOMH delselect level */
-# define SSD1305_VCOMH_x4p3 0x00 /* Data 1: ~0.43 x Vcc */
-# define SSD1305_VCOMH_x7p7 0x34 /* Data 1: ~0.77 x Vcc */
-# define SSD1305_VCOMH_x8p3 0x3c /* Data 1: ~0.83 x Vcc */
-#define SSD1305_ENTER_RMWMODE 0xe0 /* 0xe0: Enter the Read Modify Write mode */
-#define SSD1305_NOP 0xe3 /* 0xe3: NOP Command for no operation */
-#define SSD1305_EXIT_RMWMODE 0xee /* 0xee: Leave the Read Modify Write mode */
-
-/* Graphic Acceleration Commands ********************************************/
-
-#define SSD1305_HSCROLL_RIGHT 0x26 /* 0x26: Right horizontal scroll */
-#define SSD1305_HSCROLL_LEFT 0x27 /* 0x27: Left horizontal scroll */
- /* Data 1, Bits 0-2: Column scroll offset: 0-4 */
- /* Data 2, Bits 0-2: Start page address: 0-7 */
-#define SSD1305_HSCROLL_FRAMES6 0x00 /* Data 3, Bits 0-2: Timer interval, 000=6 frames */
-#define SSD1305_HSCROLL_FRAMES32 0x01 /* Data 3, Bits 0-2: Timer interval, 001=32 frames */
-#define SSD1305_HSCROLL_FRAMES64 0x02 /* Data 3, Bits 0-2: Timer interval, 010=64 frames */
-#define SSD1305_HSCROLL_FRAMES128 0x03 /* Data 3, Bits 0-2: Timer interval, 011=128 frames */
-#define SSD1305_HSCROLL_FRAMES3 0x04 /* Data 3, Bits 0-2: Timer interval, 100=3 frames */
-#define SSD1305_HSCROLL_FRAMES4 0x05 /* Data 3, Bits 0-2: Timer interval, 101=4 frames */
-#define SSD1305_HSCROLL_FRAMES2 0x06 /* Data 3, Bits 0-2: Timer interval, 110=2 frames */
- /* Data 4, Bits 0-2: End page address: 0-7 */
-
-#define SSD1305_VSCROLL_RIGHT 0x29 /* 0x26: Vertical and right horizontal scroll */
-#define SSD1305_VSCROLL_LEFT 0x2a /* 0x27: Vertical and left horizontal scroll */
- /* Data 1, Bits 0-2: Column scroll offset: 0-4 */
- /* Data 2, Bits 0-2: Start page address: 0-7 */
-#define SSD1305_VSCROLL_FRAMES6 0x00 /* Data 3, Bits 0-2: Timer interval, 000=6 frames */
-#define SSD1305_VSCROLL_FRAMES32 0x01 /* Data 3, Bits 0-2: Timer interval, 001=32 frames */
-#define SSD1305_VSCROLL_FRAMES64 0x02 /* Data 3, Bits 0-2: Timer interval, 010=64 frames */
-#define SSD1305_VSCROLL_FRAMES128 0x03 /* Data 3, Bits 0-2: Timer interval, 011=128 frames */
-#define SSD1305_VSCROLL_FRAMES3 0x04 /* Data 3, Bits 0-2: Timer interval, 100=3 frames */
-#define SSD1305_VSCROLL_FRAMES4 0x05 /* Data 3, Bits 0-2: Timer interval, 101=4 frames */
-#define SSD1305_VSCROLL_FRAMES2 0x06 /* Data 3, Bits 0-2: Timer interval, 110=2 frames */
- /* Data 4, Bits 0-2: End page address: 0-7 */
- /* Data 5, Bits 0-5: Vertical scrolling offset: 0-63 */
-#define SSD1305_SCROLL_STOP 0x2e /* 0x2e: Deactivate scroll */
-#define SSD1305_SCROLL_START 0x2f /* 0x2f: Activate scroll */
-#define SSD1305_VSCROLL_AREA 0xa3 /* 0xa3: Set vertical scroll area */
- /* Data 1: Number of rows in the top fixed area */
- /* Data 1: Number of rows in the scroll area */
-
-/* Status register bit definitions ******************************************/
-
-#define SSD1305_STATUS_DISPOFF (1 << 6) /* Bit 6: 1=Display off */
-
-#endif /* __DRIVERS_LCD_SSD1305_H */
+/**************************************************************************************
+ * drivers/lcd/ssd1305.h
+ * Definitions for the Solomon Systech SSD1305 132x64 Dot Matrix OLED/PLED
+ * Segment/Common Driver with C
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References: SSD1305.pdf, "Solomon Systech SSD1305 132x64 Dot Matrix OLED/PLED
+ * Segment/Common Driver with Controller," Solomon Systech Limited,
+ * http://www.solomon-systech.com, May, 2008.
+ *
+ * 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 __DRIVERS_LCD_SSD1305_H
+#define __DRIVERS_LCD_SSD1305_H
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+/* General Definitions ******************************************************/
+
+#define SSD1305_COLORA 0
+#define SSD1305_COLORB 1
+#define SSD1305_COLORC 2
+#define SSD1305_COLORD 3
+
+/* Fundamental Commands *****************************************************/
+#define SSD1305_SETCOLL 0x00 /* 0x00-0x0f: Set lower column address */
+# define SSD1305_COLL_MASK 0x0f
+#define SSD1305_SETCOLH 0x10 /* 0x10-0x1f: Set higher column address */
+# define SSD1305_COLH_MASK 0x0f
+#define SSD1305_ADDRMODE 0x20 /* 0x20: Set memory address mode */
+# define SSD1305_ADDRMODE_HOR 0x00 /* Data 1: Set horizontal address mode */
+# define SSD1305_ADDRMODE_VIRT 0x01 /* Data 1: Set virtal address mode */
+# define SSD1305_ADDRMODE_PAGE 0x02 /* Data 1: Set page address mode */
+#define SSD1305_SETCOLADDR 0x21 /* 0x21: Set column address */
+ /* Data 1: Column start address: 0-131 */
+ /* Data 2: Column end address: 0-131 */
+#define SSD1305_SETPAGEADDR 0x22 /* 0x22: Set page address */
+ /* Data 1: Page start address: 0x00-0x7d */
+ /* Data 2: Page end address: 0x00-0x7d */
+#define SSD1305_SETSTARTLINE 0x40 /* 0x40-7f: Set display start line */
+# define SSD1305_STARTLINE_MASK 0x3f
+
+#define SSD1305_SETCONTRAST 0x81 /* 0x81: Set contrast control */
+ /* Data 1: Set 1 of 256 contrast steps */
+#define SSD1305_SETBRIGHTNESS 0x82 /* 0x82: Set brightness */
+ /* Data 1: Set 1 of 256 contrast steps */
+#define SSD1305_SETLUT 0x91 /* 0x01: Set lookup table */
+ /* Data 1: Pulse width: 31-63 */
+ /* Data 2: Color A: 31-63 */
+ /* Data 3: Color B: 31-63 */
+ /* Data 4: Color C: 31-63 */
+#define SSD1305_SETBANKCOLOR1 0x92 /* 0x92: Set bank 1-16 color */
+# define SSD1305_SETBANK1(c) (c) /* Data 1, Bits 0-1: Bank 1 color */
+# define SSD1305_SETBANK2(c) (c << 2) /* Data 1, Bits 2-3: Bank 2 color */
+# define SSD1305_SETBANK3(c) (c << 4) /* Data 1, Bits 4-5: Bank 3 color */
+# define SSD1305_SETBANK4(c) (c << 6) /* Data 1, Bits 6-7: Bank 4 color */
+# define SSD1305_SETBANK5(c) (c) /* Data 2, Bits 0-1: Bank 5 color */
+# define SSD1305_SETBANK6(c) (c << 2) /* Data 2, Bits 2-3: Bank 6 color */
+# define SSD1305_SETBANK7(c) (c << 4) /* Data 2, Bits 4-5: Bank 7 color */
+# define SSD1305_SETBANK8(c) (c << 6) /* Data 2, Bits 6-7: Bank 8 color */
+# define SSD1305_SETBANK9(c) (c) /* Data 3, Bits 0-1: Bank 9 color */
+# define SSD1305_SETBANK10(c) (c << 2) /* Data 3, Bits 2-3: Bank 10 color */
+# define SSD1305_SETBANK11(c) (c << 4) /* Data 3, Bits 4-5: Bank 11 color */
+# define SSD1305_SETBANK12(c) (c << 6) /* Data 3, Bits 6-7: Bank 12 color */
+# define SSD1305_SETBANK13(c) (c) /* Data 4, Bits 0-1: Bank 13 color */
+# define SSD1305_SETBANK14(c) (c << 2) /* Data 4, Bits 2-3: Bank 14 color */
+# define SSD1305_SETBANK15(c) (c << 4) /* Data 4, Bits 4-5: Bank 15 color */
+# define SSD1305_SETBANK16(c) (c << 6) /* Data 4, Bits 6-7: Bank 16 color */
+#define SSD1305_SETBANKCOLOR2 0x93 /* 0x93: Set bank 17-32 color */
+# define SSD1305_SETBANK17(c) (c) /* Data 1, Bits 0-1: Bank 17 color */
+# define SSD1305_SETBANK18(c) (c << 2) /* Data 1, Bits 2-3: Bank 18 color */
+# define SSD1305_SETBANK19(c) (c << 4) /* Data 1, Bits 4-5: Bank 19 color */
+# define SSD1305_SETBANK20(c) (c << 6) /* Data 1, Bits 6-7: Bank 20 color */
+# define SSD1305_SETBANK21(c) (c) /* Data 2, Bits 0-1: Bank 21 color */
+# define SSD1305_SETBANK22(c) (c << 2) /* Data 2, Bits 2-3: Bank 22 color */
+# define SSD1305_SETBANK23(c) (c << 4) /* Data 2, Bits 4-5: Bank 23 color */
+# define SSD1305_SETBANK24(c) (c << 6) /* Data 2, Bits 6-7: Bank 24 color */
+# define SSD1305_SETBANK25(c) (c) /* Data 3, Bits 0-1: Bank 25 color */
+# define SSD1305_SETBANK26(c) (c << 2) /* Data 3, Bits 2-3: Bank 26 color */
+# define SSD1305_SETBANK27(c) (c << 4) /* Data 3, Bits 4-5: Bank 27 color */
+# define SSD1305_SETBANK28(c) (c << 6) /* Data 3, Bits 6-7: Bank 28 color */
+# define SSD1305_SETBANK29(c) (c) /* Data 4, Bits 0-1: Bank 29 color */
+# define SSD1305_SETBANK30(c) (c << 2) /* Data 4, Bits 2-3: Bank 30 color */
+# define SSD1305_SETBANK31(c) (c << 4) /* Data 4, Bits 4-5: Bank 31 color */
+# define SSD1305_SETBANK32(c) (c << 6) /* Data 4, Bits 6-7: Bank 32 color */
+#define SSD1305_MAPCOL0 0xa0 /* 0xa0: Column address 0 is mapped to SEG0 */
+#define SSD1305_MAPCOL131 0xa1 /* 0xa1: Column address 131 is mapped to SEG0 */
+#define SSD1305_DISPRAM 0xa4 /* 0xa4: Resume to RAM content display */
+#define SSD1305_DISPENTIRE 0xa5 /* 0xa5: Entire display ON */
+#define SSD1305_DISPNORMAL 0xa6 /* 0xa6: Normal display */
+#define SSD1305_DISPINVERTED 0xa7 /* 0xa7: Inverse display */
+
+#define SSD1305_SETMUX 0xa8 /* 0xa8: Set Multiplex Ratio*/
+ /* Data 1: MUX ratio -1: 15-63 */
+#define SSD1305_DIMMODE 0xab /* 0xab: Dim mode setting */
+ /* Data 1: Reserverd, must be zero */
+ /* Data 2: Contrast for bank1: 0-255 */
+ /* Data 3: Brightness for color bank: 0-255 */
+#define SSD1305_MSTRCONFIG 0xad /* 0xad: Master configuration */
+# define SSD1305_MSTRCONFIG_EXTVCC 0x8e /* Data 1: Select external Vcc */
+#define SSD1305_DISPONDIM 0xac /* 0xac: Display ON in dim mode */
+#define SSD1305_DISPOFF 0xae /* 0xae: Display OFF (sleep mode) */
+#define SSD1305_DISPON 0xaf /* 0xaf: Display ON in normal mode */
+#define SSD1305_SETPAGESTART 0xb0 /* 0xb0-b7: Set page start address */
+# define SSD1305_PAGESTART_MASK 0x07
+#define SSD1305_SETCOMNORMAL 0xc0 /* 0xc0: Set COM output, normal mode */
+#define SSD1305_SETCOMREMAPPED 0xc8 /* 0xc8: Set COM output, remapped mode */
+
+#define SSD1305_SETOFFSET 0xd3 /* 0xd3: Set display offset */
+ /* Data 1: Vertical shift by COM: 0-63 */
+#define SSD1305_SETDCLK 0xd5 /* 0xd5: Set display clock divide ratio/oscillator */
+# define SSD1305_DCLKDIV_SHIFT (0) /* Data 1, Bits 0-3: DCLK divide ratio/frequency*/
+# define SSD1305_DCLKDIV_MASK 0x0f
+# define SSD1305_DCLKFREQ_SHIFT (4) /* Data 1, Bits 4-7: DCLK divide oscillator frequency */
+# define SSD1305_DCLKFREQ_MASK 0xf0
+#define SSD1305_SETCOLORMODE 0xd8 /* 0xd: Set area color and low power display modes */
+# define SSD1305_COLORMODE_MONO 0x00 /* Data 1, Bits 4-5: 00=monochrome */
+# define SSD1305_COLORMODE_COLOR 0x30 /* Data 1, Bits 4-5: 11=area color enable */
+# define SSD1305_POWERMODE_NORMAL 0x00 /* Data 1, Bits 0,2: 00=normal power mode */
+# define SSD1305_POWERMODE_LOW 0x05 /* Data 1, Bits 0,2: 11=low power display mode */
+#define SSD1305_SETPRECHARGE 0xd9 /* 0xd9: Set pre-charge period */
+# define SSD1305_PHASE1_SHIFT (0) /* Data 1, Bits 0-3: Phase 1 period of up to 15 DCLK clocks */
+# define SSD1305_PHASE1_MASK 0x0f
+# define SSD1305_PHASE2_SHIFT (4) /* Data 1, Bits 4-7: Phase 2 period of up to 15 DCLK clocks */
+# define SSD1305_PHASE2_MASK 0xf0
+#define SSD1305_SETCOMCONFIG 0xda /* 0xda: Set COM configuration */
+# define SSD1305_COMCONFIG_SEQ 0x02 /* Data 1, Bit 4: 0=Sequential COM pin configuration */
+# define SSD1305_COMCONFIG_ALT 0x12 /* Data 1, Bit 4: 1=Alternative COM pin configuration */
+# define SSD1305_COMCONFIG_NOREMAP 0x02 /* Data 1, Bit 5: 0=Disable COM Left/Right remap */
+# define SSD1305_COMCONFIG_REMAP 0x22 /* Data 1, Bit 5: 1=Enable COM Left/Right remap */
+#define SSD1305_SETVCOMHDESEL 0xdb /* 0xdb: Set VCOMH delselect level */
+# define SSD1305_VCOMH_x4p3 0x00 /* Data 1: ~0.43 x Vcc */
+# define SSD1305_VCOMH_x7p7 0x34 /* Data 1: ~0.77 x Vcc */
+# define SSD1305_VCOMH_x8p3 0x3c /* Data 1: ~0.83 x Vcc */
+#define SSD1305_ENTER_RMWMODE 0xe0 /* 0xe0: Enter the Read Modify Write mode */
+#define SSD1305_NOP 0xe3 /* 0xe3: NOP Command for no operation */
+#define SSD1305_EXIT_RMWMODE 0xee /* 0xee: Leave the Read Modify Write mode */
+
+/* Graphic Acceleration Commands ********************************************/
+
+#define SSD1305_HSCROLL_RIGHT 0x26 /* 0x26: Right horizontal scroll */
+#define SSD1305_HSCROLL_LEFT 0x27 /* 0x27: Left horizontal scroll */
+ /* Data 1, Bits 0-2: Column scroll offset: 0-4 */
+ /* Data 2, Bits 0-2: Start page address: 0-7 */
+#define SSD1305_HSCROLL_FRAMES6 0x00 /* Data 3, Bits 0-2: Timer interval, 000=6 frames */
+#define SSD1305_HSCROLL_FRAMES32 0x01 /* Data 3, Bits 0-2: Timer interval, 001=32 frames */
+#define SSD1305_HSCROLL_FRAMES64 0x02 /* Data 3, Bits 0-2: Timer interval, 010=64 frames */
+#define SSD1305_HSCROLL_FRAMES128 0x03 /* Data 3, Bits 0-2: Timer interval, 011=128 frames */
+#define SSD1305_HSCROLL_FRAMES3 0x04 /* Data 3, Bits 0-2: Timer interval, 100=3 frames */
+#define SSD1305_HSCROLL_FRAMES4 0x05 /* Data 3, Bits 0-2: Timer interval, 101=4 frames */
+#define SSD1305_HSCROLL_FRAMES2 0x06 /* Data 3, Bits 0-2: Timer interval, 110=2 frames */
+ /* Data 4, Bits 0-2: End page address: 0-7 */
+
+#define SSD1305_VSCROLL_RIGHT 0x29 /* 0x26: Vertical and right horizontal scroll */
+#define SSD1305_VSCROLL_LEFT 0x2a /* 0x27: Vertical and left horizontal scroll */
+ /* Data 1, Bits 0-2: Column scroll offset: 0-4 */
+ /* Data 2, Bits 0-2: Start page address: 0-7 */
+#define SSD1305_VSCROLL_FRAMES6 0x00 /* Data 3, Bits 0-2: Timer interval, 000=6 frames */
+#define SSD1305_VSCROLL_FRAMES32 0x01 /* Data 3, Bits 0-2: Timer interval, 001=32 frames */
+#define SSD1305_VSCROLL_FRAMES64 0x02 /* Data 3, Bits 0-2: Timer interval, 010=64 frames */
+#define SSD1305_VSCROLL_FRAMES128 0x03 /* Data 3, Bits 0-2: Timer interval, 011=128 frames */
+#define SSD1305_VSCROLL_FRAMES3 0x04 /* Data 3, Bits 0-2: Timer interval, 100=3 frames */
+#define SSD1305_VSCROLL_FRAMES4 0x05 /* Data 3, Bits 0-2: Timer interval, 101=4 frames */
+#define SSD1305_VSCROLL_FRAMES2 0x06 /* Data 3, Bits 0-2: Timer interval, 110=2 frames */
+ /* Data 4, Bits 0-2: End page address: 0-7 */
+ /* Data 5, Bits 0-5: Vertical scrolling offset: 0-63 */
+#define SSD1305_SCROLL_STOP 0x2e /* 0x2e: Deactivate scroll */
+#define SSD1305_SCROLL_START 0x2f /* 0x2f: Activate scroll */
+#define SSD1305_VSCROLL_AREA 0xa3 /* 0xa3: Set vertical scroll area */
+ /* Data 1: Number of rows in the top fixed area */
+ /* Data 1: Number of rows in the scroll area */
+
+/* Status register bit definitions ******************************************/
+
+#define SSD1305_STATUS_DISPOFF (1 << 6) /* Bit 6: 1=Display off */
+
+#endif /* __DRIVERS_LCD_SSD1305_H */
diff --git a/nuttx/drivers/lcd/ug-9664hswag01.c b/nuttx/drivers/lcd/ug-9664hswag01.c
index bb49f20e6..e0e8e8e3a 100644
--- a/nuttx/drivers/lcd/ug-9664hswag01.c
+++ b/nuttx/drivers/lcd/ug-9664hswag01.c
@@ -4,7 +4,7 @@
* controller.
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Reference: "Product Specification, OEL Display Module, UG-9664HSWAG01", Univision
* Technology Inc., SAS1-6020-B, January 3, 2008.
diff --git a/nuttx/drivers/mmcsd/Kconfig b/nuttx/drivers/mmcsd/Kconfig
index fc682e706..c224f220a 100644
--- a/nuttx/drivers/mmcsd/Kconfig
+++ b/nuttx/drivers/mmcsd/Kconfig
@@ -40,7 +40,7 @@ config MMCSD_HAVECARDDETECT
config MMCSD_SPI
bool "MMC/SD spi transfer support"
default y
-
+
config MMCSD_SPICLOCK
int "MMC/SD maximum SPI clock"
default 20000000
diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs
index 48e5d4fb6..850456597 100644
--- a/nuttx/drivers/mmcsd/Make.defs
+++ b/nuttx/drivers/mmcsd/Make.defs
@@ -2,7 +2,7 @@
# drivers/mmcsd/Make.defs
#
# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mmcsd/mmcsd_csd.h b/nuttx/drivers/mmcsd/mmcsd_csd.h
index e35eacad5..d5343aa84 100644
--- a/nuttx/drivers/mmcsd/mmcsd_csd.h
+++ b/nuttx/drivers/mmcsd/mmcsd_csd.h
@@ -2,7 +2,7 @@
* drivers/mmcsd/mmcsd_csd.h
*
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mmcsd/mmcsd_debug.c b/nuttx/drivers/mmcsd/mmcsd_debug.c
index 03872f5cf..0bd7f896e 100644
--- a/nuttx/drivers/mmcsd/mmcsd_debug.c
+++ b/nuttx/drivers/mmcsd/mmcsd_debug.c
@@ -2,7 +2,7 @@
* drivers/mmcsd/mmcsd_debug.c
*
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mmcsd/mmcsd_internal.h b/nuttx/drivers/mmcsd/mmcsd_internal.h
index 577ebbba9..ed669cdfa 100644
--- a/nuttx/drivers/mmcsd/mmcsd_internal.h
+++ b/nuttx/drivers/mmcsd/mmcsd_internal.h
@@ -2,7 +2,7 @@
* drivers/mmcsd/mmcsd_internal.h
*
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c
index 90c73261a..d0bc6659c 100644
--- a/nuttx/drivers/mmcsd/mmcsd_sdio.c
+++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c
@@ -3171,7 +3171,9 @@ errout_with_buffers:
rwb_uninitialize(&priv->rwbuffer);
errout_with_hwinit:
#endif
- mmcsd_hwuninitialize(priv);
+ mmcsd_hwuninitialize(priv); /* This will free the private data structure */
+ return ret;
+
errout_with_alloc:
kfree(priv);
return ret;
diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.h b/nuttx/drivers/mmcsd/mmcsd_sdio.h
index 75c97bd65..9e3794e25 100644
--- a/nuttx/drivers/mmcsd/mmcsd_sdio.h
+++ b/nuttx/drivers/mmcsd/mmcsd_sdio.h
@@ -1,339 +1,339 @@
-/********************************************************************************************
- * drivers/mmcsd/mmcsd_sdio.h
- *
- * Copyright (C) 2009, 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.
- *
- ********************************************************************************************/
-
-#ifndef __DRIVERS_MMCSD_MMCSD_SDIO_H
-#define __DRIVERS_MMCSD_MMCSD_SDIO_H
-
-/********************************************************************************************
- * Included Files
- ********************************************************************************************/
-
-#include <nuttx/config.h>
-#include <stdint.h>
-
-/********************************************************************************************
- * Pre-Processor Definitions
- ********************************************************************************************/
-
-/* CMD8 Argument:
- * [31:12]: Reserved (shall be set to '0')
- * [11:8]: Supply Voltage (VHS) 0x1 (Range: 2.7-3.6 V)
- * [7:0]: Check Pattern (recommended 0xaa)
- * CMD8 Response: R7
- */
-
-#define MMCSD_CMD8VOLTAGE_SHIFT (8) /* Bits 8-11: Supply voltage */
-#define MMCSD_CMD8VOLTAGE_MASK ((uint32_t)0x0f << MMCSD_CMD8VOLTAGE_SHIFT)
-# define MMCSD_CMD8VOLTAGE_27 ((uint32_t)0x01 << MMCSD_CMD8VOLTAGE_SHIFT) /* 2.7-3.6V */
-#define MMCSD_CMD8ECHO_SHIFT (0) /* Bits 0-7: Check pattern */
-#define MMCSD_CMD8ECHO_MASK ((uint32_t)0xff << MMCSD_CMD8ECHO_SHIFT)
-# define MMCSD_CMD8CHECKPATTERN ((uint32_t)0xaa << MMCSD_CMD8ECHO_SHIFT)
-
-/* ACMD6 argument */
-
-#define MMCSD_ACMD6_BUSWIDTH_1 ((uint32_t)0) /* Bus width = 1-bit */
-#define MMCSD_ACMD6_BUSWIDTH_4 ((uint32_t)2) /* Bus width = 4-bit */
-
-/* ACMD41 argument */
-
-#define MMCSD_ACMD41_VOLTAGEWINDOW ((uint32_t)0x80100000)
-#define MMCSD_ACMD41_HIGHCAPACITY ((uint32_t)1 << 30)
-#define MMCSD_ACMD41_STDCAPACITY ((uint32_t)0)
-
-/* ACMD42 argument */
-
-#define MMCSD_ACMD42_CD_DISCONNECT ((uint32_t)0) /* Disconnect card detection logic */
-#define MMCSD_ACMD42_CD_CONNECT ((uint32_t)1) /* Connect card detection logic */
-
-/* R1 Card Status bit definitions */
-
-#define MMCSD_R1_OUTOFRANGE ((uint32_t)1 << 31) /* Bad argument */
-#define MMCSD_R1_ADDRESSERROR ((uint32_t)1 << 30) /* Bad address */
-#define MMCSD_R1_BLOCKLENERROR ((uint32_t)1 << 29) /* Bad block length */
-#define MMCSD_R1_ERASESEQERROR ((uint32_t)1 << 28) /* Erase cmd error */
-#define MMCSD_R1_ERASEPARAM ((uint32_t)1 << 27) /* Bad write blocks */
-#define MMCSD_R1_WPVIOLATION ((uint32_t)1 << 26) /* Erase access failure */
-#define MMCSD_R1_CARDISLOCKED ((uint32_t)1 << 25) /* Card is locked */
-#define MMCSD_R1_LOCKUNLOCKFAILED ((uint32_t)1 << 24) /* Password error */
-#define MMCSD_R1_COMCRCERROR ((uint32_t)1 << 23) /* CRC error */
-#define MMCSD_R1_ILLEGALCOMMAND ((uint32_t)1 << 22) /* Bad command */
-#define MMCSD_R1_CARDECCFAILED ((uint32_t)1 << 21) /* Failed to correct data */
-#define MMCSD_R1_CCERROR ((uint32_t)1 << 20) /* Card controller error */
-#define MMCSD_R1_ERROR ((uint32_t)1 << 19) /* General error */
-#define MMCSD_R1_UNDERRUN ((uint32_t)1 << 18) /* Underrun (MMC only) */
-#define MMCSD_R1_OVERRRUN ((uint32_t)1 << 17) /* Overrun (MMC only) */
-#define MMCSD_R1_CIDCSDOVERWRITE ((uint32_t)1 << 16) /* CID/CSD error */
-#define MMCSD_R1_WPERASESKIP ((uint32_t)1 << 15) /* Not all erased */
-#define MMCSD_R1_CARDECCDISABLED ((uint32_t)1 << 14) /* Internal ECC not used */
-#define MMCSD_R1_ERASERESET ((uint32_t)1 << 13) /* Reset sequence cleared */
-#define MMCSD_R1_STATE_SHIFT (9) /* Current card state */
-#define MMCSD_R1_STATE_MASK ((uint32_t)15 << MMCSD_R1_STATE_SHIFT)
- /* Card identification mode states */
-# define MMCSD_R1_STATE_IDLE ((uint32_t)0 << MMCSD_R1_STATE_SHIFT) /* 0=Idle state */
-# define MMCSD_R1_STATE_READY ((uint32_t)1 << MMCSD_R1_STATE_SHIFT) /* 1=Ready state */
-# define MMCSD_R1_STATE_IDENT ((uint32_t)2 << MMCSD_R1_STATE_SHIFT) /* 2=Identification state */
- /* Data transfer states */
-# define MMCSD_R1_STATE_STBY ((uint32_t)3 << MMCSD_R1_STATE_SHIFT) /* 3=Standby state */
-# define MMCSD_R1_STATE_TRAN ((uint32_t)4 << MMCSD_R1_STATE_SHIFT) /* 4=Transfer state */
-# define MMCSD_R1_STATE_DATA ((uint32_t)5 << MMCSD_R1_STATE_SHIFT) /* 5=Sending data state */
-# define MMCSD_R1_STATE_RCV ((uint32_t)6 << MMCSD_R1_STATE_SHIFT) /* 6=Receiving data state */
-# define MMCSD_R1_STATE_PRG ((uint32_t)7 << MMCSD_R1_STATE_SHIFT) /* 7=Programming state */
-# define MMCSD_R1_STATE_DIS ((uint32_t)8 << MMCSD_R1_STATE_SHIFT) /* 8=Disconnect state */
-#define MMCSD_R1_READYFORDATA ((uint32_t)1 << 8) /* Buffer empty */
-#define MMCSD_R1_APPCMD ((uint32_t)1 << 5) /* Next CMD is ACMD */
-#define MMCSD_R1_AKESEQERROR ((uint32_t)1 << 3) /* Authentication error */
-#define MMCSD_R1_ERRORMASK ((uint32_t)0xfdffe008) /* Error mask */
-
-#define IS_STATE(v,s) ((((uint32_t)v)&MMCSD_R1_STATE_MASK)==(s))
-
-/* R3 (OCR) */
-
-#define MMC_VDD_20_36 ((uint32_t)0x00ffff00) /* VDD voltage 2.0-3.6 */
-
-#define MMCSD_VDD_145_150 ((uint32_t)1 << 0) /* VDD voltage 1.45 - 1.50 */
-#define MMCSD_VDD_150_155 ((uint32_t)1 << 1) /* VDD voltage 1.50 - 1.55 */
-#define MMCSD_VDD_155_160 ((uint32_t)1 << 2) /* VDD voltage 1.55 - 1.60 */
-#define MMCSD_VDD_160_165 ((uint32_t)1 << 3) /* VDD voltage 1.60 - 1.65 */
-#define MMCSD_VDD_165_170 ((uint32_t)1 << 4) /* VDD voltage 1.65 - 1.70 */
-#define MMCSD_VDD_17_18 ((uint32_t)1 << 5) /* VDD voltage 1.7 - 1.8 */
-#define MMCSD_VDD_18_19 ((uint32_t)1 << 6) /* VDD voltage 1.8 - 1.9 */
-#define MMCSD_VDD_19_20 ((uint32_t)1 << 7) /* VDD voltage 1.9 - 2.0 */
-#define MMCSD_VDD_20_21 ((uint32_t)1 << 8) /* VDD voltage 2.0-2.1 */
-#define MMCSD_VDD_21_22 ((uint32_t)1 << 9) /* VDD voltage 2.1-2.2 */
-#define MMCSD_VDD_22_23 ((uint32_t)1 << 10) /* VDD voltage 2.2-2.3 */
-#define MMCSD_VDD_23_24 ((uint32_t)1 << 11) /* VDD voltage 2.3-2.4 */
-#define MMCSD_VDD_24_25 ((uint32_t)1 << 12) /* VDD voltage 2.4-2.5 */
-#define MMCSD_VDD_25_26 ((uint32_t)1 << 13) /* VDD voltage 2.5-2.6 */
-#define MMCSD_VDD_26_27 ((uint32_t)1 << 14) /* VDD voltage 2.6-2.7 */
-#define MMCSD_VDD_27_28 ((uint32_t)1 << 15) /* VDD voltage 2.7-2.8 */
-#define MMCSD_VDD_28_29 ((uint32_t)1 << 16) /* VDD voltage 2.8-2.9 */
-#define MMCSD_VDD_29_30 ((uint32_t)1 << 17) /* VDD voltage 2.9-3.0 */
-#define MMCSD_VDD_30_31 ((uint32_t)1 << 18) /* VDD voltage 3.0-3.1 */
-#define MMCSD_VDD_31_32 ((uint32_t)1 << 19) /* VDD voltage 3.1-3.2 */
-#define MMCSD_VDD_32_33 ((uint32_t)1 << 20) /* VDD voltage 3.2-3.3 */
-#define MMCSD_VDD_33_34 ((uint32_t)1 << 21) /* VDD voltage 3.3-3.4 */
-#define MMCSD_VDD_34_35 ((uint32_t)1 << 22) /* VDD voltage 3.4-3.5 */
-#define MMCSD_VDD_35_36 ((uint32_t)1 << 23) /* VDD voltage 3.5-3.6 */
-#define MMCSD_R3_HIGHCAPACITY ((uint32_t)1 << 30) /* true: Card supports block addressing */
-#define MMCSD_CARD_BUSY ((uint32_t)1 << 31) /* Card power-up busy bit */
-
-/* R6 Card Status bit definitions */
-
-#define MMCSD_R6_RCA_SHIFT (16) /* New published RCA */
-#define MMCSD_R6_RCA_MASK ((uint32_t)0xffff << MMCSD_R6_RCA_SHIFT)
-#define MMCSD_R6_COMCRCERROR ((uint32_t)1 << 15) /* CRC error */
-#define MMCSD_R6_ILLEGALCOMMAND ((uint32_t)1 << 14) /* Bad command */
-#define MMCSD_R6_ERROR ((uint32_t)1 << 13) /* General error */
-#define MMCSD_R6_STATE_SHIFT (9) /* Current card state */
-#define MMCSD_R6_STATE_MASK ((uint32_t)15 << MMCSD_R6_STATE_SHIFT)
- /* Card identification mode states */
-# define MMCSD_R6_STATE_IDLE ((uint32_t)0 << MMCSD_R6_STATE_SHIFT) /* 0=Idle state */
-# define MMCSD_R6_STATE_READY ((uint32_t)1 << MMCSD_R6_STATE_SHIFT) /* 1=Ready state */
-# define MMCSD_R6_STATE_IDENT ((uint32_t)2 << MMCSD_R6_STATE_SHIFT) /* 2=Identification state */
- /* Data transfer states */
-# define MMCSD_R6_STATE_STBY ((uint32_t)3 << MMCSD_R6_STATE_SHIFT) /* 3=Standby state */
-# define MMCSD_R6_STATE_TRAN ((uint32_t)4 << MMCSD_R6_STATE_SHIFT) /* 4=Transfer state */
-# define MMCSD_R6_STATE_DATA (5(uint32_t) << MMCSD_R6_STATE_SHIFT) /* 5=Sending data state */
-# define MMCSD_R6_STATE_RCV ((uint32_t)6 << MMCSD_R6_STATE_SHIFT) /* 6=Receiving data state */
-# define MMCSD_R6_STATE_PRG ((uint32_t)7 << MMCSD_R6_STATE_SHIFT) /* 7=Programming state */
-# define MMCSD_R6_STATE_DIS ((uint32_t) << MMCSD_R6_STATE_SHIFT) /* 8=Disconnect state */
-#define MMCSD_R6_ERRORMASK ((uint32_t)0x0000e000) /* Error mask */
-
-/* SD Configuration Register (SCR) encoding */
-
-#define MMCSD_SCR_BUSWIDTH_1BIT (1)
-#define MMCSD_SCR_BUSWIDTH_2BIT (2)
-#define MMCSD_SCR_BUSWIDTH_4BIT (4)
-#define MMCSD_SCR_BUSWIDTH_8BIT (8)
-
-/* Last 4 bytes of the 48-bit R7 response */
-
-#define MMCSD_R7VERSION_SHIFT (28) /* Bits 28-31: Command version number */
-#define MMCSD_R7VERSION_MASK ((uint32_t)0x0f << MMCSD_R7VERSION_SHIFT)
-#define MMCSD_R7VOLTAGE_SHIFT (8) /* Bits 8-11: Voltage accepted */
-#define MMCSD_R7VOLTAGE_MASK ((uint32_t)0x0f << MMCSD_R7VOLTAGE_SHIFT)
-# define MMCSD_R7VOLTAGE_27 ((uint32_t)0x01 << MMCSD_R7VOLTAGE_SHIFT) /* 2.7-3.6V */
-#define MMCSD_R7ECHO_SHIFT (0) /* Bits 0-7: Echoed check pattern */
-#define MMCSD_R7ECHO_MASK ((uint32_t)0xff << MMCSD_R7ECHO_SHIFT)
-# define MMCSD_R7CHECKPATTERN ((uint32_t)0xaa << MMCSD_R7ECHO_SHIFT)
-
-/********************************************************************************************
- * Public Types
- ********************************************************************************************/
-
-/* Decoded Card Identification (CID) register */
-
-struct mmcsd_cid_s
-{
- uint8_t mid; /* 127:120 8-bit Manufacturer ID */
- uint16_t oid; /* 119:104 16-bit OEM/Application ID (ascii) */
- uint8_t pnm[6]; /* 103:64 40-bit Product Name (ascii) + null terminator */
- uint8_t prv; /* 63:56 8-bit Product revision */
- uint32_t psn; /* 55:24 32-bit Product serial number */
- /* 23:20 4-bit (reserved) */
- uint16_t mdt; /* 19:8 12-bit Manufacturing date */
- uint8_t crc; /* 7:1 7-bit CRC7 */
- /* 0:0 1-bit (not used) */
-};
-
-/* Decoded Card Specific Data (CSD) register */
-
-struct mmcsd_csd_s
-{
- uint8_t csdstructure; /* 127:126 CSD structure */
- uint8_t mmcspecvers; /* 125:122 MMC Spec version (MMC only) */
-
- struct
- {
- uint8_t timeunit; /* 2:0 Time exponent */
- uint8_t timevalue; /* 6:3 Time mantissa */
- } taac; /* 119:112 Data read access-time-1 */
-
- uint8_t nsac; /* 111:104 Data read access-time-2 in CLK cycle(NSAC*100) */
-
- struct
- {
- uint8_t transferrateunit; /* 2:0 Rate exponent */
- uint8_t timevalue; /* 6:3 Rate mantissa */
- } transpeed; /* 103:96 Max. data transfer rate */
-
- uint16_t ccc; /* 95:84 Card command classes */
- uint8_t readbllen; /* 83:80 Max. read data block length */
- uint8_t readblpartial; /* 79:79 Partial blocks for read allowed */
- uint8_t writeblkmisalign; /* 78:78 Write block misalignment */
- uint8_t readblkmisalign; /* 77:77 Read block misalignment */
- uint8_t dsrimp; /* 76:76 DSR implemented */
-
- union
- {
-#ifdef CONFIG_MMCSD_MMCSUPPORT
- struct
- {
- uint16_t csize; /* 73:62 Device size */
- uint8_t vddrcurrmin; /* 61:59 Max. read current at Vdd min */
- uint8_t vddrcurrmax; /* 58:56 Max. read current at Vdd max */
- uint8_t vddwcurrmin; /* 55:53 Max. write current at Vdd min */
- uint8_t vddwcurrmax; /* 52:50 Max. write current at Vdd max */
- uint8_t csizemult; /* 49:47 Device size multiplier */
-
- union
- {
- struct /* MMC system specification version 3.1 */
- {
- uint8_t ergrpsize; /* 46:42 Erase group size (MMC 3.1) */
- uint8_t ergrpmult; /* 41:37 Erase group multiplier (MMC 3.1) */
- } mmc31;
- struct /* MMC system specification version 2.2 */
- {
- uint8_t sectorsize; /* 46:42 Erase sector size (MMC 2.2) */
- uint8_t ergrpsize; /* 41:37 Erase group size (MMC 2.2) */
- } mmc22;
- } er;
-
- uint8_t mmcwpgrpsize; /* 36:32 Write protect group size (MMC) */
- } mmc;
-#endif
- struct
- {
- uint16_t csize; /* 73:62 Device size */
- uint8_t vddrcurrmin; /* 61:59 Max. read current at Vdd min */
- uint8_t vddrcurrmax; /* 58:56 Max. read current at Vdd max */
- uint8_t vddwcurrmin; /* 55:53 Max. write current at Vdd min */
- uint8_t vddwcurrmax; /* 52:50 Max. write current at Vdd max */
- uint8_t csizemult; /* 49:47 Device size multiplier */
- uint8_t sderblen; /* 46:46 Erase single block enable (SD) */
- uint8_t sdsectorsize; /* 45:39 Erase sector size (SD) */
- uint8_t sdwpgrpsize; /* 38:32 Write protect group size (SD) */
- } sdbyte;
-
- struct
- {
- /* 73:70 (reserved) */
- uint32_t csize; /* 69:48 Device size */
- /* 47:47 (reserved) */
- uint8_t sderblen; /* 46:46 Erase single block enable (SD) */
- uint8_t sdsectorsize; /* 45:39 Erase sector size (SD) */
- uint8_t sdwpgrpsize; /* 38:32 Write protect group size (SD) */
- } sdblock;
- } u;
-
- uint8_t wpgrpen; /* 31:31 Write protect group enable */
- uint8_t mmcdfltecc; /* 30:29 Manufacturer default ECC (MMC) */
- uint8_t r2wfactor; /* 28:26 Write speed factor */
- uint8_t writebllen; /* 25:22 Max. write data block length */
- uint8_t writeblpartial; /* 21:21 Partial blocks for write allowed */
- uint8_t fileformatgrp; /* 15:15 File format group */
- uint8_t copy; /* 14:14 Copy flag (OTP) */
- uint8_t permwriteprotect; /* 13:13 Permanent write protection */
- uint8_t tmpwriteprotect; /* 12:12 Temporary write protection */
- uint8_t fileformat; /* 10:11 File format */
- uint8_t mmcecc; /* 9:8 ECC (MMC) */
- uint8_t crc; /* 7:1 CRC */
- /* 0:0 Not used */
-};
-
-struct mmcsd_scr_s
-{
- uint8_t scrversion; /* 63:60 Version of SCR structure */
- uint8_t sdversion; /* 59:56 SD memory card physical layer version */
- uint8_t erasestate; /* 55:55 Data state after erase (1 or 0) */
- uint8_t security; /* 54:52 SD security support */
- uint8_t buswidth; /* 51:48 DAT bus widthes supported */
- /* 47:32 SD reserved space */
- uint32_t mfgdata; /* 31:0 Reserved for manufacturing data */
-};
-
-/********************************************************************************************
- * Public Data
- ********************************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/********************************************************************************************
- * Public Functions
- ********************************************************************************************/
-
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-#endif /* __DRIVERS_MMCSD_MMCSD_SDIO_H */
+/********************************************************************************************
+ * drivers/mmcsd/mmcsd_sdio.h
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 __DRIVERS_MMCSD_MMCSD_SDIO_H
+#define __DRIVERS_MMCSD_MMCSD_SDIO_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+/********************************************************************************************
+ * Pre-Processor Definitions
+ ********************************************************************************************/
+
+/* CMD8 Argument:
+ * [31:12]: Reserved (shall be set to '0')
+ * [11:8]: Supply Voltage (VHS) 0x1 (Range: 2.7-3.6 V)
+ * [7:0]: Check Pattern (recommended 0xaa)
+ * CMD8 Response: R7
+ */
+
+#define MMCSD_CMD8VOLTAGE_SHIFT (8) /* Bits 8-11: Supply voltage */
+#define MMCSD_CMD8VOLTAGE_MASK ((uint32_t)0x0f << MMCSD_CMD8VOLTAGE_SHIFT)
+# define MMCSD_CMD8VOLTAGE_27 ((uint32_t)0x01 << MMCSD_CMD8VOLTAGE_SHIFT) /* 2.7-3.6V */
+#define MMCSD_CMD8ECHO_SHIFT (0) /* Bits 0-7: Check pattern */
+#define MMCSD_CMD8ECHO_MASK ((uint32_t)0xff << MMCSD_CMD8ECHO_SHIFT)
+# define MMCSD_CMD8CHECKPATTERN ((uint32_t)0xaa << MMCSD_CMD8ECHO_SHIFT)
+
+/* ACMD6 argument */
+
+#define MMCSD_ACMD6_BUSWIDTH_1 ((uint32_t)0) /* Bus width = 1-bit */
+#define MMCSD_ACMD6_BUSWIDTH_4 ((uint32_t)2) /* Bus width = 4-bit */
+
+/* ACMD41 argument */
+
+#define MMCSD_ACMD41_VOLTAGEWINDOW ((uint32_t)0x80100000)
+#define MMCSD_ACMD41_HIGHCAPACITY ((uint32_t)1 << 30)
+#define MMCSD_ACMD41_STDCAPACITY ((uint32_t)0)
+
+/* ACMD42 argument */
+
+#define MMCSD_ACMD42_CD_DISCONNECT ((uint32_t)0) /* Disconnect card detection logic */
+#define MMCSD_ACMD42_CD_CONNECT ((uint32_t)1) /* Connect card detection logic */
+
+/* R1 Card Status bit definitions */
+
+#define MMCSD_R1_OUTOFRANGE ((uint32_t)1 << 31) /* Bad argument */
+#define MMCSD_R1_ADDRESSERROR ((uint32_t)1 << 30) /* Bad address */
+#define MMCSD_R1_BLOCKLENERROR ((uint32_t)1 << 29) /* Bad block length */
+#define MMCSD_R1_ERASESEQERROR ((uint32_t)1 << 28) /* Erase cmd error */
+#define MMCSD_R1_ERASEPARAM ((uint32_t)1 << 27) /* Bad write blocks */
+#define MMCSD_R1_WPVIOLATION ((uint32_t)1 << 26) /* Erase access failure */
+#define MMCSD_R1_CARDISLOCKED ((uint32_t)1 << 25) /* Card is locked */
+#define MMCSD_R1_LOCKUNLOCKFAILED ((uint32_t)1 << 24) /* Password error */
+#define MMCSD_R1_COMCRCERROR ((uint32_t)1 << 23) /* CRC error */
+#define MMCSD_R1_ILLEGALCOMMAND ((uint32_t)1 << 22) /* Bad command */
+#define MMCSD_R1_CARDECCFAILED ((uint32_t)1 << 21) /* Failed to correct data */
+#define MMCSD_R1_CCERROR ((uint32_t)1 << 20) /* Card controller error */
+#define MMCSD_R1_ERROR ((uint32_t)1 << 19) /* General error */
+#define MMCSD_R1_UNDERRUN ((uint32_t)1 << 18) /* Underrun (MMC only) */
+#define MMCSD_R1_OVERRRUN ((uint32_t)1 << 17) /* Overrun (MMC only) */
+#define MMCSD_R1_CIDCSDOVERWRITE ((uint32_t)1 << 16) /* CID/CSD error */
+#define MMCSD_R1_WPERASESKIP ((uint32_t)1 << 15) /* Not all erased */
+#define MMCSD_R1_CARDECCDISABLED ((uint32_t)1 << 14) /* Internal ECC not used */
+#define MMCSD_R1_ERASERESET ((uint32_t)1 << 13) /* Reset sequence cleared */
+#define MMCSD_R1_STATE_SHIFT (9) /* Current card state */
+#define MMCSD_R1_STATE_MASK ((uint32_t)15 << MMCSD_R1_STATE_SHIFT)
+ /* Card identification mode states */
+# define MMCSD_R1_STATE_IDLE ((uint32_t)0 << MMCSD_R1_STATE_SHIFT) /* 0=Idle state */
+# define MMCSD_R1_STATE_READY ((uint32_t)1 << MMCSD_R1_STATE_SHIFT) /* 1=Ready state */
+# define MMCSD_R1_STATE_IDENT ((uint32_t)2 << MMCSD_R1_STATE_SHIFT) /* 2=Identification state */
+ /* Data transfer states */
+# define MMCSD_R1_STATE_STBY ((uint32_t)3 << MMCSD_R1_STATE_SHIFT) /* 3=Standby state */
+# define MMCSD_R1_STATE_TRAN ((uint32_t)4 << MMCSD_R1_STATE_SHIFT) /* 4=Transfer state */
+# define MMCSD_R1_STATE_DATA ((uint32_t)5 << MMCSD_R1_STATE_SHIFT) /* 5=Sending data state */
+# define MMCSD_R1_STATE_RCV ((uint32_t)6 << MMCSD_R1_STATE_SHIFT) /* 6=Receiving data state */
+# define MMCSD_R1_STATE_PRG ((uint32_t)7 << MMCSD_R1_STATE_SHIFT) /* 7=Programming state */
+# define MMCSD_R1_STATE_DIS ((uint32_t)8 << MMCSD_R1_STATE_SHIFT) /* 8=Disconnect state */
+#define MMCSD_R1_READYFORDATA ((uint32_t)1 << 8) /* Buffer empty */
+#define MMCSD_R1_APPCMD ((uint32_t)1 << 5) /* Next CMD is ACMD */
+#define MMCSD_R1_AKESEQERROR ((uint32_t)1 << 3) /* Authentication error */
+#define MMCSD_R1_ERRORMASK ((uint32_t)0xfdffe008) /* Error mask */
+
+#define IS_STATE(v,s) ((((uint32_t)v)&MMCSD_R1_STATE_MASK)==(s))
+
+/* R3 (OCR) */
+
+#define MMC_VDD_20_36 ((uint32_t)0x00ffff00) /* VDD voltage 2.0-3.6 */
+
+#define MMCSD_VDD_145_150 ((uint32_t)1 << 0) /* VDD voltage 1.45 - 1.50 */
+#define MMCSD_VDD_150_155 ((uint32_t)1 << 1) /* VDD voltage 1.50 - 1.55 */
+#define MMCSD_VDD_155_160 ((uint32_t)1 << 2) /* VDD voltage 1.55 - 1.60 */
+#define MMCSD_VDD_160_165 ((uint32_t)1 << 3) /* VDD voltage 1.60 - 1.65 */
+#define MMCSD_VDD_165_170 ((uint32_t)1 << 4) /* VDD voltage 1.65 - 1.70 */
+#define MMCSD_VDD_17_18 ((uint32_t)1 << 5) /* VDD voltage 1.7 - 1.8 */
+#define MMCSD_VDD_18_19 ((uint32_t)1 << 6) /* VDD voltage 1.8 - 1.9 */
+#define MMCSD_VDD_19_20 ((uint32_t)1 << 7) /* VDD voltage 1.9 - 2.0 */
+#define MMCSD_VDD_20_21 ((uint32_t)1 << 8) /* VDD voltage 2.0-2.1 */
+#define MMCSD_VDD_21_22 ((uint32_t)1 << 9) /* VDD voltage 2.1-2.2 */
+#define MMCSD_VDD_22_23 ((uint32_t)1 << 10) /* VDD voltage 2.2-2.3 */
+#define MMCSD_VDD_23_24 ((uint32_t)1 << 11) /* VDD voltage 2.3-2.4 */
+#define MMCSD_VDD_24_25 ((uint32_t)1 << 12) /* VDD voltage 2.4-2.5 */
+#define MMCSD_VDD_25_26 ((uint32_t)1 << 13) /* VDD voltage 2.5-2.6 */
+#define MMCSD_VDD_26_27 ((uint32_t)1 << 14) /* VDD voltage 2.6-2.7 */
+#define MMCSD_VDD_27_28 ((uint32_t)1 << 15) /* VDD voltage 2.7-2.8 */
+#define MMCSD_VDD_28_29 ((uint32_t)1 << 16) /* VDD voltage 2.8-2.9 */
+#define MMCSD_VDD_29_30 ((uint32_t)1 << 17) /* VDD voltage 2.9-3.0 */
+#define MMCSD_VDD_30_31 ((uint32_t)1 << 18) /* VDD voltage 3.0-3.1 */
+#define MMCSD_VDD_31_32 ((uint32_t)1 << 19) /* VDD voltage 3.1-3.2 */
+#define MMCSD_VDD_32_33 ((uint32_t)1 << 20) /* VDD voltage 3.2-3.3 */
+#define MMCSD_VDD_33_34 ((uint32_t)1 << 21) /* VDD voltage 3.3-3.4 */
+#define MMCSD_VDD_34_35 ((uint32_t)1 << 22) /* VDD voltage 3.4-3.5 */
+#define MMCSD_VDD_35_36 ((uint32_t)1 << 23) /* VDD voltage 3.5-3.6 */
+#define MMCSD_R3_HIGHCAPACITY ((uint32_t)1 << 30) /* true: Card supports block addressing */
+#define MMCSD_CARD_BUSY ((uint32_t)1 << 31) /* Card power-up busy bit */
+
+/* R6 Card Status bit definitions */
+
+#define MMCSD_R6_RCA_SHIFT (16) /* New published RCA */
+#define MMCSD_R6_RCA_MASK ((uint32_t)0xffff << MMCSD_R6_RCA_SHIFT)
+#define MMCSD_R6_COMCRCERROR ((uint32_t)1 << 15) /* CRC error */
+#define MMCSD_R6_ILLEGALCOMMAND ((uint32_t)1 << 14) /* Bad command */
+#define MMCSD_R6_ERROR ((uint32_t)1 << 13) /* General error */
+#define MMCSD_R6_STATE_SHIFT (9) /* Current card state */
+#define MMCSD_R6_STATE_MASK ((uint32_t)15 << MMCSD_R6_STATE_SHIFT)
+ /* Card identification mode states */
+# define MMCSD_R6_STATE_IDLE ((uint32_t)0 << MMCSD_R6_STATE_SHIFT) /* 0=Idle state */
+# define MMCSD_R6_STATE_READY ((uint32_t)1 << MMCSD_R6_STATE_SHIFT) /* 1=Ready state */
+# define MMCSD_R6_STATE_IDENT ((uint32_t)2 << MMCSD_R6_STATE_SHIFT) /* 2=Identification state */
+ /* Data transfer states */
+# define MMCSD_R6_STATE_STBY ((uint32_t)3 << MMCSD_R6_STATE_SHIFT) /* 3=Standby state */
+# define MMCSD_R6_STATE_TRAN ((uint32_t)4 << MMCSD_R6_STATE_SHIFT) /* 4=Transfer state */
+# define MMCSD_R6_STATE_DATA (5(uint32_t) << MMCSD_R6_STATE_SHIFT) /* 5=Sending data state */
+# define MMCSD_R6_STATE_RCV ((uint32_t)6 << MMCSD_R6_STATE_SHIFT) /* 6=Receiving data state */
+# define MMCSD_R6_STATE_PRG ((uint32_t)7 << MMCSD_R6_STATE_SHIFT) /* 7=Programming state */
+# define MMCSD_R6_STATE_DIS ((uint32_t) << MMCSD_R6_STATE_SHIFT) /* 8=Disconnect state */
+#define MMCSD_R6_ERRORMASK ((uint32_t)0x0000e000) /* Error mask */
+
+/* SD Configuration Register (SCR) encoding */
+
+#define MMCSD_SCR_BUSWIDTH_1BIT (1)
+#define MMCSD_SCR_BUSWIDTH_2BIT (2)
+#define MMCSD_SCR_BUSWIDTH_4BIT (4)
+#define MMCSD_SCR_BUSWIDTH_8BIT (8)
+
+/* Last 4 bytes of the 48-bit R7 response */
+
+#define MMCSD_R7VERSION_SHIFT (28) /* Bits 28-31: Command version number */
+#define MMCSD_R7VERSION_MASK ((uint32_t)0x0f << MMCSD_R7VERSION_SHIFT)
+#define MMCSD_R7VOLTAGE_SHIFT (8) /* Bits 8-11: Voltage accepted */
+#define MMCSD_R7VOLTAGE_MASK ((uint32_t)0x0f << MMCSD_R7VOLTAGE_SHIFT)
+# define MMCSD_R7VOLTAGE_27 ((uint32_t)0x01 << MMCSD_R7VOLTAGE_SHIFT) /* 2.7-3.6V */
+#define MMCSD_R7ECHO_SHIFT (0) /* Bits 0-7: Echoed check pattern */
+#define MMCSD_R7ECHO_MASK ((uint32_t)0xff << MMCSD_R7ECHO_SHIFT)
+# define MMCSD_R7CHECKPATTERN ((uint32_t)0xaa << MMCSD_R7ECHO_SHIFT)
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/* Decoded Card Identification (CID) register */
+
+struct mmcsd_cid_s
+{
+ uint8_t mid; /* 127:120 8-bit Manufacturer ID */
+ uint16_t oid; /* 119:104 16-bit OEM/Application ID (ascii) */
+ uint8_t pnm[6]; /* 103:64 40-bit Product Name (ascii) + null terminator */
+ uint8_t prv; /* 63:56 8-bit Product revision */
+ uint32_t psn; /* 55:24 32-bit Product serial number */
+ /* 23:20 4-bit (reserved) */
+ uint16_t mdt; /* 19:8 12-bit Manufacturing date */
+ uint8_t crc; /* 7:1 7-bit CRC7 */
+ /* 0:0 1-bit (not used) */
+};
+
+/* Decoded Card Specific Data (CSD) register */
+
+struct mmcsd_csd_s
+{
+ uint8_t csdstructure; /* 127:126 CSD structure */
+ uint8_t mmcspecvers; /* 125:122 MMC Spec version (MMC only) */
+
+ struct
+ {
+ uint8_t timeunit; /* 2:0 Time exponent */
+ uint8_t timevalue; /* 6:3 Time mantissa */
+ } taac; /* 119:112 Data read access-time-1 */
+
+ uint8_t nsac; /* 111:104 Data read access-time-2 in CLK cycle(NSAC*100) */
+
+ struct
+ {
+ uint8_t transferrateunit; /* 2:0 Rate exponent */
+ uint8_t timevalue; /* 6:3 Rate mantissa */
+ } transpeed; /* 103:96 Max. data transfer rate */
+
+ uint16_t ccc; /* 95:84 Card command classes */
+ uint8_t readbllen; /* 83:80 Max. read data block length */
+ uint8_t readblpartial; /* 79:79 Partial blocks for read allowed */
+ uint8_t writeblkmisalign; /* 78:78 Write block misalignment */
+ uint8_t readblkmisalign; /* 77:77 Read block misalignment */
+ uint8_t dsrimp; /* 76:76 DSR implemented */
+
+ union
+ {
+#ifdef CONFIG_MMCSD_MMCSUPPORT
+ struct
+ {
+ uint16_t csize; /* 73:62 Device size */
+ uint8_t vddrcurrmin; /* 61:59 Max. read current at Vdd min */
+ uint8_t vddrcurrmax; /* 58:56 Max. read current at Vdd max */
+ uint8_t vddwcurrmin; /* 55:53 Max. write current at Vdd min */
+ uint8_t vddwcurrmax; /* 52:50 Max. write current at Vdd max */
+ uint8_t csizemult; /* 49:47 Device size multiplier */
+
+ union
+ {
+ struct /* MMC system specification version 3.1 */
+ {
+ uint8_t ergrpsize; /* 46:42 Erase group size (MMC 3.1) */
+ uint8_t ergrpmult; /* 41:37 Erase group multiplier (MMC 3.1) */
+ } mmc31;
+ struct /* MMC system specification version 2.2 */
+ {
+ uint8_t sectorsize; /* 46:42 Erase sector size (MMC 2.2) */
+ uint8_t ergrpsize; /* 41:37 Erase group size (MMC 2.2) */
+ } mmc22;
+ } er;
+
+ uint8_t mmcwpgrpsize; /* 36:32 Write protect group size (MMC) */
+ } mmc;
+#endif
+ struct
+ {
+ uint16_t csize; /* 73:62 Device size */
+ uint8_t vddrcurrmin; /* 61:59 Max. read current at Vdd min */
+ uint8_t vddrcurrmax; /* 58:56 Max. read current at Vdd max */
+ uint8_t vddwcurrmin; /* 55:53 Max. write current at Vdd min */
+ uint8_t vddwcurrmax; /* 52:50 Max. write current at Vdd max */
+ uint8_t csizemult; /* 49:47 Device size multiplier */
+ uint8_t sderblen; /* 46:46 Erase single block enable (SD) */
+ uint8_t sdsectorsize; /* 45:39 Erase sector size (SD) */
+ uint8_t sdwpgrpsize; /* 38:32 Write protect group size (SD) */
+ } sdbyte;
+
+ struct
+ {
+ /* 73:70 (reserved) */
+ uint32_t csize; /* 69:48 Device size */
+ /* 47:47 (reserved) */
+ uint8_t sderblen; /* 46:46 Erase single block enable (SD) */
+ uint8_t sdsectorsize; /* 45:39 Erase sector size (SD) */
+ uint8_t sdwpgrpsize; /* 38:32 Write protect group size (SD) */
+ } sdblock;
+ } u;
+
+ uint8_t wpgrpen; /* 31:31 Write protect group enable */
+ uint8_t mmcdfltecc; /* 30:29 Manufacturer default ECC (MMC) */
+ uint8_t r2wfactor; /* 28:26 Write speed factor */
+ uint8_t writebllen; /* 25:22 Max. write data block length */
+ uint8_t writeblpartial; /* 21:21 Partial blocks for write allowed */
+ uint8_t fileformatgrp; /* 15:15 File format group */
+ uint8_t copy; /* 14:14 Copy flag (OTP) */
+ uint8_t permwriteprotect; /* 13:13 Permanent write protection */
+ uint8_t tmpwriteprotect; /* 12:12 Temporary write protection */
+ uint8_t fileformat; /* 10:11 File format */
+ uint8_t mmcecc; /* 9:8 ECC (MMC) */
+ uint8_t crc; /* 7:1 CRC */
+ /* 0:0 Not used */
+};
+
+struct mmcsd_scr_s
+{
+ uint8_t scrversion; /* 63:60 Version of SCR structure */
+ uint8_t sdversion; /* 59:56 SD memory card physical layer version */
+ uint8_t erasestate; /* 55:55 Data state after erase (1 or 0) */
+ uint8_t security; /* 54:52 SD security support */
+ uint8_t buswidth; /* 51:48 DAT bus widthes supported */
+ /* 47:32 SD reserved space */
+ uint32_t mfgdata; /* 31:0 Reserved for manufacturing data */
+};
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __DRIVERS_MMCSD_MMCSD_SDIO_H */
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.h b/nuttx/drivers/mmcsd/mmcsd_spi.h
index 055862beb..8c6f9bae7 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.h
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.h
@@ -2,7 +2,7 @@
* drivers/mmcsd/mmcsd_spi.h
*
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mtd/at45db.c b/nuttx/drivers/mtd/at45db.c
index f4a695de0..f3c0c72c1 100644
--- a/nuttx/drivers/mtd/at45db.c
+++ b/nuttx/drivers/mtd/at45db.c
@@ -3,7 +3,7 @@
* Driver for SPI-based AT45DB161D (16Mbit)
*
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mtd/flash_eraseall.c b/nuttx/drivers/mtd/flash_eraseall.c
index 77666ff03..ce0cfe649 100644
--- a/nuttx/drivers/mtd/flash_eraseall.c
+++ b/nuttx/drivers/mtd/flash_eraseall.c
@@ -2,7 +2,7 @@
* drivers/mtd/flash_eraseall.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index b16397883..cdb35aa5c 100644
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -2,7 +2,7 @@
* drivers/mtd/ftl.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mtd/skeleton.c b/nuttx/drivers/mtd/skeleton.c
index 673ddadb3..a2fb98238 100644
--- a/nuttx/drivers/mtd/skeleton.c
+++ b/nuttx/drivers/mtd/skeleton.c
@@ -2,7 +2,7 @@
* drivers/mtd/skeleton.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/mtd/sst25.c b/nuttx/drivers/mtd/sst25.c
index 01838f078..66d201add 100644
--- a/nuttx/drivers/mtd/sst25.c
+++ b/nuttx/drivers/mtd/sst25.c
@@ -1,5 +1,5 @@
/************************************************************************************
- * drivers/mtd/m25px.c
+ * drivers/mtd/sst25.c
* Driver for SPI-based SST25 FLASH.
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
diff --git a/nuttx/drivers/net/Kconfig b/nuttx/drivers/net/Kconfig
index 988b96c94..b5c09bf01 100644
--- a/nuttx/drivers/net/Kconfig
+++ b/nuttx/drivers/net/Kconfig
@@ -36,9 +36,13 @@ config ENC28J60_NINTERFACES
config ENC28J60_SPIMODE
int "SPI mode"
- default 2
+ default 0
---help---
- Controls the SPI mode
+ Controls the SPI mode. The ENC28J60 spec says that it supports SPI
+ mode 0,0 only: "The implementation used on this device supports SPI
+ mode 0,0 only. In addition, the SPI port requires that SCK be at Idle
+ in a low state; selectable clock polarity is not supported."
+ However, sometimes you need to tinker with these things.
config ENC28J60_FREQUENCY
int "SPI frequency"
diff --git a/nuttx/drivers/net/Make.defs b/nuttx/drivers/net/Make.defs
index ab256cd8a..bb0d6a718 100644
--- a/nuttx/drivers/net/Make.defs
+++ b/nuttx/drivers/net/Make.defs
@@ -1,8 +1,8 @@
############################################################################
# drivers/net/Make.defs
#
-# Copyright (C) 2007, 2010-2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Copyright (C) 2007, 2010-2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -47,7 +47,7 @@ ifeq ($(CONFIG_NET_CS89x0),y)
CSRCS += cs89x0.c
endif
-ifeq ($(CONFIG_NET_ENC28J60),y)
+ifeq ($(CONFIG_ENC28J60),y)
CSRCS += enc28j60.c
endif
diff --git a/nuttx/drivers/net/cs89x0.c b/nuttx/drivers/net/cs89x0.c
index 0f301ee00..22b9b87a5 100644
--- a/nuttx/drivers/net/cs89x0.c
+++ b/nuttx/drivers/net/cs89x0.c
@@ -2,7 +2,7 @@
* drivers/net/cs89x0.c
*
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/net/cs89x0.h b/nuttx/drivers/net/cs89x0.h
index c2073eb98..f6d99120a 100644
--- a/nuttx/drivers/net/cs89x0.h
+++ b/nuttx/drivers/net/cs89x0.h
@@ -1,326 +1,326 @@
-/****************************************************************************
- * drivers/net/cs89x0.h
- *
- * Copyright (C) 2009 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 __DRIVERS_NET_CS89x0_H
-#define __DRIVERS_NET_CS89x0_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* CONFIG_CS89x0_ALIGN16/32 determines if the 16-bit CS89x0 registers are
- * aligned to 16-bit or 32-bit address boundaries. NOTE: If there multiple
- * CS89x00 parts in the board architecture, we assume that the address
- * alignment is the same for all implementations. If that is not the
- * case, then it will be necessary to move a shift value into
- * the cs89x0_driver_s structure and calculate the offsets dynamically in
- * the putreg and getreg functions.
- */
-
-#if defined(CONFIG_CS89x0_ALIGN16)
-# define CS89x0_RTDATA_OFFSET (0 << 1)
-# define CS89x0_TxCMD_OFFSET (2 << 1)
-# define CS89x0_TxLEN_OFFSET (3 << 1)
-# define CS89x0_ISQ_OFFSET (4 << 1)
-# define CS89x0_PPTR_OFFSET (5 << 1)
-# define CS89x0_PDATA_OFFSET (6 << 1)
-#elif defined(CONFIG_CS89x0_ALIGN32)
-# define CS89x0_RTDATA_OFFSET (0 << 2)
-# define CS89x0_TxCMD_OFFSET (2 << 2)
-# define CS89x0_TxLEN_OFFSET (3 << 2)
-# define CS89x0_ISQ_OFFSET (4 << 2)
-# define CS89x0_PPTR_OFFSET (5 << 2)
-# define CS89x0_PDATA_OFFSET (6 << 2)
-#else
-# error "CS89x00 address alignment is not defined"
-#endif
-
-/* ISQ register bit definitions */
-
-#define ISQ_EVENTMASK 0x003f /* Bits 0-5 indicate the status register */
-#define ISQ_RXEVENT 0x0004
-#define ISQ_TXEVENT 0x0008
-#define ISQ_BUFEVENT 0x000c
-#define ISQ_RXMISSEVENT 0x0010
-#define ISQ_TXCOLEVENT 0x0012
-
-/* ISQ register TxEVENT bit definitions*/
-
-#define ISQ_RXEVENT_IAHASH (1 << 6)
-#define ISQ_RXEVENT_DRIBBLE (1 << 7)
-#define ISQ_RXEVENT_RXOK (1 << 8)
-#define ISQ_RXEVENT_HASHED (1 << 9)
-#define ISQ_RXEVENT_HASHNDX_SHIFT 10
-#define ISQ_RXEVENT_HASHNDX_MASK (0x3f << ISQ_RXEVENT_HASHNDX_SHIFT)
-
-/* ISQ register TxEVENT bit definitions*/
-
-#define ISQ_TXEVENT_LOSSOFCRS (1 << 6)
-#define ISQ_TXEVENT_SQEERROR (1 << 7)
-#define ISQ_TXEVENT_TXOK (1 << 8)
-#define ISQ_TXEVENT_OUTWINDOW (1 << 9)
-#define ISQ_TXEVENT_JABBER (1 << 10)
-#define ISQ_TXEVENT_NCOLLISION_SHIFT 11
-#define ISQ_TXEVENT_NCOLLISION_MASK (15 << ISQ_TXEVENT_NCOLLISION_SHIFT)
-#define ISQ_TXEVENT_16COLL (1 << 15)
-
-/* ISQ register BufEVENT bit definitions */
-
-#define ISQ_BUFEVENT_SWINT (1 << 6)
-#define ISQ_BUFEVENT_RXDMAFRAME (1 << 7)
-#define ISQ_BUFEVENT_RDY4TX (1 << 8)
-#define ISQ_BUFEVENT_TXUNDERRUN (1 << 9)
-#define ISQ_BUFEVENT_RXMISS (1 << 10)
-#define ISQ_BUFEVENT_RX128 (1 << 11)
-#define ISQ_BUFEVENT_RXDEST (1 << 15)
-
-/* Packet page register offsets *********************************************/
-
-/* 0x0000 Bus interface registers */
-
-#define PPR_CHIPID 0x0000 /* Chip identifier - must be 0x630E */
-#define PPR_CHIPREV 0x0002 /* Chip revision, model codes */
-#define PPR_IOBASEADDRESS 0x0020 /* I/O Base Address */
-#define PPR_INTREG 0x0022 /* Interrupt configuration */
-# define PPR_INTREG_IRQ0 0x0000 /* Use INTR0 pin */
-# define PPR_INTREG_IRQ1 0x0001 /* Use INTR1 pin */
-# define PPR_INTREG_IRQ2 0x0002 /* Use INTR2 pin */
-# define PPR_INTREG_IRQ3 0x0003 /* Use INTR3 pin */
-
-#define PPR_DMACHANNELNUMBER 0x0024 /* DMA Channel Number (0,1, or 2) */
-#define PPR_DMASTARTOFFRAME 0x0026 /* DMA Start of Frame */
-#define PPR_DMAFRAMECOUNT 0x0028 /* DMA Frame Count (12-bits) */
-#define PPR_RXDMABYTECOUNT 0x002a /* Rx DMA Byte Count */
-#define PPR_MEMORYBASEADDRESS 0x002c /* Memory Base Address Register (20-bit) */
-#define PPR_BOOTPROMBASEADDRESS 0x0030 /* Boot PROM Base Address */
-#define PPR_BOOTPROMADDRESSMASK 0x0034 /* Boot PROM Address Mask */
-#define PPR_EEPROMCOMMAND 0x0040 /* EEPROM Command */
-#define PPR_EEPROMDATA 0x0042 /* EEPROM Data */
-#define PPR_RECVFRAMEBYTES 0x0050 /* Received Frame Byte Counter */
-
-/* 0x0100 - Configuration and control registers */
-
-#define PPR_RXCFG 0x0102 /* Receiver configuration */
-# define PPR_RXCFG_SKIP1 (1 << 6) /* Skip (discard) current frame */
-# define PPR_RXCFG_STREAM (1 << 7) /* Enable streaming mode */
-# define PPR_RXCFG_RXOK (1 << 8) /* RxOK interrupt enable */
-# define PPR_RxCFG_RxDMAonly (1 << 9) /* Use RxDMA for all frames */
-# define PPR_RxCFG_AutoRxDMA (1 << 10) /* Select RxDMA automatically */
-# define PPR_RxCFG_BufferCRC (1 << 11) /* Include CRC characters in frame */
-# define PPR_RxCFG_CRC (1 << 12) /* Enable interrupt on CRC error */
-# define PPR_RxCFG_RUNT (1 << 13) /* Enable interrupt on RUNT frames */
-# define PPR_RxCFG_EXTRA (1 << 14) /* Enable interrupt on frames with extra data */
-
-#define PPR_RXCTL 0x0104 /* Receiver control */
-# define PPR_RXCTL_IAHASH (1 << 6) /* Accept frames that match hash */
-# define PPR_RXCTL_PROMISCUOUS (1 << 7) /* Accept any frame */
-# define PPR_RXCTL_RXOK (1 << 8) /* Accept well formed frames */
-# define PPR_RXCTL_MULTICAST (1 << 9) /* Accept multicast frames */
-# define PPR_RXCTL_IA (1 << 10) /* Accept frame that matches IA */
-# define PPR_RXCTL_BROADCAST (1 << 11) /* Accept broadcast frames */
-# define PPR_RXCTL_CRC (1 << 12) /* Accept frames with bad CRC */
-# define PPR_RXCTL_RUNT (1 << 13) /* Accept runt frames */
-# define PPR_RXCTL_EXTRA (1 << 14) /* Accept frames that are too long */
-
-#define PPR_TXCFG 0x0106 /* Transmit configuration */
-# define PPR_TXCFG_CRS (1 << 6) /* Enable interrupt on loss of carrier */
-# define PPR_TXCFG_SQE (1 << 7) /* Enable interrupt on Signal Quality Error */
-# define PPR_TXCFG_TXOK (1 << 8) /* Enable interrupt on successful xmits */
-# define PPR_TXCFG_LATE (1 << 9) /* Enable interrupt on "out of window" */
-# define PPR_TXCFG_JABBER (1 << 10) /* Enable interrupt on jabber detect */
-# define PPR_TXCFG_COLLISION (1 << 11) /* Enable interrupt if collision */
-# define PPR_TXCFG_16COLLISIONS (1 << 15) /* Enable interrupt if > 16 collisions */
-
-#define PPR_TXCMD 0x0108 /* Transmit command status */
-# define PPR_TXCMD_TXSTART5 (0 << 6) /* Start after 5 bytes in buffer */
-# define PPR_TXCMD_TXSTART381 (1 << 6) /* Start after 381 bytes in buffer */
-# define PPR_TXCMD_TXSTART1021 (2 << 6) /* Start after 1021 bytes in buffer */
-# define PPR_TXCMD_TXSTARTFULL (3 << 6) /* Start after all bytes loaded */
-# define PPR_TXCMD_FORCE (1 << 8) /* Discard any pending packets */
-# define PPR_TXCMD_ONECOLLISION (1 << 9) /* Abort after a single collision */
-# define PPR_TXCMD_NOCRC (1 << 12) /* Do not add CRC */
-# define PPR_TXCMD_NOPAD (1 << 13) /* Do not pad short packets */
-
-#define PPR_BUFCFG 0x010a /* Buffer configuration */
-# define PPR_BUFCFG_SWI (1 << 6) /* Force interrupt via software */
-# define PPR_BUFCFG_RXDMA (1 << 7) /* Enable interrupt on Rx DMA */
-# define PPR_BUFCFG_TXRDY (1 << 8) /* Enable interrupt when ready for Tx */
-# define PPR_BUFCFG_TXUE (1 << 9) /* Enable interrupt in Tx underrun */
-# define PPR_BUFCFG_RXMISS (1 << 10) /* Enable interrupt on missed Rx packets */
-# define PPR_BUFCFG_RX128 (1 << 11) /* Enable Rx interrupt after 128 bytes */
-# define PPR_BUFCFG_TXCOL (1 << 12) /* Enable int on Tx collision ctr overflow */
-# define PPR_BUFCFG_MISS (1 << 13) /* Enable int on Rx miss ctr overflow */
-# define PPR_BUFCFG_RXDEST (1 << 15) /* Enable int on Rx dest addr match */
-
-#define PPR_LINECTL 0x0112 /* Line control */
-# define PPR_LINECTL_RX (1 << 6) /* Enable receiver */
-# define PPR_LINECTL_TX (1 << 7) /* Enable transmitter */
-# define PPR_LINECTL_AUIONLY (1 << 8) /* AUI interface only */
-# define PPR_LINECTL_AUTOAUI10BT (1 << 9) /* Autodetect AUI or 10BaseT interface */
-# define PPR_LINECTL_MODBACKOFFE (1 << 11) /* Enable modified backoff algorithm */
-# define PPR_LINECTL_POLARITYDIS (1 << 12) /* Disable Rx polarity autodetect */
-# define PPR_LINECTL_2PARTDEFDIS (1 << 13) /* Disable two-part defferal */
-# define PPR_LINECTL_LORXSQUELCH (1 << 14) /* Reduce receiver squelch threshold */
-
-#define PPR_SELFCTL 0x0114 /* Chip self control */
-# define PPR_SELFCTL_RESET (1 << 6) /* Self-clearing reset */
-# define PPR_SELFCTL_SWSUSPEND (1 << 8) /* Initiate suspend mode */
-# define PPR_SELFCTL_HWSLEEPE (1 << 9) /* Enable SLEEP input */
-# define PPR_SELFCTL_HWSTANDBYE (1 << 10) /* Enable standby mode */
-# define PPR_SELFCTL_HC0E (1 << 12) /* Use HCB0 for LINK LED */
-# define PPR_SELFCTL_HC1E (1 << 13) /* Use HCB1 for BSTATUS LED */
-# define PPR_SELFCTL_HCB0 (1 << 14) /* Control LINK LED if HC0E set */
-# define PPR_SELFCTL_HCB1 (1 << 15) /* Cntrol BSTATUS LED if HC1E set */
-
-#define PPR_BUSCTL 0x0116 /* Bus control */
-# define PPR_BUSCTL_RESETRXDMA (1 << 6) /* Reset RxDMA pointer */
-# define PPR_BUSCTL_DMAEXTEND (1 << 8) /* Extend DMA cycle */
-# define PPR_BUSCTL_USESA (1 << 9) /* Assert MEMCS16 on address decode */
-# define PPR_BUSCTL_MEMORYE (1 << 10) /* Enable memory mode */
-# define PPR_BUSCTL_DMABURST (1 << 11) /* Limit DMA access burst */
-# define PPR_BUSCTL_IOCHRDYE (1 << 12) /* Set IOCHRDY high impedence */
-# define PPR_BUSCTL_RXDMASIZE (1 << 13) /* Set DMA buffer size 64KB */
-# define PPR_BUSCTL_ENABLEIRQ (1 << 15) /* Generate interrupt on interrupt event */
-
-#define PPR_TESTCTL 0x0118 /* Test control */
-# define PPR_TESTCTL_DISABLELT (1 << 7) /* Disable link status */
-# define PPR_TESTCTL_ENDECLOOP (1 << 9) /* Internal loopback */
-# define PPR_TESTCTL_AUILOOP (1 << 10) /* AUI loopback */
-# define PPR_TESTCTL_DISBACKOFF (1 << 11) /* Disable backoff algorithm */
-# define PPR_TESTCTL_FDX (1 << 14) /* Enable full duplex mode */
-
-/* 0x0120 - Status and Event Registers */
-
-#define PPR_ISQ 0x0120 /* Interrupt Status Queue */
-#define PPR_RER 0x0124 /* Receive event */
-# define PPR_RER_IAHASH (1 << 6) /* Frame hash match */
-# define PPR_RER_DRIBBLE (1 << 7) /* Frame had 1-7 extra bits after last byte */
-# define PPR_RER_RXOK (1 << 8) /* Frame received with no errors */
-# define PPR_RER_HASHED (1 << 9) /* Frame address hashed OK */
-# define PPR_RER_IA (1 << 10) /* Frame address matched IA */
-# define PPR_RER_BROADCAST (1 << 11) /* Broadcast frame */
-# define PPR_RER_CRC (1 << 12) /* Frame had CRC error */
-# define PPR_RER_RUNT (1 << 13) /* Runt frame */
-# define PPR_RER_EXTRA (1 << 14) /* Frame was too long */
-
-#define PPR_TER 0x0128 /* Transmit event */
-# define PPR_TER_CRS (1 << 6) /* Carrier lost */
-# define PPR_TER_SQE (1 << 7) /* Signal Quality Error */
-# define PPR_TER_TXOK (1 << 8) /* Packet sent without error */
-# define PPR_TER_LATE (1 << 9) /* Out of window */
-# define PPR_TER_JABBER (1 << 10) /* Stuck transmit? */
-# define PPR_TER_NUMCOLLISIONS_SHIFT 11
-# define PPR_TER_NUMCOLLISIONS_MASK (15 << PPR_TER_NUMCOLLISIONS_SHIFT)
-# define PPR_TER_16COLLISIONS (1 << 15) /* > 16 collisions */
-
-#define PPR_BER 0x012C /* Buffer event */
-# define PPR_BER_SWINT (1 << 6) /* Software interrupt */
-# define PPR_BER_RXDMAFRAME (1 << 7) /* Received framed DMAed */
-# define PPR_BER_RDY4TX (1 << 8) /* Ready for transmission */
-# define PPR_BER_TXUNDERRUN (1 << 9) /* Transmit underrun */
-# define PPR_BER_RXMISS (1 << 10) /* Received frame missed */
-# define PPR_BER_RX128 (1 << 11) /* 128 bytes received */
-# define PPR_BER_RXDEST (1 << 15) /* Received framed passed address filter */
-
-#define PPR_RXMISS 0x0130 /* Receiver miss counter */
-#define PPR_TXCOL 0x0132 /* Transmit collision counter */
-#define PPR_LINESTAT 0x0134 /* Line status */
-# define PPR_LINESTAT_LINKOK (1 << 7) /* Line is connected and working */
-# define PPR_LINESTAT_AUI (1 << 8) /* Connected via AUI */
-# define PPR_LINESTAT_10BT (1 << 9) /* Connected via twisted pair */
-# define PPR_LINESTAT_POLARITY (1 << 12) /* Line polarity OK (10BT only) */
-# define PPR_LINESTAT_CRS (1 << 14) /* Frame being received */
-
-#define PPR_SELFSTAT 0x0136 /* Chip self status */
-# define PPR_SELFSTAT_33VACTIVE (1 << 6) /* supply voltage is 3.3V */
-# define PPR_SELFSTAT_INITD (1 << 7) /* Chip initialization complete */
-# define PPR_SELFSTAT_SIBSY (1 << 8) /* EEPROM is busy */
-# define PPR_SELFSTAT_EEPROM (1 << 9) /* EEPROM present */
-# define PPR_SELFSTAT_EEPROMOK (1 << 10) /* EEPROM checks out */
-# define PPR_SELFSTAT_ELPRESENT (1 << 11) /* External address latch logic available */
-# define PPR_SELFSTAT_EESIZE (1 << 12) /* Size of EEPROM */
-
-#define PPR_BUSSTAT 0x0138 /* Bus status */
-# define PPR_BUSSTAT_TXBID (1 << 7) /* Tx error */
-# define PPR_BUSSTAT_TXRDY (1 << 8) /* Ready for Tx data */
-
-#define PPR_TDR 0x013C /* AUI Time Domain Reflectometer */
-
-/* 0x0144 - Initiate transmit registers */
-
-#define PPR_TXCOMMAND 0x0144 /* Tx Command */
-#define PPR_TXLENGTH 0x0146 /* Tx Length */
-
-/* 0x0150 - Address filter registers */
-
-#define PPR_LAF 0x0150 /* Logical address filter (6 bytes) */
-#define PPR_IA 0x0158 /* Individual address (MAC) */
-
-/* 0x0400 - Frame location registers */
-
-#define PPR_RXSTATUS 0x0400 /* Rx Status */
-#define PPR_RXLENGTH 0x0402 /* Rx Length */
-#define PPR_RXFRAMELOCATION 0x0404 /* Rx Frame Location */
-#define PPR_TXFRAMELOCATION 0x0a00 /* Tx Frame Location */
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __DRIVERS_NET_CS89x0_H */
+/****************************************************************************
+ * drivers/net/cs89x0.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 __DRIVERS_NET_CS89x0_H
+#define __DRIVERS_NET_CS89x0_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_CS89x0_ALIGN16/32 determines if the 16-bit CS89x0 registers are
+ * aligned to 16-bit or 32-bit address boundaries. NOTE: If there multiple
+ * CS89x00 parts in the board architecture, we assume that the address
+ * alignment is the same for all implementations. If that is not the
+ * case, then it will be necessary to move a shift value into
+ * the cs89x0_driver_s structure and calculate the offsets dynamically in
+ * the putreg and getreg functions.
+ */
+
+#if defined(CONFIG_CS89x0_ALIGN16)
+# define CS89x0_RTDATA_OFFSET (0 << 1)
+# define CS89x0_TxCMD_OFFSET (2 << 1)
+# define CS89x0_TxLEN_OFFSET (3 << 1)
+# define CS89x0_ISQ_OFFSET (4 << 1)
+# define CS89x0_PPTR_OFFSET (5 << 1)
+# define CS89x0_PDATA_OFFSET (6 << 1)
+#elif defined(CONFIG_CS89x0_ALIGN32)
+# define CS89x0_RTDATA_OFFSET (0 << 2)
+# define CS89x0_TxCMD_OFFSET (2 << 2)
+# define CS89x0_TxLEN_OFFSET (3 << 2)
+# define CS89x0_ISQ_OFFSET (4 << 2)
+# define CS89x0_PPTR_OFFSET (5 << 2)
+# define CS89x0_PDATA_OFFSET (6 << 2)
+#else
+# error "CS89x00 address alignment is not defined"
+#endif
+
+/* ISQ register bit definitions */
+
+#define ISQ_EVENTMASK 0x003f /* Bits 0-5 indicate the status register */
+#define ISQ_RXEVENT 0x0004
+#define ISQ_TXEVENT 0x0008
+#define ISQ_BUFEVENT 0x000c
+#define ISQ_RXMISSEVENT 0x0010
+#define ISQ_TXCOLEVENT 0x0012
+
+/* ISQ register TxEVENT bit definitions*/
+
+#define ISQ_RXEVENT_IAHASH (1 << 6)
+#define ISQ_RXEVENT_DRIBBLE (1 << 7)
+#define ISQ_RXEVENT_RXOK (1 << 8)
+#define ISQ_RXEVENT_HASHED (1 << 9)
+#define ISQ_RXEVENT_HASHNDX_SHIFT 10
+#define ISQ_RXEVENT_HASHNDX_MASK (0x3f << ISQ_RXEVENT_HASHNDX_SHIFT)
+
+/* ISQ register TxEVENT bit definitions*/
+
+#define ISQ_TXEVENT_LOSSOFCRS (1 << 6)
+#define ISQ_TXEVENT_SQEERROR (1 << 7)
+#define ISQ_TXEVENT_TXOK (1 << 8)
+#define ISQ_TXEVENT_OUTWINDOW (1 << 9)
+#define ISQ_TXEVENT_JABBER (1 << 10)
+#define ISQ_TXEVENT_NCOLLISION_SHIFT 11
+#define ISQ_TXEVENT_NCOLLISION_MASK (15 << ISQ_TXEVENT_NCOLLISION_SHIFT)
+#define ISQ_TXEVENT_16COLL (1 << 15)
+
+/* ISQ register BufEVENT bit definitions */
+
+#define ISQ_BUFEVENT_SWINT (1 << 6)
+#define ISQ_BUFEVENT_RXDMAFRAME (1 << 7)
+#define ISQ_BUFEVENT_RDY4TX (1 << 8)
+#define ISQ_BUFEVENT_TXUNDERRUN (1 << 9)
+#define ISQ_BUFEVENT_RXMISS (1 << 10)
+#define ISQ_BUFEVENT_RX128 (1 << 11)
+#define ISQ_BUFEVENT_RXDEST (1 << 15)
+
+/* Packet page register offsets *********************************************/
+
+/* 0x0000 Bus interface registers */
+
+#define PPR_CHIPID 0x0000 /* Chip identifier - must be 0x630E */
+#define PPR_CHIPREV 0x0002 /* Chip revision, model codes */
+#define PPR_IOBASEADDRESS 0x0020 /* I/O Base Address */
+#define PPR_INTREG 0x0022 /* Interrupt configuration */
+# define PPR_INTREG_IRQ0 0x0000 /* Use INTR0 pin */
+# define PPR_INTREG_IRQ1 0x0001 /* Use INTR1 pin */
+# define PPR_INTREG_IRQ2 0x0002 /* Use INTR2 pin */
+# define PPR_INTREG_IRQ3 0x0003 /* Use INTR3 pin */
+
+#define PPR_DMACHANNELNUMBER 0x0024 /* DMA Channel Number (0,1, or 2) */
+#define PPR_DMASTARTOFFRAME 0x0026 /* DMA Start of Frame */
+#define PPR_DMAFRAMECOUNT 0x0028 /* DMA Frame Count (12-bits) */
+#define PPR_RXDMABYTECOUNT 0x002a /* Rx DMA Byte Count */
+#define PPR_MEMORYBASEADDRESS 0x002c /* Memory Base Address Register (20-bit) */
+#define PPR_BOOTPROMBASEADDRESS 0x0030 /* Boot PROM Base Address */
+#define PPR_BOOTPROMADDRESSMASK 0x0034 /* Boot PROM Address Mask */
+#define PPR_EEPROMCOMMAND 0x0040 /* EEPROM Command */
+#define PPR_EEPROMDATA 0x0042 /* EEPROM Data */
+#define PPR_RECVFRAMEBYTES 0x0050 /* Received Frame Byte Counter */
+
+/* 0x0100 - Configuration and control registers */
+
+#define PPR_RXCFG 0x0102 /* Receiver configuration */
+# define PPR_RXCFG_SKIP1 (1 << 6) /* Skip (discard) current frame */
+# define PPR_RXCFG_STREAM (1 << 7) /* Enable streaming mode */
+# define PPR_RXCFG_RXOK (1 << 8) /* RxOK interrupt enable */
+# define PPR_RxCFG_RxDMAonly (1 << 9) /* Use RxDMA for all frames */
+# define PPR_RxCFG_AutoRxDMA (1 << 10) /* Select RxDMA automatically */
+# define PPR_RxCFG_BufferCRC (1 << 11) /* Include CRC characters in frame */
+# define PPR_RxCFG_CRC (1 << 12) /* Enable interrupt on CRC error */
+# define PPR_RxCFG_RUNT (1 << 13) /* Enable interrupt on RUNT frames */
+# define PPR_RxCFG_EXTRA (1 << 14) /* Enable interrupt on frames with extra data */
+
+#define PPR_RXCTL 0x0104 /* Receiver control */
+# define PPR_RXCTL_IAHASH (1 << 6) /* Accept frames that match hash */
+# define PPR_RXCTL_PROMISCUOUS (1 << 7) /* Accept any frame */
+# define PPR_RXCTL_RXOK (1 << 8) /* Accept well formed frames */
+# define PPR_RXCTL_MULTICAST (1 << 9) /* Accept multicast frames */
+# define PPR_RXCTL_IA (1 << 10) /* Accept frame that matches IA */
+# define PPR_RXCTL_BROADCAST (1 << 11) /* Accept broadcast frames */
+# define PPR_RXCTL_CRC (1 << 12) /* Accept frames with bad CRC */
+# define PPR_RXCTL_RUNT (1 << 13) /* Accept runt frames */
+# define PPR_RXCTL_EXTRA (1 << 14) /* Accept frames that are too long */
+
+#define PPR_TXCFG 0x0106 /* Transmit configuration */
+# define PPR_TXCFG_CRS (1 << 6) /* Enable interrupt on loss of carrier */
+# define PPR_TXCFG_SQE (1 << 7) /* Enable interrupt on Signal Quality Error */
+# define PPR_TXCFG_TXOK (1 << 8) /* Enable interrupt on successful xmits */
+# define PPR_TXCFG_LATE (1 << 9) /* Enable interrupt on "out of window" */
+# define PPR_TXCFG_JABBER (1 << 10) /* Enable interrupt on jabber detect */
+# define PPR_TXCFG_COLLISION (1 << 11) /* Enable interrupt if collision */
+# define PPR_TXCFG_16COLLISIONS (1 << 15) /* Enable interrupt if > 16 collisions */
+
+#define PPR_TXCMD 0x0108 /* Transmit command status */
+# define PPR_TXCMD_TXSTART5 (0 << 6) /* Start after 5 bytes in buffer */
+# define PPR_TXCMD_TXSTART381 (1 << 6) /* Start after 381 bytes in buffer */
+# define PPR_TXCMD_TXSTART1021 (2 << 6) /* Start after 1021 bytes in buffer */
+# define PPR_TXCMD_TXSTARTFULL (3 << 6) /* Start after all bytes loaded */
+# define PPR_TXCMD_FORCE (1 << 8) /* Discard any pending packets */
+# define PPR_TXCMD_ONECOLLISION (1 << 9) /* Abort after a single collision */
+# define PPR_TXCMD_NOCRC (1 << 12) /* Do not add CRC */
+# define PPR_TXCMD_NOPAD (1 << 13) /* Do not pad short packets */
+
+#define PPR_BUFCFG 0x010a /* Buffer configuration */
+# define PPR_BUFCFG_SWI (1 << 6) /* Force interrupt via software */
+# define PPR_BUFCFG_RXDMA (1 << 7) /* Enable interrupt on Rx DMA */
+# define PPR_BUFCFG_TXRDY (1 << 8) /* Enable interrupt when ready for Tx */
+# define PPR_BUFCFG_TXUE (1 << 9) /* Enable interrupt in Tx underrun */
+# define PPR_BUFCFG_RXMISS (1 << 10) /* Enable interrupt on missed Rx packets */
+# define PPR_BUFCFG_RX128 (1 << 11) /* Enable Rx interrupt after 128 bytes */
+# define PPR_BUFCFG_TXCOL (1 << 12) /* Enable int on Tx collision ctr overflow */
+# define PPR_BUFCFG_MISS (1 << 13) /* Enable int on Rx miss ctr overflow */
+# define PPR_BUFCFG_RXDEST (1 << 15) /* Enable int on Rx dest addr match */
+
+#define PPR_LINECTL 0x0112 /* Line control */
+# define PPR_LINECTL_RX (1 << 6) /* Enable receiver */
+# define PPR_LINECTL_TX (1 << 7) /* Enable transmitter */
+# define PPR_LINECTL_AUIONLY (1 << 8) /* AUI interface only */
+# define PPR_LINECTL_AUTOAUI10BT (1 << 9) /* Autodetect AUI or 10BaseT interface */
+# define PPR_LINECTL_MODBACKOFFE (1 << 11) /* Enable modified backoff algorithm */
+# define PPR_LINECTL_POLARITYDIS (1 << 12) /* Disable Rx polarity autodetect */
+# define PPR_LINECTL_2PARTDEFDIS (1 << 13) /* Disable two-part defferal */
+# define PPR_LINECTL_LORXSQUELCH (1 << 14) /* Reduce receiver squelch threshold */
+
+#define PPR_SELFCTL 0x0114 /* Chip self control */
+# define PPR_SELFCTL_RESET (1 << 6) /* Self-clearing reset */
+# define PPR_SELFCTL_SWSUSPEND (1 << 8) /* Initiate suspend mode */
+# define PPR_SELFCTL_HWSLEEPE (1 << 9) /* Enable SLEEP input */
+# define PPR_SELFCTL_HWSTANDBYE (1 << 10) /* Enable standby mode */
+# define PPR_SELFCTL_HC0E (1 << 12) /* Use HCB0 for LINK LED */
+# define PPR_SELFCTL_HC1E (1 << 13) /* Use HCB1 for BSTATUS LED */
+# define PPR_SELFCTL_HCB0 (1 << 14) /* Control LINK LED if HC0E set */
+# define PPR_SELFCTL_HCB1 (1 << 15) /* Cntrol BSTATUS LED if HC1E set */
+
+#define PPR_BUSCTL 0x0116 /* Bus control */
+# define PPR_BUSCTL_RESETRXDMA (1 << 6) /* Reset RxDMA pointer */
+# define PPR_BUSCTL_DMAEXTEND (1 << 8) /* Extend DMA cycle */
+# define PPR_BUSCTL_USESA (1 << 9) /* Assert MEMCS16 on address decode */
+# define PPR_BUSCTL_MEMORYE (1 << 10) /* Enable memory mode */
+# define PPR_BUSCTL_DMABURST (1 << 11) /* Limit DMA access burst */
+# define PPR_BUSCTL_IOCHRDYE (1 << 12) /* Set IOCHRDY high impedence */
+# define PPR_BUSCTL_RXDMASIZE (1 << 13) /* Set DMA buffer size 64KB */
+# define PPR_BUSCTL_ENABLEIRQ (1 << 15) /* Generate interrupt on interrupt event */
+
+#define PPR_TESTCTL 0x0118 /* Test control */
+# define PPR_TESTCTL_DISABLELT (1 << 7) /* Disable link status */
+# define PPR_TESTCTL_ENDECLOOP (1 << 9) /* Internal loopback */
+# define PPR_TESTCTL_AUILOOP (1 << 10) /* AUI loopback */
+# define PPR_TESTCTL_DISBACKOFF (1 << 11) /* Disable backoff algorithm */
+# define PPR_TESTCTL_FDX (1 << 14) /* Enable full duplex mode */
+
+/* 0x0120 - Status and Event Registers */
+
+#define PPR_ISQ 0x0120 /* Interrupt Status Queue */
+#define PPR_RER 0x0124 /* Receive event */
+# define PPR_RER_IAHASH (1 << 6) /* Frame hash match */
+# define PPR_RER_DRIBBLE (1 << 7) /* Frame had 1-7 extra bits after last byte */
+# define PPR_RER_RXOK (1 << 8) /* Frame received with no errors */
+# define PPR_RER_HASHED (1 << 9) /* Frame address hashed OK */
+# define PPR_RER_IA (1 << 10) /* Frame address matched IA */
+# define PPR_RER_BROADCAST (1 << 11) /* Broadcast frame */
+# define PPR_RER_CRC (1 << 12) /* Frame had CRC error */
+# define PPR_RER_RUNT (1 << 13) /* Runt frame */
+# define PPR_RER_EXTRA (1 << 14) /* Frame was too long */
+
+#define PPR_TER 0x0128 /* Transmit event */
+# define PPR_TER_CRS (1 << 6) /* Carrier lost */
+# define PPR_TER_SQE (1 << 7) /* Signal Quality Error */
+# define PPR_TER_TXOK (1 << 8) /* Packet sent without error */
+# define PPR_TER_LATE (1 << 9) /* Out of window */
+# define PPR_TER_JABBER (1 << 10) /* Stuck transmit? */
+# define PPR_TER_NUMCOLLISIONS_SHIFT 11
+# define PPR_TER_NUMCOLLISIONS_MASK (15 << PPR_TER_NUMCOLLISIONS_SHIFT)
+# define PPR_TER_16COLLISIONS (1 << 15) /* > 16 collisions */
+
+#define PPR_BER 0x012C /* Buffer event */
+# define PPR_BER_SWINT (1 << 6) /* Software interrupt */
+# define PPR_BER_RXDMAFRAME (1 << 7) /* Received framed DMAed */
+# define PPR_BER_RDY4TX (1 << 8) /* Ready for transmission */
+# define PPR_BER_TXUNDERRUN (1 << 9) /* Transmit underrun */
+# define PPR_BER_RXMISS (1 << 10) /* Received frame missed */
+# define PPR_BER_RX128 (1 << 11) /* 128 bytes received */
+# define PPR_BER_RXDEST (1 << 15) /* Received framed passed address filter */
+
+#define PPR_RXMISS 0x0130 /* Receiver miss counter */
+#define PPR_TXCOL 0x0132 /* Transmit collision counter */
+#define PPR_LINESTAT 0x0134 /* Line status */
+# define PPR_LINESTAT_LINKOK (1 << 7) /* Line is connected and working */
+# define PPR_LINESTAT_AUI (1 << 8) /* Connected via AUI */
+# define PPR_LINESTAT_10BT (1 << 9) /* Connected via twisted pair */
+# define PPR_LINESTAT_POLARITY (1 << 12) /* Line polarity OK (10BT only) */
+# define PPR_LINESTAT_CRS (1 << 14) /* Frame being received */
+
+#define PPR_SELFSTAT 0x0136 /* Chip self status */
+# define PPR_SELFSTAT_33VACTIVE (1 << 6) /* supply voltage is 3.3V */
+# define PPR_SELFSTAT_INITD (1 << 7) /* Chip initialization complete */
+# define PPR_SELFSTAT_SIBSY (1 << 8) /* EEPROM is busy */
+# define PPR_SELFSTAT_EEPROM (1 << 9) /* EEPROM present */
+# define PPR_SELFSTAT_EEPROMOK (1 << 10) /* EEPROM checks out */
+# define PPR_SELFSTAT_ELPRESENT (1 << 11) /* External address latch logic available */
+# define PPR_SELFSTAT_EESIZE (1 << 12) /* Size of EEPROM */
+
+#define PPR_BUSSTAT 0x0138 /* Bus status */
+# define PPR_BUSSTAT_TXBID (1 << 7) /* Tx error */
+# define PPR_BUSSTAT_TXRDY (1 << 8) /* Ready for Tx data */
+
+#define PPR_TDR 0x013C /* AUI Time Domain Reflectometer */
+
+/* 0x0144 - Initiate transmit registers */
+
+#define PPR_TXCOMMAND 0x0144 /* Tx Command */
+#define PPR_TXLENGTH 0x0146 /* Tx Length */
+
+/* 0x0150 - Address filter registers */
+
+#define PPR_LAF 0x0150 /* Logical address filter (6 bytes) */
+#define PPR_IA 0x0158 /* Individual address (MAC) */
+
+/* 0x0400 - Frame location registers */
+
+#define PPR_RXSTATUS 0x0400 /* Rx Status */
+#define PPR_RXLENGTH 0x0402 /* Rx Length */
+#define PPR_RXFRAMELOCATION 0x0404 /* Rx Frame Location */
+#define PPR_TXFRAMELOCATION 0x0a00 /* Tx Frame Location */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __DRIVERS_NET_CS89x0_H */
diff --git a/nuttx/drivers/net/dm90x0.c b/nuttx/drivers/net/dm90x0.c
index 15433e0f8..2f5b26abb 100644
--- a/nuttx/drivers/net/dm90x0.c
+++ b/nuttx/drivers/net/dm90x0.c
@@ -2,7 +2,7 @@
* drivers/net/dm9x.c
*
* Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Davicom data sheets (DM9000-DS-F03-041906.pdf,
* DM9010-DS-F01-103006.pdf) and looking at lots of other DM90x0
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index 76b0f205b..47a84ec9f 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -42,7 +42,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ENC28J60)
+#if defined(CONFIG_NET) && defined(CONFIG_ENC28J60)
#include <stdint.h>
#include <stdbool.h>
@@ -74,7 +74,7 @@
/* ENC28J60 Configuration Settings:
*
- * CONFIG_NET_ENC28J60 - Enabled ENC28J60 support
+ * CONFIG_ENC28J60 - Enabled ENC28J60 support
* CONFIG_ENC28J60_SPIMODE - Controls the SPI mode
* CONFIG_ENC28J60_FREQUENCY - Define to use a different bus frequency
* CONFIG_ENC28J60_NINTERFACES - Specifies the number of physical ENC28J60
@@ -83,12 +83,15 @@
* CONFIG_ENC28J60_HALFDUPPLEX - Default is full duplex
*/
-/* The ENC28J60 spec says that is supports SPI mode 0,0 only. However,
- * somtimes you need to tinker with these things.
+/* The ENC28J60 spec says that it supports SPI mode 0,0 only: "The
+ * implementation used on this device supports SPI mode 0,0 only. In
+ * addition, the SPI port requires that SCK be at Idle in a low state;
+ * selectable clock polarity is not supported." However, sometimes you
+ * need to tinker with these things.
*/
#ifndef CONFIG_ENC28J60_SPIMODE
-# define CONFIG_ENC28J60_SPIMODE SPIDEV_MODE2
+# define CONFIG_ENC28J60_SPIMODE SPIDEV_MODE0
#endif
/* CONFIG_ENC28J60_NINTERFACES determines the number of physical interfaces
@@ -164,6 +167,15 @@
* Private Types
****************************************************************************/
+/* The state of the interface */
+
+enum enc_state_e
+{
+ ENCSTATE_UNIT = 0, /* The interface is in an unknown state */
+ ENCSTATE_DOWN, /* The interface is down */
+ ENCSTATE_UP /* The interface is up */
+};
+
/* The enc_driver_s encapsulates all state information for a single hardware
* interface
*/
@@ -172,22 +184,25 @@ struct enc_driver_s
{
/* Device control */
- bool bifup; /* true:ifup false:ifdown */
- uint8_t bank; /* Currently selected bank */
- uint16_t nextpkt; /* Next packet address */
- int irq; /* GPIO IRQ configured for the ENC28J60 */
+ uint8_t ifstate; /* Interface state: See ENCSTATE_* */
+ uint8_t bank; /* Currently selected bank */
+#ifndef CONFIG_SPI_OWNBUS
+ uint8_t lockcount; /* Avoid recursive locks */
+#endif
+ uint16_t nextpkt; /* Next packet address */
+ FAR const struct enc_lower_s *lower; /* Low-level MCU-specific support */
/* Timing */
- WDOG_ID txpoll; /* TX poll timer */
- WDOG_ID txtimeout; /* TX timeout timer */
+ WDOG_ID txpoll; /* TX poll timer */
+ WDOG_ID txtimeout; /* TX timeout timer */
- /* We we don't own the SPI bus, then we cannot do SPI accesses from the
+ /* If we don't own the SPI bus, then we cannot do SPI accesses from the
* interrupt handler.
*/
#ifndef CONFIG_SPI_OWNBUS
- struct work_s work; /* Work queue support */
+ struct work_s work; /* Work queue support */
#endif
/* This is the contained SPI driver intstance */
@@ -196,12 +211,12 @@ struct enc_driver_s
/* This holds the information visible to uIP/NuttX */
- struct uip_driver_s dev; /* Interface understood by uIP */
+ struct uip_driver_s dev; /* Interface understood by uIP */
/* Statistics */
#ifdef CONFIG_ENC28J60_STATS
- struct enc_stats_s stats;
+ struct enc_stats_s stats;
#endif
};
@@ -219,11 +234,11 @@ static struct enc_driver_s g_enc28j60[CONFIG_ENC28J60_NINTERFACES];
static inline void enc_configspi(FAR struct spi_dev_s *spi);
#ifdef CONFIG_SPI_OWNBUS
-static inline void enc_select(FAR struct spi_dev_s *spi);
-static inline void enc_deselect(FAR struct spi_dev_s *spi);
+static inline void enc_select(FAR struct enc_driver_s *priv);
+static inline void enc_deselect(FAR struct enc_driver_s *priv);
#else
-static void enc_select(FAR struct spi_dev_s *spi);
-static void enc_deselect(FAR struct spi_dev_s *spi);
+static void enc_select(FAR struct enc_driver_s *priv);
+static void enc_deselect(FAR struct enc_driver_s *priv);
#endif
/* SPI control register access */
@@ -231,11 +246,12 @@ static void enc_deselect(FAR struct spi_dev_s *spi);
static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd);
static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd,
uint8_t wrdata);
+static inline void enc_src(FAR struct enc_driver_s *priv);
static void enc_setbank(FAR struct enc_driver_s *priv, uint8_t bank);
static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg);
static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
uint8_t wrdata);
-static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
+static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
uint8_t bits, uint8_t value);
/* SPI buffer transfers */
@@ -342,31 +358,50 @@ static inline void enc_configspi(FAR struct spi_dev_s *spi)
****************************************************************************/
#ifdef CONFIG_SPI_OWNBUS
-static inline void enc_select(FAR struct spi_dev_s *spi)
+static inline void enc_select(FAR struct enc_driver_s *priv)
{
/* We own the SPI bus, so just select the chip */
- SPI_SELECT(spi, SPIDEV_ETHERNET, true);
+ SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);
}
#else
-static void enc_select(FAR struct spi_dev_s *spi)
+static void enc_select(FAR struct enc_driver_s *priv)
{
- /* Select ENC28J60 chip (locking the SPI bus in case there are multiple
- * devices competing for the SPI bus
+ /* Lock the SPI bus in case there are multiple devices competing for the SPI
+ * bus. First check if we already hold the lock.
*/
- SPI_LOCK(spi, true);
- SPI_SELECT(spi, SPIDEV_ETHERNET, true);
+ if (priv->lockcount > 0)
+ {
+ /* Yes... just increment the lock count. In this case, we know
+ * that the bus has already been configured for the ENC28J60.
+ */
- /* Now make sure that the SPI bus is configured for the ENC28J60 (it
- * might have gotten configured for a different device while unlocked)
- */
+ DEBUGASSERT(priv->lockcount < 255);
+ priv->lockcount++;
+ }
+ else
+ {
+ /* No... take the lock and set the lock count to 1 */
- SPI_SETMODE(spi, CONFIG_ENC28J60_SPIMODE);
- SPI_SETBITS(spi, 8);
+ DEBUGASSERT(priv->lockcount == 0);
+ SPI_LOCK(priv->spi, true);
+ priv->lockcount = 1;
+
+ /* Now make sure that the SPI bus is configured for the ENC28J60 (it
+ * might have gotten configured for a different device while unlocked)
+ */
+
+ SPI_SETMODE(priv->spi, CONFIG_ENC28J60_SPIMODE);
+ SPI_SETBITS(priv->spi, 8);
#ifdef CONFIG_ENC28J60_FREQUENCY
- SPI_SETFREQUENCY(spi, CONFIG_ENC28J60_FREQUENCY);
+ SPI_SETFREQUENCY(priv->spi, CONFIG_ENC28J60_FREQUENCY);
#endif
+ }
+
+ /* Select ENC28J60 chip. */
+
+ SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);
}
#endif
@@ -387,19 +422,33 @@ static void enc_select(FAR struct spi_dev_s *spi)
****************************************************************************/
#ifdef CONFIG_SPI_OWNBUS
-static inline void enc_deselect(FAR struct spi_dev_s *spi)
+static inline void enc_deselect(FAR struct enc_driver_s *priv)
{
/* We own the SPI bus, so just de-select the chip */
- SPI_SELECT(spi, SPIDEV_ETHERNET, false);
+ SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
}
#else
-static void enc_deselect(FAR struct spi_dev_s *spi)
+static void enc_deselect(FAR struct enc_driver_s *priv)
{
- /* De-select ENC28J60 chip and relinquish the SPI bus. */
+ /* De-select ENC28J60 chip. */
+
+ SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
- SPI_SELECT(spi, SPIDEV_ETHERNET, false);
- SPI_LOCK(spi, false);
+ /* And relinquishthe lock on the bus. If the lock count is > 1 then we
+ * are in a nested lock and we only need to decrement the lock cound.
+ */
+
+ if (priv->lockcount <= 1)
+ {
+ DEBUGASSERT(priv->lockcount == 1);
+ SPI_LOCK(priv->spi, false);
+ priv->lockcount = 0;
+ }
+ else
+ {
+ priv->lockcount--;
+ }
}
#endif
@@ -423,26 +472,24 @@ static void enc_deselect(FAR struct spi_dev_s *spi)
static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd)
{
- FAR struct spi_dev_s *spi;
uint8_t rddata;
DEBUGASSERT(priv && priv->spi);
- spi = priv->spi;
/* Select ENC28J60 chip */
- enc_select(spi);
+ enc_select(priv);
/* Send the read command and collect the data. The sequence requires
* 16-clocks: 8 to clock out the cmd + 8 to clock in the data.
*/
- (void)SPI_SEND(spi, cmd); /* Clock out the command */
- rddata = SPI_SEND(spi, 0); /* Clock in the data */
+ (void)SPI_SEND(priv->spi, cmd); /* Clock out the command */
+ rddata = SPI_SEND(priv->spi, 0); /* Clock in the data */
/* De-select ENC28J60 chip */
- enc_deselect(spi);
+ enc_deselect(priv);
return rddata;
}
@@ -468,25 +515,75 @@ static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd)
static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd,
uint8_t wrdata)
{
- FAR struct spi_dev_s *spi;
-
DEBUGASSERT(priv && priv->spi);
- spi = priv->spi;
/* Select ENC28J60 chip */
- enc_select(spi);
+ enc_select(priv);
/* Send the write command and data. The sequence requires 16-clocks:
* 8 to clock out the cmd + 8 to clock out the data.
*/
- (void)SPI_SEND(spi, cmd); /* Clock out the command */
- (void)SPI_SEND(spi, wrdata); /* Clock out the data */
+ (void)SPI_SEND(priv->spi, cmd); /* Clock out the command */
+ (void)SPI_SEND(priv->spi, wrdata); /* Clock out the data */
/* De-select ENC28J60 chip. */
- enc_deselect(spi);
+ enc_deselect(priv);
+}
+
+/****************************************************************************
+ * Function: enc_src
+ *
+ * Description:
+ * Send the single byte system reset command (SRC).
+ *
+ * "The System Reset Command (SRC) allows the host controller to issue a
+ * System Soft Reset command. Unlike other SPI commands, the SRC is
+ * only a single byte command and does not operate on any register. The
+ * command is started by pulling the CS pin low. The SRC opcode is the
+ * sent, followed by a 5-bit Soft Reset command constant of 1Fh. The
+ * SRC operation is terminated by raising the CS pin."
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static inline void enc_src(FAR struct enc_driver_s *priv)
+{
+ DEBUGASSERT(priv && priv->spi);
+
+ /* Select ENC28J60 chip */
+
+ enc_select(priv);
+
+ /* Send the system reset command. */
+
+ (void)SPI_SEND(priv->spi, ENC_SRC);
+
+ /* Check CLKRDY bit to see when the reset is complete. There is an errata
+ * that says the CLKRDY may be invalid. We'll wait a couple of msec to
+ * workaround this condition.
+ *
+ * Also, "After a System Reset, all PHY registers should not be read or
+ * written to until at least 50 µs have passed since the Reset has ended.
+ * All registers will revert to their Reset default values. The dual
+ * port buffer memory will maintain state throughout the System Reset."
+ */
+
+ up_mdelay(2);
+ /* while ((enc_rdgreg(priv, ENC_ESTAT) & ESTAT_CLKRDY) != 0); */
+
+ /* De-select ENC28J60 chip. */
+
+ enc_deselect(priv);
}
/****************************************************************************
@@ -551,39 +648,38 @@ static void enc_setbank(FAR struct enc_driver_s *priv, uint8_t bank)
static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
{
- FAR struct spi_dev_s *spi;
uint8_t rddata;
DEBUGASSERT(priv && priv->spi);
- spi = priv->spi;
-
- /* Select ENC28J60 chip */
-
- enc_select(spi);
/* Set the bank */
enc_setbank(priv, GETBANK(ctrlreg));
+ /* Select ENC28J60 chip */
+
+ enc_select(priv);
+
/* Send the RCR command and collect the data. How we collect the data
* depends on if this is a PHY/CAN or not. The normal sequence requires
* 16-clocks: 8 to clock out the cmd and 8 to clock in the data.
*/
- (void)SPI_SEND(spi, ENC_RCR | GETADDR(ctrlreg)); /* Clock out the command */
+ (void)SPI_SEND(priv->spi, ENC_RCR | GETADDR(ctrlreg)); /* Clock out the command */
if (ISPHYMAC(ctrlreg))
{
/* The PHY/MAC sequence requires 24-clocks: 8 to clock out the cmd,
* 8 dummy bits, and 8 to clock in the PHY/MAC data.
*/
- (void)SPI_SEND(spi,0); /* Clock in the dummy byte */
+ (void)SPI_SEND(priv->spi, 0); /* Clock in the dummy byte */
}
- rddata = SPI_SEND(spi, 0); /* Clock in the data */
+
+ rddata = SPI_SEND(priv->spi, 0); /* Clock in the data */
/* De-select ENC28J60 chip */
- enc_deselect(spi);
+ enc_deselect(priv);
return rddata;
}
@@ -610,14 +706,11 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
uint8_t wrdata)
{
- FAR struct spi_dev_s *spi;
-
DEBUGASSERT(priv && priv->spi);
- spi = priv->spi;
/* Select ENC28J60 chip */
- enc_select(spi);
+ enc_select(priv);
/* Set the bank */
@@ -627,12 +720,12 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
* 8 to clock out the cmd + 8 to clock out the data.
*/
- (void)SPI_SEND(spi, ENC_WCR | GETADDR(ctrlreg)); /* Clock out the command */
- (void)SPI_SEND(spi, wrdata); /* Clock out the data */
+ (void)SPI_SEND(priv->spi, ENC_WCR | GETADDR(ctrlreg)); /* Clock out the command */
+ (void)SPI_SEND(priv->spi, wrdata); /* Clock out the data */
/* De-select ENC28J60 chip. */
- enc_deselect(spi);
+ enc_deselect(priv);
}
/****************************************************************************
@@ -672,6 +765,7 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
elapsed = clock_systimer() - start;
}
while ((rddata & bits) != value || elapsed > ENC_POLLTIMEOUT);
+
return (rddata & bits) == value ? -ETIMEDOUT : OK;
}
@@ -697,26 +791,23 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
size_t buflen)
{
- FAR struct spi_dev_s *spi;
-
DEBUGASSERT(priv && priv->spi);
- spi = priv->spi;
/* Select ENC28J60 chip */
- enc_select(spi);
+ enc_select(priv);
/* Send the read buffer memory command (ignoring the response) */
- (void)SPI_SEND(spi, ENC_RBM);
+ (void)SPI_SEND(priv->spi, ENC_RBM);
/* Then read the buffer data */
- SPI_RECVBLOCK(spi, buffer, buflen);
+ SPI_RECVBLOCK(priv->spi, buffer, buflen);
/* De-select ENC28J60 chip. */
- enc_deselect(spi);
+ enc_deselect(priv);
}
/****************************************************************************
@@ -741,26 +832,23 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
static void enc_wrbuffer(FAR struct enc_driver_s *priv,
FAR const uint8_t *buffer, size_t buflen)
{
- FAR struct spi_dev_s *spi;
-
DEBUGASSERT(priv && priv->spi);
- spi = priv->spi;
/* Select ENC28J60 chip */
- enc_select(spi);
+ enc_select(priv);
/* Send the write buffer memory command (ignoring the response) */
- (void)SPI_SEND(spi, ENC_WBM);
+ (void)SPI_SEND(priv->spi, ENC_WBM);
/* Then send the buffer */
- SPI_SNDBLOCK(spi, buffer, buflen);
+ SPI_SNDBLOCK(priv->spi, buffer, buflen);
/* De-select ENC28J60 chip. */
- enc_deselect(spi);
+ enc_deselect(priv);
}
/****************************************************************************
@@ -802,6 +890,7 @@ static uint16_t enc_rdphy(FAR struct enc_driver_s *priv, uint8_t phyaddr)
data = (uint16_t)enc_rdbreg(priv, ENC_MIRDL);
data |= (uint16_t)enc_rdbreg(priv, ENC_MIRDH) << 8;
}
+
return data;
}
@@ -1294,7 +1383,14 @@ static void enc_worker(FAR void *arg)
DEBUGASSERT(priv);
- /* Disable further interrupts by clearing the global interrup enable bit */
+ /* Disable further interrupts by clearing the global interrupt enable bit.
+ * "After an interrupt occurs, the host controller should clear the global
+ * enable bit for the interrupt pin before servicing the interrupt. Clearing
+ * the enable bit will cause the interrupt pin to return to the non-asserted
+ * state (high). Doing so will prevent the host controller from missing a
+ * falling edge should another interrupt occur while the immediate interrupt
+ * is being serviced."
+ */
enc_bfcgreg(priv, ENC_EIE, EIE_INTIE);
@@ -1462,12 +1558,17 @@ static void enc_worker(FAR void *arg)
enc_rxerif(priv); /* Handle the RX error */
enc_bfcgreg(priv, ENC_EIR, EIR_RXERIF); /* Clear the RXERIF interrupt */
}
-
}
/* Enable Ethernet interrupts */
enc_bfsgreg(priv, ENC_EIE, EIE_INTIE);
+
+ /* Enable GPIO interrupts if they were disbled in enc_interrupt */
+
+#ifndef CONFIG_SPI_OWNBUS
+ priv->lower->enable(priv->lower);
+#endif
}
/****************************************************************************
@@ -1491,8 +1592,6 @@ static int enc_interrupt(int irq, FAR void *context)
{
register FAR struct enc_driver_s *priv = &g_enc28j60[0];
- DEBUGASSERT(priv->irq == irq);
-
#ifdef CONFIG_SPI_OWNBUS
/* In very simple environments, we own the SPI and can do data transfers
* from the interrupt handler. That is actually a very bad idea in any
@@ -1509,7 +1608,15 @@ static int enc_interrupt(int irq, FAR void *context)
* a good thing to do in any event.
*/
- return work_queue(&priv->work, enc_worker, (FAR void *)priv, 0);
+ DEBUGASSERT(work_available(&priv->work));
+
+ /* Notice that further GPIO interrupts are disabled until the work is
+ * actually performed. This is to prevent overrun of the worker thread.
+ * Interrupts are re-enabled in enc_worker() when the work is completed.
+ */
+
+ priv->lower->disable(priv->lower);
+ return work_queue(HPWORK, &priv->work, enc_worker, (FAR void *)priv, 0);
#endif
}
@@ -1658,9 +1765,10 @@ static int enc_ifup(struct uip_driver_s *dev)
* controller
*/
- priv->bifup = true;
- up_enable_irq(priv->irq);
+ priv->ifstate = ENCSTATE_UP;
+ priv->lower->enable(priv->lower);
}
+
return ret;
}
@@ -1687,13 +1795,13 @@ static int enc_ifdown(struct uip_driver_s *dev)
int ret;
nlldbg("Taking down: %d.%d.%d.%d\n",
- dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
- (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
+ dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
+ (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
/* Disable the Ethernet interrupt */
flags = irqsave();
- up_disable_irq(priv->irq);
+ priv->lower->disable(priv->lower);
/* Cancel the TX poll timer and TX timeout timers */
@@ -1705,7 +1813,7 @@ static int enc_ifdown(struct uip_driver_s *dev)
ret = enc_reset(priv);
enc_pwrsave(priv);
- priv->bifup = false;
+ priv->ifstate = ENCSTATE_DOWN;
irqrestore(flags);
return ret;
}
@@ -1738,7 +1846,7 @@ static int enc_txavail(struct uip_driver_s *dev)
/* Ignore the notification if the interface is not yet up */
- if (priv->bifup)
+ if (priv->ifstate == ENCSTATE_UP)
{
/* Check if the hardware is ready to send another packet. The driver
* starts a transmission process by setting ECON1.TXRTS. When the packet is
@@ -1991,15 +2099,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
/* Reset the ENC28J60 */
- enc_wrgreg(priv, ENC_SRC, ENC_SRC);
-
- /* Check CLKRDY bit to see when the reset is complete. There is an errata
- * that says the CLKRDY may be invalid. We'll wait a couple of msec to
- * workaround this condition.
- */
-
- up_mdelay(2);
- /* while ((enc_rdgreg(priv, ENC_ESTAT) & ESTAT_CLKRDY) != 0); */
+ enc_src(priv);
/* Initialize ECON1: Clear ECON1 */
@@ -2045,6 +2145,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
nlldbg("Bad Rev ID: %02x\n", regval);
return -ENODEV;
}
+
nllvdbg("Rev ID: %02x\n", regval);
/* Set filter mode: unicast OR broadcast AND crc valid */
@@ -2117,10 +2218,10 @@ static int enc_reset(FAR struct enc_driver_s *priv)
*
* Parameters:
* spi - A reference to the platform's SPI driver for the ENC28J60
+ * lower - The MCU-specific interrupt used to control low-level MCU
+ * functions (i.e., ENC28J60 GPIO interrupts).
* devno - If more than one ENC28J60 is supported, then this is the
* zero based number that identifies the ENC28J60;
- * irq - The fully configured GPIO IRQ that ENC28J60 interrupts will be
- * asserted on. This driver will attach and entable this IRQ.
*
* Returned Value:
* OK on success; Negated errno on failure.
@@ -2129,10 +2230,10 @@ static int enc_reset(FAR struct enc_driver_s *priv)
*
****************************************************************************/
-int enc_initialize(FAR struct spi_dev_s *spi, unsigned int devno, unsigned int irq)
+int enc_initialize(FAR struct spi_dev_s *spi,
+ FAR const struct enc_lower_s *lower, unsigned int devno)
{
- FAR struct enc_driver_s *priv ;
- int ret;
+ FAR struct enc_driver_s *priv;
DEBUGASSERT(devno < CONFIG_ENC28J60_NINTERFACES);
priv = &g_enc28j60[devno];
@@ -2154,30 +2255,30 @@ int enc_initialize(FAR struct spi_dev_s *spi, unsigned int devno, unsigned int i
priv->txpoll = wd_create(); /* Create periodic poll timer */
priv->txtimeout = wd_create(); /* Create TX timeout timer */
priv->spi = spi; /* Save the SPI instance */
- priv->irq = irq; /* Save the IRQ number */
-
- /* Make sure that the interface is in the down state. NOTE: The MAC
- * address will not be set up until ifup. That gives the app time to set
- * the MAC address before bringing the interface up.
+ priv->lower = lower; /* Save the low-level MCU interface */
+
+ /* The interface should be in the down state. However, this function is called
+ * too early in initalization to perform the ENC28J60 reset in enc_ifdown. We
+ * are depending upon the fact that the application level logic will call enc_ifdown
+ * later to reset the ENC28J60. NOTE: The MAC address will not be set up until
+ * enc_ifup() is called. That gives the app time to set the MAC address before
+ * bringing the interface up.
*/
- ret = enc_ifdown(&priv->dev);
- if (ret == OK)
- {
- /* Attach the IRQ to the driver (but don't enable it yet) */
-
- if (irq_attach(irq, enc_interrupt))
- {
- /* We could not attach the ISR to the interrupt */
+ priv->ifstate = ENCSTATE_UNIT;
- ret = -EAGAIN;
- }
+ /* Attach the interrupt to the driver (but don't enable it yet) */
- /* Register the device with the OS so that socket IOCTLs can be performed */
+ if (lower->attach(lower, enc_interrupt))
+ {
+ /* We could not attach the ISR to the interrupt */
- (void)netdev_register(&priv->dev);
+ return -EAGAIN;
}
- return ret;
+
+ /* Register the device with the OS so that socket IOCTLs can be performed */
+
+ return netdev_register(&priv->dev);
}
/****************************************************************************
diff --git a/nuttx/drivers/net/enc28j60.h b/nuttx/drivers/net/enc28j60.h
index 408224b22..3c787c533 100644
--- a/nuttx/drivers/net/enc28j60.h
+++ b/nuttx/drivers/net/enc28j60.h
@@ -2,7 +2,7 @@
* drivers/net/enc28j60.h
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
* - ENC28J60 Data Sheet, Stand-Alone Ethernet Controller with SPI Interface,
@@ -56,7 +56,7 @@
*/
#define ENC_RCR (0x00) /* Read Control Register
- * 000 | aaaaa | (Registe value returned)) */
+ * 000 | aaaaa | (Register value returned)) */
#define ENC_RBM (0x3a) /* Read Buffer Memory
* 001 | 11010 | (Read buffer data follows) */
#define ENC_WCR (0x40) /* Write Control Register
diff --git a/nuttx/drivers/power/pm_activity.c b/nuttx/drivers/power/pm_activity.c
index f52fc93ff..d3c8a52e7 100644
--- a/nuttx/drivers/power/pm_activity.c
+++ b/nuttx/drivers/power/pm_activity.c
@@ -2,7 +2,7 @@
* drivers/power/pm_activity.c
*
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/power/pm_update.c b/nuttx/drivers/power/pm_update.c
index ae5e1f840..4b6b58c55 100644
--- a/nuttx/drivers/power/pm_update.c
+++ b/nuttx/drivers/power/pm_update.c
@@ -328,7 +328,7 @@ void pm_update(int16_t accum)
/* The work will be performed on the worker thread */
DEBUGASSERT(g_pmglobals.work.worker == NULL);
- (void)work_queue(&g_pmglobals.work, pm_worker, (FAR void*)((intptr_t)accum), 0);
+ (void)work_queue(HPWORK, &g_pmglobals.work, pm_worker, (FAR void*)((intptr_t)accum), 0);
}
-#endif /* CONFIG_PM */ \ No newline at end of file
+#endif /* CONFIG_PM */
diff --git a/nuttx/drivers/rwbuffer.c b/nuttx/drivers/rwbuffer.c
index 1d924e2a0..076ebc781 100644
--- a/nuttx/drivers/rwbuffer.c
+++ b/nuttx/drivers/rwbuffer.c
@@ -213,7 +213,7 @@ static void rwb_wrstarttimeout(FAR struct rwbuffer_s *rwb)
*/
int ticks = (CONFIG_FS_WRDELAY + CLK_TCK/2) / CLK_TCK;
- (void)work_queue(&rwb->work, rwb_wrtimeout, (FAR void *)rwb, ticks);
+ (void)work_queue(LPWORK, &rwb->work, rwb_wrtimeout, (FAR void *)rwb, ticks);
}
/****************************************************************************
@@ -222,7 +222,7 @@ static void rwb_wrstarttimeout(FAR struct rwbuffer_s *rwb)
static inline void rwb_wrcanceltimeout(struct rwbuffer_s *rwb)
{
- (void)work_cancel(&rwb->work);
+ (void)work_cancel(LPWORK, &rwb->work);
}
/****************************************************************************
diff --git a/nuttx/drivers/sensors/Make.defs b/nuttx/drivers/sensors/Make.defs
index d04e7541e..866ccb053 100644
--- a/nuttx/drivers/sensors/Make.defs
+++ b/nuttx/drivers/sensors/Make.defs
@@ -2,7 +2,7 @@
# drivers/sensors/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/sensors/lm75.c b/nuttx/drivers/sensors/lm75.c
index 8e1a0fb4b..2d3346447 100644
--- a/nuttx/drivers/sensors/lm75.c
+++ b/nuttx/drivers/sensors/lm75.c
@@ -3,7 +3,7 @@
* Character driver for the STMicro LM-75 Temperature Sensor
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/sercomm/Make.defs b/nuttx/drivers/sercomm/Make.defs
index 3585f5314..0cf93d4c8 100644
--- a/nuttx/drivers/sercomm/Make.defs
+++ b/nuttx/drivers/sercomm/Make.defs
@@ -2,7 +2,7 @@
# drivers/serial/Make.defs
#
# Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/sercomm/README.txt b/nuttx/drivers/sercomm/README.txt
index a9239a204..a9239a204 100755..100644
--- a/nuttx/drivers/sercomm/README.txt
+++ b/nuttx/drivers/sercomm/README.txt
diff --git a/nuttx/drivers/serial/Kconfig b/nuttx/drivers/serial/Kconfig
index b8867bd3f..43869fdec 100644
--- a/nuttx/drivers/serial/Kconfig
+++ b/nuttx/drivers/serial/Kconfig
@@ -44,10 +44,10 @@ config 16550_UART0_BITS
16550 UART0 number of bits. Default: 8
config 16550_UART0_2STOP
- bool "16550 UART0 two stop bits"
- default n
+ int "16550 UART0 two stop bits"
+ default 0
---help---
- 16550 UART0 two stop bits. Default: 1
+ 0=1 stop bit, 1=Two stop bits. Default: 1 stop bit
config 16550_UART0_RXBUFSIZE
int "16550 UART0 Rx buffer size"
@@ -94,10 +94,10 @@ config 16550_UART1_BITS
16550 UART1 number of bits. Default: 8
config 16550_UART1_2STOP
- bool "16550 UART1 two stop bits"
- default n
+ int "16550 UART1 two stop bits"
+ default 0
---help---
- 16550 UART1 two stop bits. Default: 1
+ 0=1 stop bit, 1=Two stop bits. Default: 1 stop bit
config 16550_UART1_RXBUFSIZE
int "16550 UART1 Rx buffer size"
@@ -144,10 +144,10 @@ config 16550_UART2_BITS
16550 UART2 number of bits. Default: 8
config 16550_UART2_2STOP
- bool "16550 UART2 two stop bits"
- default n
+ int "16550 UART2 two stop bits"
+ default 0
---help---
- 16550 UART2 two stop bits. Default: 1
+ 0=1 stop bit, 1=Two stop bits. Default: 1 stop bit
config 16550_UART2_RXBUFSIZE
int "16550 UART2 Rx buffer size"
@@ -194,10 +194,10 @@ config 16550_UART3_BITS
16550 UART3 number of bits. Default: 8
config 16550_UART3_2STOP
- bool "16550 UART3 two stop bits"
- default n
+ int "16550 UART3 two stop bits"
+ default 0
---help---
- 16550 UART3 two stop bits. Default: 1
+ 0=1 stop bit, 1=Two stop bits. Default: 1 stop bit
config 16550_UART3_RXBUFSIZE
int "16550 UART3 Rx buffer size"
@@ -215,25 +215,25 @@ endif
choice
prompt "16550 Serial Console"
- default NO_SERIAL_CONSOLE
+ default 16550_NO_SERIAL_CONSOLE
-config UART0_SERIAL_CONSOLE
+config 16550_UART0_SERIAL_CONSOLE
bool "16550 UART0 serial console"
depends on 16550_UART0
-config UART1_SERIAL_CONSOLE
+config 16550_UART1_SERIAL_CONSOLE
bool "16550 UART1 serial console"
depends on 16550_UART1
-config UART2_SERIAL_CONSOLE
+config 16550_UART2_SERIAL_CONSOLE
bool "16550 UART2 serial console"
depends on 16550_UART2
-config UART3_SERIAL_CONSOLE
+config 16550_UART3_SERIAL_CONSOLE
bool "16550 UART3 serial console"
depends on 16550_UART3
-config NO_SERIAL_CONSOLE
+config 16550_NO_SERIAL_CONSOLE
bool "No 16550 serial console"
endchoice
@@ -267,19 +267,783 @@ config 16550_ADDRWIDTH
endif
+#
+# MCU serial peripheral driver?
+#
+
+config ARCH_HAVE_UART
+ bool
+config ARCH_HAVE_UART0
+ bool
+config ARCH_HAVE_UART1
+ bool
+config ARCH_HAVE_UART2
+ bool
+config ARCH_HAVE_UART3
+ bool
+config ARCH_HAVE_UART4
+ bool
+config ARCH_HAVE_UART5
+ bool
+config ARCH_HAVE_UART6
+ bool
+
+config ARCH_HAVE_USART0
+ bool
+config ARCH_HAVE_USART1
+ bool
+config ARCH_HAVE_USART2
+ bool
+config ARCH_HAVE_USART3
+ bool
+config ARCH_HAVE_USART4
+ bool
+config ARCH_HAVE_USART5
+ bool
+config ARCH_HAVE_USART6
+ bool
+
+config MCU_SERIAL
+ bool
+ default y if ARCH_HAVE_UART || ARCH_HAVE_UART0 || ARCH_HAVE_USART0 || ARCH_HAVE_UART1 || ARCH_HAVE_USART1 || \
+ ARCH_HAVE_UART2 || ARCH_HAVE_USART2 || ARCH_HAVE_UART3 || ARCH_HAVE_USART3 || \
+ ARCH_HAVE_UART4 || ARCH_HAVE_USART4 || ARCH_HAVE_UART5 || ARCH_HAVE_USART5 || ARCH_HAVE_UART6 || ARCH_HAVE_USART6
+
+#
+# Standard serial driver configuration
+#
+
config STANDARD_SERIAL
- bool "Standard serial"
- default y if !LOWLEVEL_CONSOLE && !16550_UART
+ bool "Enable standard \"upper-half\" serial driver"
+ default y if MCU_SERIAL
+ default n if !MCU_SERIAL
+ depends on !LOWLEVEL_CONSOLE
+ ---help---
+ Enable the standard, upper-half serial driver used by most MCU serial peripherals.
-if STANDARD_SERIAL
config CONFIG_SERIAL_NPOLLWAITERS
int "Number of poll threads"
default 2
- depends on !DISABLE_POLL
+ depends on !DISABLE_POLL && STANDARD_SERIAL
---help---
Maximum number of threads than can be waiting for POLL events.
Default: 2
-endif
+#
+# U[S]ARTn_XYZ settings for MCU serial drivers
+#
+
+choice
+ prompt "Serial console"
+ depends on MCU_SERIAL
+ default NO_SERIAL_CONSOLE
+
+config UART_SERIAL_CONSOLE
+ bool "UART"
+ depends on ARCH_HAVE_UART
+
+config UART0_SERIAL_CONSOLE
+ bool "UART0"
+ depends on ARCH_HAVE_UART0
+
+config USART0_SERIAL_CONSOLE
+ bool "USART0"
+ depends on ARCH_HAVE_USART0
+
+config UART1_SERIAL_CONSOLE
+ bool "UART1"
+ depends on ARCH_HAVE_UART1
+
+config USART1_SERIAL_CONSOLE
+ bool "USART1"
+ depends on ARCH_HAVE_USART1
+
+config UART2_SERIAL_CONSOLE
+ bool "UART2"
+ depends on ARCH_HAVE_UART2
+
+config USART2_SERIAL_CONSOLE
+ bool "USART2"
+ depends on ARCH_HAVE_USART2
+
+config UART3_SERIAL_CONSOLE
+ bool "UART3"
+ depends on ARCH_HAVE_UART3
+
+config USART3_SERIAL_CONSOLE
+ bool "USART3"
+ depends on ARCH_HAVE_USART3
+
+config UART4_SERIAL_CONSOLE
+ bool "UART4"
+ depends on ARCH_HAVE_UART4
+
+config USART4_SERIAL_CONSOLE
+ bool "USART4"
+ depends on ARCH_HAVE_USART4
+
+config UART5_SERIAL_CONSOLE
+ bool "UART5"
+ depends on ARCH_HAVE_UART5
+
+config USART5_SERIAL_CONSOLE
+ bool "USART5"
+ depends on ARCH_HAVE_USART5
+
+config UART6_SERIAL_CONSOLE
+ bool "UART6"
+ depends on ARCH_HAVE_UART6
+
+config USART6_SERIAL_CONSOLE
+ bool "USART6"
+ depends on ARCH_HAVE_USART6
+
+config NO_SERIAL_CONSOLE
+ bool "No serial console"
+
+endchoice
+
+menu "UART Configuration"
+ depends on ARCH_HAVE_UART
+
+config UART_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART_2STOP
+ int "use 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART0 Configuration"
+ depends on ARCH_HAVE_UART0
+
+config UART0_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART0_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART0_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART0_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART0_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART0_2STOP
+ int "use 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART0 Configuration"
+ depends on ARCH_HAVE_USART0
+
+config USART0_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART0_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART0_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART0_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART0_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART0_2STOP
+ int "use 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART1 Configuration"
+ depends on ARCH_HAVE_UART1
+
+config UART1_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART1_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART1_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART1_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART1_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART1_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART1 Configuration"
+ depends on ARCH_HAVE_USART1
+
+config USART1_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART1_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART1_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART1_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART1_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART1_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART2 Configuration"
+ depends on ARCH_HAVE_UART2
+
+config UART2_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART2_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+config UART2_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART2_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART2_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART2_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART2 Configuration"
+ depends on ARCH_HAVE_USART2
+
+config USART2_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART2_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART2_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART2_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART2_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART2_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART3 Configuration"
+ depends on ARCH_HAVE_UART3
+
+config UART3_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART3_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART3_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART3_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART3_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART3_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART3 Configuration"
+ depends on ARCH_HAVE_USART3
+
+config USART3_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART3_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART3_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART3_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART3_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART3_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART4 Configuration"
+ depends on ARCH_HAVE_UART4
+
+config UART4_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART4_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART4_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART4_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART4_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART4_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART4 Configuration"
+ depends on ARCH_HAVE_USART4
+
+config USART4_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART4_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART4_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART4_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART4_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART4_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART5 Configuration"
+ depends on ARCH_HAVE_UART5
+
+config UART5_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART5_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART5_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART5_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART5_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART5_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART5 Configuration"
+ depends on ARCH_HAVE_USART5
+
+config USART5_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART5_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART5_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART5_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART5_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART5_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "USART6 Configuration"
+ depends on ARCH_HAVE_USART6
+
+config USART6_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config USART6_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config USART6_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the USART.
+
+config USART6_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config USART6_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config USART6_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+
+endmenu
+
+menu "UART6 Configuration"
+ depends on ARCH_HAVE_UART6
+
+config UART6_RXBUFSIZE
+ int "receive buffer size"
+ default 256
+ help
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config UART6_TXBUFSIZE
+ int "transmit buffer size"
+ default 256
+ help
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config UART6_BAUD
+ int "baud rate"
+ default 11520
+ help
+ The configured BAUD of the UART.
+
+config UART6_BITS
+ int "character size"
+ default 8
+ help
+ The number of bits. Must be either 7 or 8.
+
+config UART6_PARITY
+ int "parity setting"
+ default 0
+ help
+ 0=no parity, 1=odd parity, 2=even parity
+
+config UART6_2STOP
+ int "uses 2 stop bits"
+ default 0
+ help
+ 1=Two stop bits
+endmenu
diff --git a/nuttx/drivers/serial/uart_16550.c b/nuttx/drivers/serial/uart_16550.c
index ea7d944f3..8fb71bfd2 100644
--- a/nuttx/drivers/serial/uart_16550.c
+++ b/nuttx/drivers/serial/uart_16550.c
@@ -128,20 +128,20 @@ struct uart_ops_s g_uart_ops =
/* I/O buffers */
#ifdef CONFIG_16550_UART0
-static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
-static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
+static char g_uart0rxbuffer[CONFIG_16550_UART0_RXBUFSIZE];
+static char g_uart0txbuffer[CONFIG_16550_UART0_TXBUFSIZE];
#endif
#ifdef CONFIG_16550_UART1
-static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
-static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
+static char g_uart1rxbuffer[CONFIG_16550_UART1_RXBUFSIZE];
+static char g_uart1txbuffer[CONFIG_16550_UART1_TXBUFSIZE];
#endif
#ifdef CONFIG_16550_UART2
-static char g_uart2rxbuffer[CONFIG_UART1_RXBUFSIZE];
-static char g_uart2txbuffer[CONFIG_UART1_TXBUFSIZE];
+static char g_uart2rxbuffer[CONFIG_16550_UART2_RXBUFSIZE];
+static char g_uart2txbuffer[CONFIG_16550_UART2_TXBUFSIZE];
#endif
#ifdef CONFIG_16550_UART3
-static char g_uart3rxbuffer[CONFIG_UART1_RXBUFSIZE];
-static char g_uart3txbuffer[CONFIG_UART1_TXBUFSIZE];
+static char g_uart3rxbuffer[CONFIG_16550_UART3_RXBUFSIZE];
+static char g_uart3txbuffer[CONFIG_16550_UART3_TXBUFSIZE];
#endif
/* This describes the state of the LPC17xx uart0 port. */
@@ -151,16 +151,16 @@ static struct u16550_s g_uart0priv =
{
.uartbase = CONFIG_16550_UART0_BASE,
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .baud = CONFIG_UART0_BAUD,
+ .baud = CONFIG_16550_UART0_BAUD,
.uartclk = CONFIG_16550_UART0_CLOCK,
#endif
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
.irq = CONFIG_16550_UART0_IRQ,
#endif
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .parity = CONFIG_UART0_PARITY,
- .bits = CONFIG_UART0_BITS,
- .stopbits2 = CONFIG_UART0_2STOP,
+ .parity = CONFIG_16550_UART0_PARITY,
+ .bits = CONFIG_16550_UART0_BITS,
+ .stopbits2 = CONFIG_16550_UART0_2STOP,
#endif
};
@@ -168,12 +168,12 @@ static uart_dev_t g_uart0port =
{
.recv =
{
- .size = CONFIG_UART0_RXBUFSIZE,
+ .size = CONFIG_16550_UART0_RXBUFSIZE,
.buffer = g_uart0rxbuffer,
},
.xmit =
{
- .size = CONFIG_UART0_TXBUFSIZE,
+ .size = CONFIG_16550_UART0_TXBUFSIZE,
.buffer = g_uart0txbuffer,
},
.ops = &g_uart_ops,
@@ -188,16 +188,16 @@ static struct u16550_s g_uart1priv =
{
.uartbase = CONFIG_16550_UART1_BASE,
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .baud = CONFIG_UART1_BAUD,
+ .baud = CONFIG_16550_UART1_BAUD,
.uartclk = CONFIG_16550_UART1_CLOCK,
#endif
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
.irq = CONFIG_16550_UART1_IRQ,
#endif
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .parity = CONFIG_UART1_PARITY,
- .bits = CONFIG_UART1_BITS,
- .stopbits2 = CONFIG_UART1_2STOP,
+ .parity = CONFIG_16550_UART1_PARITY,
+ .bits = CONFIG_16550_UART1_BITS,
+ .stopbits2 = CONFIG_16550_UART1_2STOP,
#endif
};
@@ -205,12 +205,12 @@ static uart_dev_t g_uart1port =
{
.recv =
{
- .size = CONFIG_UART1_RXBUFSIZE,
+ .size = CONFIG_16550_UART1_RXBUFSIZE,
.buffer = g_uart1rxbuffer,
},
.xmit =
{
- .size = CONFIG_UART1_TXBUFSIZE,
+ .size = CONFIG_16550_UART1_TXBUFSIZE,
.buffer = g_uart1txbuffer,
},
.ops = &g_uart_ops,
@@ -225,16 +225,16 @@ static struct u16550_s g_uart2priv =
{
.uartbase = CONFIG_16550_UART2_BASE,
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .baud = CONFIG_UART2_BAUD,
+ .baud = CONFIG_16550_UART2_BAUD,
.uartclk = CONFIG_16550_UART2_CLOCK,
#endif
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
.irq = CONFIG_16550_UART2_IRQ,
#endif
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .parity = CONFIG_UART2_PARITY,
- .bits = CONFIG_UART2_BITS,
- .stopbits2 = CONFIG_UART2_2STOP,
+ .parity = CONFIG_16550_UART2_PARITY,
+ .bits = CONFIG_16550_UART2_BITS,
+ .stopbits2 = CONFIG_16550_UART2_2STOP,
#endif
};
@@ -242,12 +242,12 @@ static uart_dev_t g_uart2port =
{
.recv =
{
- .size = CONFIG_UART2_RXBUFSIZE,
+ .size = CONFIG_16550_UART2_RXBUFSIZE,
.buffer = g_uart2rxbuffer,
},
.xmit =
{
- .size = CONFIG_UART2_TXBUFSIZE,
+ .size = CONFIG_16550_UART2_TXBUFSIZE,
.buffer = g_uart2txbuffer,
},
.ops = &g_uart_ops,
@@ -262,16 +262,16 @@ static struct u16550_s g_uart3priv =
{
.uartbase = CONFIG_16550_UART3_BASE,
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .baud = CONFIG_UART3_BAUD,
+ .baud = CONFIG_16550_UART3_BAUD,
.uartclk = CONFIG_16550_UART3_CLOCK,
#endif
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
.irq = CONFIG_16550_UART3_IRQ,
#endif
#ifndef CONFIG_16550_SUPRESS_CONFIG
- .parity = CONFIG_UART3_PARITY,
- .bits = CONFIG_UART3_BITS,
- .stopbits2 = CONFIG_UART3_2STOP,
+ .parity = CONFIG_16550_UART3_PARITY,
+ .bits = CONFIG_16550_UART3_BITS,
+ .stopbits2 = CONFIG_16550_UART3_2STOP,
#endif
};
@@ -279,12 +279,12 @@ static uart_dev_t g_uart3port =
{
.recv =
{
- .size = CONFIG_UART3_RXBUFSIZE,
+ .size = CONFIG_16550_UART3_RXBUFSIZE,
.buffer = g_uart3rxbuffer,
},
.xmit =
{
- .size = CONFIG_UART3_TXBUFSIZE,
+ .size = CONFIG_16550_UART3_TXBUFSIZE,
.buffer = g_uart3txbuffer,
},
.ops = &g_uart_ops,
@@ -294,7 +294,7 @@ static uart_dev_t g_uart3port =
/* Which UART with be tty0/console and which tty1? tty2? tty3? */
-#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+#if defined(CONFIG_16550_UART0_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart0port /* UART0=console */
# define TTYS0_DEV g_uart0port /* UART0=ttyS0 */
# ifdef CONFIG_16550_UART1
@@ -333,7 +333,7 @@ static uart_dev_t g_uart3port =
# undef TTYS3_DEV /* No ttyS3 */
# endif
# endif
-#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+#elif defined(CONFIG_16550_UART1_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart1port /* UART1=console */
# define TTYS0_DEV g_uart1port /* UART1=ttyS0 */
# ifdef CONFIG_16550_UART
@@ -372,7 +372,7 @@ static uart_dev_t g_uart3port =
# undef TTYS3_DEV /* No ttyS3 */
# endif
# endif
-#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
+#elif defined(CONFIG_16550_UART2_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart2port /* UART2=console */
# define TTYS0_DEV g_uart2port /* UART2=ttyS0 */
# ifdef CONFIG_16550_UART
@@ -411,7 +411,7 @@ static uart_dev_t g_uart3port =
# undef TTYS3_DEV /* No ttyS3 */
# endif
# endif
-#elif defined(CONFIG_UART3_SERIAL_CONSOLE)
+#elif defined(CONFIG_16550_UART3_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart3port /* UART3=console */
# define TTYS0_DEV g_uart3port /* UART3=ttyS0 */
# ifdef CONFIG_16550_UART
@@ -1161,4 +1161,4 @@ int up_putc(int ch)
}
#endif
-#endif /* CONFIG_UART_16550 */
+#endif /* CONFIG_16550_UART */
diff --git a/nuttx/drivers/usbdev/Kconfig b/nuttx/drivers/usbdev/Kconfig
index 24b13f378..70c7a04f0 100644
--- a/nuttx/drivers/usbdev/Kconfig
+++ b/nuttx/drivers/usbdev/Kconfig
@@ -2,12 +2,97 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
+menu "Device Controller Driver Options"
+
+config USBDEV_ISOCHRONOUS
+ bool "Enable isochronous"
+ default n
+ ---help---
+ Build in extra support for isochronous endpoints
+
+config USBDEV_DUALSPEED
+ bool "Enable high and full speed"
+ default n
+ ---help---
+ Hardware handles high and full speed operation (USB 2.0)
+
+choice USBDEV_POWERED
+ prompt "Select USB device powered"
+ default USBDEV_SELFPOWERED
+
+config USBDEV_SELFPOWERED
+ bool "Self powered"
+ ---help---
+ Will cause USB features to indicate that the device is self-powered
+
+config USBDEV_BUSPOWERED
+ bool "Bus powered"
+ ---help---
+ Will cause USB features to indicate that the device is self-powered
+
+endchoice
+
+config USBDEV_MAXPOWER
+ int "Maximum power consumption in mA"
+ default 100
+ depends on USBDEV_BUSPOWERED
+ ---help---
+ Maximum power consumption in mA
+
+config USBDEV_DMA
+ bool "Enable DMA methods"
+ default n
+ ---help---
+ Select this enable DMA-related methods in USB device controller driver
+ interface. These methods include the DMA buffer allocation methods:
+ allobuffer() and freebuffer().
+
+ The USB class driver allocates packet I/O buffers for data transfer by
+ calling the driver allocbuffer() and freebuffer() methods. Those methods
+ are only available if USBDEV_DMA is defined in the system configuration.
+
+config USBDEV_DMAMEMORY
+bool "Board DMA Allocation Hooks"
+ default n
+ depends on USBDEV_DMA
+ ---help---
+ The USB class driver allocates packet I/O buffers for data transfer by
+ calling the driver allocbuffer() and freebuffer() methods. Those methods
+ are only available if USBDEV_DMA is defined in the system configuration.
+
+ If USBDEV_DMAMEMORY is also defined in the NuttX configuration, then
+ the driver implementations of the allocbuffer() and freebuffer()
+ methods may use board-specific usbdev_dma_alloc() and usbdev_dma_free().
+ If USBDEV_DMA and USBDEV_DMAMEMORY are both defined, then the board-
+ specific logic must provide the functions usbdev_dma_alloc() and
+ usbdev_dma_free(): usbdev_dma_alloc() will allocate DMA-capable
+ memory of the specified size; usbdev_dma_free() is the corresponding
+ function that will be called to free the DMA-capable memory.
+
+config USBDEV_TRACE
+ bool "Enable USB tracing for debug"
+ default n
+ ---help---
+ Enables USB tracing for debug
+
+config USBDEV_TRACE_NRECORDS
+ int "Number of trace entries to remember"
+ default 32
+ depends on USBDEV_TRACE
+ ---help---
+ Number of trace entries to remember
+
+endmenu
+
menuconfig USBDEV_COMPOSITE
bool "USB composite device support"
default n
---help---
Enables USB composite device support
+
if USBDEV_COMPOSITE
+
#config COMPOSITE_IAD
# bool ""
# default n
@@ -62,59 +147,12 @@ config COMPOSITE_VERSIONNO
Interface version number.
endif
-config USBDEV_ISOCHRONOUS
- bool "Enable isochronous"
- default n
- ---help---
- Build in extra support for isochronous endpoints
-
-config USBDEV_DUALSPEED
- bool "Enable high and full speed"
- default n
- ---help---
- Hardware handles high and full speed
- operation (USB 2.0)
-
-choice USBDEV_POWERED
- prompt "Select USB device powered"
- default USBDEV_SELFPOWERED
-config USBDEV_SELFPOWERED
- bool "Self powerd"
- ---help---
- Will cause USB features to indicate
- that the device is self-powered
-
-config USBDEV_BUSPOWERED
- bool "Bus powerd"
- ---help---
- Will cause USB features to indicate
- that the device is self-powered
-endchoice
-config USBDEV_MAXPOWER
- int "Maximum power consumption in mA"
- default 100
- depends on USBDEV_BUSPOWERED
- ---help---
- Maximum power consumption in mA
-
-config USBDEV_TRACE
- bool "Enable USB tracing for debug"
- default n
- ---help---
- Enables USB tracing for debug
-
-config USBDEV_TRACE_NRECORDS
- int "Number of trace entries to remember"
- default 32
- depends on USBDEV_TRACE
- ---help---
- Number of trace entries to remember
-
menuconfig PL2303
bool "Emulates the Prolific PL2303 serial/USB converter"
default n
---help---
This logic emulates the Prolific PL2303 serial/USB converter
+
if PL2303
config PL2303_EPINTIN
int "Logical endpoint numbers"
@@ -178,6 +216,7 @@ menuconfig CDCACM
default n
---help---
Enables USB Modem (CDC ACM) support
+
if CDCACM
config CDCACM_COMPOSITE
bool "CDCACM composite support"
@@ -443,6 +482,10 @@ config USBMSC_PRODUCTSTR
string "Mass stroage product string"
default "Mass stroage"
+config USBMSC_VERSIONNO
+ hex "USB MSC Version Number"
+ default "0x399"
+
config USBMSC_REMOVABLE
bool "Mass stroage remove able"
default n
diff --git a/nuttx/drivers/usbhost/Make.defs b/nuttx/drivers/usbhost/Make.defs
index cc28e874d..fd54ab53e 100644
--- a/nuttx/drivers/usbhost/Make.defs
+++ b/nuttx/drivers/usbhost/Make.defs
@@ -2,7 +2,7 @@
# drivers/usbhost/Make.defs
#
# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/usbhost/usbhost_findclass.c b/nuttx/drivers/usbhost/usbhost_findclass.c
index f08aff580..3e38670cf 100644
--- a/nuttx/drivers/usbhost/usbhost_findclass.c
+++ b/nuttx/drivers/usbhost/usbhost_findclass.c
@@ -2,7 +2,7 @@
* drivers/usbhost/usbhost_findclass.c
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c
index 73224ff5c..e69d68e7b 100644
--- a/nuttx/drivers/usbhost/usbhost_hidkbd.c
+++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c
@@ -2,7 +2,7 @@
* drivers/usbhost/usbhost_hidkbd.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -1674,7 +1674,7 @@ static int usbhost_disconnected(struct usbhost_class_s *class)
*/
DEBUGASSERT(priv->work.worker == NULL);
- (void)work_queue(&priv->work, usbhost_destroy, priv, 0);
+ (void)work_queue(HPWORK, &priv->work, usbhost_destroy, priv, 0);
}
return OK;
diff --git a/nuttx/drivers/usbhost/usbhost_registerclass.c b/nuttx/drivers/usbhost/usbhost_registerclass.c
index 76ef511af..f4d1b64af 100644
--- a/nuttx/drivers/usbhost/usbhost_registerclass.c
+++ b/nuttx/drivers/usbhost/usbhost_registerclass.c
@@ -2,7 +2,7 @@
* drivers/usbhost/usbhost_registerclass.c
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/usbhost/usbhost_registry.c b/nuttx/drivers/usbhost/usbhost_registry.c
index 56c03e2dc..fb2e900e2 100644
--- a/nuttx/drivers/usbhost/usbhost_registry.c
+++ b/nuttx/drivers/usbhost/usbhost_registry.c
@@ -2,7 +2,7 @@
* drivers/usbhost/usbhost_registry.c
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/usbhost/usbhost_registry.h b/nuttx/drivers/usbhost/usbhost_registry.h
index 63436af5d..759a1c66e 100644
--- a/nuttx/drivers/usbhost/usbhost_registry.h
+++ b/nuttx/drivers/usbhost/usbhost_registry.h
@@ -2,7 +2,7 @@
* drivers/usbhost/usbdev_registry.h
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/usbhost/usbhost_skeleton.c b/nuttx/drivers/usbhost/usbhost_skeleton.c
index 0a88a4f1b..c44a265e8 100644
--- a/nuttx/drivers/usbhost/usbhost_skeleton.c
+++ b/nuttx/drivers/usbhost/usbhost_skeleton.c
@@ -1,8 +1,8 @@
/****************************************************************************
* drivers/usbhost/usbhost_skeleton.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -1015,7 +1015,7 @@ static int usbhost_disconnected(struct usbhost_class_s *class)
uvdbg("Queuing destruction: worker %p->%p\n", priv->work.worker, usbhost_destroy);
DEBUGASSERT(priv->work.worker == NULL);
- (void)work_queue(&priv->work, usbhost_destroy, priv, 0);
+ (void)work_queue(HPWORK, &priv->work, usbhost_destroy, priv, 0);
}
else
{
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index 2e3136b33..2b14676d7 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -1786,7 +1786,7 @@ static int usbhost_disconnected(struct usbhost_class_s *class)
uvdbg("Queuing destruction: worker %p->%p\n", priv->work.worker, usbhost_destroy);
DEBUGASSERT(priv->work.worker == NULL);
- (void)work_queue(&priv->work, usbhost_destroy, priv, 0);
+ (void)work_queue(HPWORK, &priv->work, usbhost_destroy, priv, 0);
}
else
{
diff --git a/nuttx/drivers/wireless/Make.defs b/nuttx/drivers/wireless/Make.defs
index ac73c8d85..f47f7666a 100644
--- a/nuttx/drivers/wireless/Make.defs
+++ b/nuttx/drivers/wireless/Make.defs
@@ -2,7 +2,7 @@
# drivers/wireless/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/wireless/cc1101/cc1101.c b/nuttx/drivers/wireless/cc1101/cc1101.c
index 45faaecd2..45faaecd2 100755..100644
--- a/nuttx/drivers/wireless/cc1101/cc1101.c
+++ b/nuttx/drivers/wireless/cc1101/cc1101.c