summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-09-07 13:32:13 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-09-07 13:32:13 +0000
commitc9e0f9f37ea4d38a26baad8dafbf2e82f73322db (patch)
treeaed1608fbd3bfc8e9132c3514a192a75b0571a04
parentf8523254d0c4584e1a56d835ab0af9e8a8625c4b (diff)
downloadnuttx-c9e0f9f37ea4d38a26baad8dafbf2e82f73322db.tar.gz
nuttx-c9e0f9f37ea4d38a26baad8dafbf2e82f73322db.tar.bz2
nuttx-c9e0f9f37ea4d38a26baad8dafbf2e82f73322db.zip
Add AT24xx and LPC17xx I2C drivers (from Lzyy)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3941 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/Documentation/NuttX.html9
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/Make.defs5
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_i2c.c545
-rw-r--r--nuttx/drivers/mtd/Make.defs4
-rwxr-xr-xnuttx/drivers/mtd/at24xx.c349
-rw-r--r--nuttx/include/nuttx/mtd.h12
7 files changed, 922 insertions, 7 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 32522415b..97b90f608 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2056,4 +2056,7 @@
Timeout calculation uses clock_settime() instead of clock_gettime().
Pretty gross error, but actually it works with the side effect of setting
a bad time.
-
+ * drivers/mtd/at24xx.c: Driver for I2C-based at24cxx EEPROM submitted by
+ Li Zhuoyi (Lzyy).
+ * arch/arm/src/lpc17xx/lpc17_i2c.c: I2C driver for the NXP LPC17xx family
+ submitted by Li Zhuoyi (Lzyy)
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index c93b87034..20e81e48f 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: September 4, 2011</p>
+ <p>Last Updated: September 7, 2011</p>
</td>
</tr>
</table>
@@ -1461,7 +1461,8 @@
<td>
<p>
<b>NXP LPC1766 and LPC1768</b>.
- Configurations are available for three boards:
+ Drivers are available for CAN, DAC, Ethernet, GPIO, GPIO interrupts, I2C, UARTs, SPI, SSP, USB host, and USB device.
+ Verified LPC17xx onfigurations are available for three boards.
<ul>
<li>
The Nucleus 2G board from <a href="http://www.2g-eng.com/">2G Engineering</a> (LPC1768),
@@ -1470,7 +1471,7 @@
The mbed board from <a href="http://mbed.org">mbed.org</a> (LPC1768, Contributed by Dave Marples), and
</li>
<li>
- The LPC1766-sTK board from <a href="http://www.olimex.com/">Olimex</a> (LPC1766).
+ The LPC1766-STK board from <a href="http://www.olimex.com/">Olimex</a> (LPC1766).
</li>
<li>
The Embedded Artists base board with NXP LPCXpresso LPC1768.
@@ -1478,7 +1479,7 @@
</ul>
</p>
<p>
- The Nucleus 2G boar, the mbed board, and the LPCXpresso all feature the NXP LPC1768 MCU;
+ The Nucleus 2G board, the mbed board, and the LPCXpresso all feature the NXP LPC1768 MCU;
the Olimex LPC1766-STK board features an LPC1766.
All use a GNU arm-elf or arm-eabi toolchain* under either Linux or Cygwin (with native Windows GNU tools or Cygwin-based GNU tools).
</p>
diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs
index 1f779f6d4..34591e531 100755
--- a/nuttx/arch/arm/src/lpc17xx/Make.defs
+++ b/nuttx/arch/arm/src/lpc17xx/Make.defs
@@ -58,8 +58,9 @@ endif
CHIP_ASRCS =
CHIP_CSRCS = lpc17_allocateheap.c lpc17_can.c lpc17_clockconfig.c \
- lpc17_clrpend.c lpc17_gpio.c lpc17_idle.c lpc17_irq.c lpc17_lowputc.c \
- lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c lpc17_timerisr.c
+ lpc17_clrpend.c lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c \
+ lpc17_lowputc.c lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c \
+ lpc17_timerisr.c
# Configuration-dependent LPC17xx files
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c b/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c
new file mode 100755
index 000000000..ccff276e5
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c
@@ -0,0 +1,545 @@
+/*******************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_i2c.c
+ *
+ * Copyright (C) 2011 Li Zhuoyi. All rights reserved.
+ * Author: Li Zhuoyi <lzyy.cn@gmail.com>
+ * History: 0.1 2011-08-20 initial version
+ *
+ * Derived from arch/arm/src/lpc31xx/lpc31_i2c.c
+ *
+ * Author: David Hewson
+ *
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ *******************************************************************************/
+
+/*******************************************************************************
+ * Included Files
+ *******************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/i2c.h>
+
+#include <arch/irq.h>
+#include <arch/board/board.h>
+
+#include "wdog.h"
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+
+
+#include "lpc17_internal.h"
+#include "lpc17_syscon.h"
+#include "lpc17_pinconn.h"
+#include "lpc17_i2c.h"
+
+#if defined(CONFIG_LPC17_I2C0) || defined(CONFIG_LPC17_I2C1) || defined(CONFIG_LPC17_I2C2)
+
+#ifndef GPIO_I2C1_SCL
+ #define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
+ #define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
+#endif
+#ifndef CONFIG_I2C0_FREQ
+ #define CONFIG_I2C0_FREQ 100000
+#endif
+#ifndef CONFIG_I2C1_FREQ
+ #define CONFIG_I2C1_FREQ 100000
+#endif
+#ifndef CONFIG_I2C2_FREQ
+ #define CONFIG_I2C2_FREQ 100000
+#endif
+
+/*******************************************************************************
+ * Definitions
+ *******************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define I2C_TIMEOUT ((20 * CLK_TCK) / 1000) /* 20 mS */
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+struct lpc17_i2cdev_s
+{
+ struct i2c_dev_s dev; /* Generic I2C device */
+ struct i2c_msg_s msg; /* a single message for legacy read/write */
+ unsigned int base; /* Base address of registers */
+ uint16_t irqid; /* IRQ for this device */
+
+ sem_t mutex; /* Only one thread can access at a time */
+ sem_t wait; /* Place to wait for state machine completion */
+ volatile uint8_t state; /* State of state machine */
+ WDOG_ID timeout; /* watchdog to timeout when bus hung */
+
+ uint16_t wrcnt; /* number of bytes sent to tx fifo */
+ uint16_t rdcnt; /* number of bytes read from rx fifo */
+};
+
+static struct lpc17_i2cdev_s i2cdevices[3];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+static int i2c_start (struct lpc17_i2cdev_s *priv);
+static void i2c_stop (struct lpc17_i2cdev_s *priv);
+static int i2c_interrupt (int irq, FAR void *context);
+static void i2c_timeout (int argc, uint32_t arg, ...);
+
+/****************************************************************************
+ * I2C device operations
+ ****************************************************************************/
+
+static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency);
+static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits);
+static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen);
+static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen);
+static int i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count);
+
+struct i2c_ops_s lpc17_i2c_ops =
+{
+ .setfrequency = i2c_setfrequency,
+ .setaddress = i2c_setaddress,
+ .write = i2c_write,
+ .read = i2c_read,
+#ifdef CONFIG_I2C_TRANSFER
+ .transfer = i2c_transfer
+#endif
+};
+
+/*******************************************************************************
+ * Name: lpc17_i2c_setfrequency
+ *
+ * Description:
+ * Set the frequence for the next transfer
+ *
+ *******************************************************************************/
+
+static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency)
+{
+ struct lpc17_i2cdev_s *priv = (struct lpc17_i2cdev_s *) dev;
+
+ if (frequency > 100000)
+ {
+ /* asymetric per 400Khz I2C spec */
+ putreg32 ( LPC17_CCLK / (83 + 47) * 47 / frequency, priv->base + LPC17_I2C_SCLH_OFFSET);
+ putreg32 ( LPC17_CCLK / (83 + 47) * 83 / frequency, priv->base + LPC17_I2C_SCLL_OFFSET);
+ }
+ else
+ {
+ /* 50/50 mark space ratio */
+ putreg32 (LPC17_CCLK / 100 * 50 / frequency, priv->base + LPC17_I2C_SCLH_OFFSET);
+ putreg32 (LPC17_CCLK / 100 * 50 / frequency, priv->base + LPC17_I2C_SCLL_OFFSET);
+ }
+
+ /* FIXME: This function should return the actual selected frequency */
+ return frequency;
+}
+
+/*******************************************************************************
+ * Name: lpc17_i2c_setaddress
+ *
+ * Description:
+ * Set the I2C slave address for a subsequent read/write
+ *
+ *******************************************************************************/
+static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits)
+{
+ struct lpc17_i2cdev_s *priv = (struct lpc17_i2cdev_s *) dev;
+
+ DEBUGASSERT(dev != NULL);
+ DEBUGASSERT(nbits == 7 );
+
+ priv->msg.addr = addr<<1;
+ priv->msg.flags = 0 ;
+
+ return OK;
+}
+
+/*******************************************************************************
+ * Name: lpc17_i2c_write
+ *
+ * Description:
+ * Send a block of data on I2C using the previously selected I2C
+ * frequency and slave address.
+ *
+ *******************************************************************************/
+static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen)
+{
+ struct lpc17_i2cdev_s *priv = (struct lpc17_i2cdev_s *) dev;
+ int ret;
+
+ DEBUGASSERT (dev != NULL);
+
+ priv->wrcnt=0;
+ priv->rdcnt=0;
+ priv->msg.addr &= ~0x01;
+ priv->msg.buffer = (uint8_t*)buffer;
+ priv->msg.length = buflen;
+
+ ret = i2c_start (priv);
+
+ return ret >0 ? OK : -ETIMEDOUT;
+}
+
+/*******************************************************************************
+ * Name: lpc17_i2c_read
+ *
+ * Description:
+ * Receive a block of data on I2C using the previously selected I2C
+ * frequency and slave address.
+ *
+ *******************************************************************************/
+static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen)
+{
+ struct lpc17_i2cdev_s *priv = (struct lpc17_i2cdev_s *) dev;
+ int ret;
+
+ DEBUGASSERT (dev != NULL);
+
+ priv->wrcnt=0;
+ priv->rdcnt=0;
+ priv->msg.addr |= 0x01;
+ priv->msg.buffer = buffer;
+ priv->msg.length = buflen;
+
+ ret = i2c_start (priv);
+
+ return ret >0 ? OK : -ETIMEDOUT;
+}
+
+/*******************************************************************************
+ * Name: i2c_start
+ *
+ * Description:
+ * Perform a I2C transfer start
+ *
+ *******************************************************************************/
+static int i2c_start (struct lpc17_i2cdev_s *priv)
+{
+ int ret=-1;
+ sem_wait (&priv->mutex);
+
+ putreg32(I2C_CONCLR_STAC|I2C_CONCLR_SIC,priv->base+LPC17_I2C_CONCLR_OFFSET);
+ putreg32(I2C_CONSET_STA,priv->base+LPC17_I2C_CONSET_OFFSET);
+
+ wd_start (priv->timeout, I2C_TIMEOUT, i2c_timeout, 1, (uint32_t)priv);
+ sem_wait(&priv->wait);
+ wd_cancel (priv->timeout);
+ sem_post (&priv->mutex);
+
+ if( priv-> state == 0x18 || priv->state == 0x28)
+ ret=priv->wrcnt;
+ else if( priv-> state == 0x50 || priv->state == 0x58)
+ ret=priv->rdcnt;
+ return ret;
+}
+
+/*******************************************************************************
+ * Name: i2c_stop
+ *
+ * Description:
+ * Perform a I2C transfer stop
+ *
+ *******************************************************************************/
+static void i2c_stop (struct lpc17_i2cdev_s *priv)
+{
+ if(priv->state!=0x38)
+ putreg32(I2C_CONSET_STO|I2C_CONSET_AA,priv->base+LPC17_I2C_CONSET_OFFSET);
+ sem_post (&priv->wait);
+}
+
+/*******************************************************************************
+ * Name: i2c_timeout
+ *
+ * Description:
+ * Watchdog timer for timeout of I2C operation
+ *
+ *******************************************************************************/
+
+static void i2c_timeout (int argc, uint32_t arg, ...)
+{
+ struct lpc17_i2cdev_s *priv = (struct lpc17_i2cdev_s *) arg;
+
+ irqstate_t flags = irqsave();
+ priv->state = 0xff;
+ sem_post (&priv->wait);
+ irqrestore (flags);
+}
+
+/*******************************************************************************
+ * Name: i2c_interrupt
+ *
+ * Description:
+ * The I2C Interrupt Handler
+ *
+ *******************************************************************************/
+
+static int i2c_interrupt (int irq, FAR void *context)
+{
+ struct lpc17_i2cdev_s *priv;
+#ifdef CONFIG_LPC17_I2C0
+ if (irq == LPC17_IRQ_I2C0)
+ {
+ priv=&i2cdevices[0];
+ }
+ else
+#endif
+#ifdef CONFIG_LPC17_I2C1
+ if (irq == LPC17_IRQ_I2C1)
+ {
+ priv=&i2cdevices[1];
+ }
+ else
+#endif
+#ifdef CONFIG_LPC17_I2C2
+ if (irq == LPC17_IRQ_I2C2)
+ {
+ priv=&i2cdevices[2];
+ }
+ else
+#endif
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+/*
+ * refrence UM10360 19.10.5
+ */
+ uint32_t state = getreg32(priv->base+LPC17_I2C_STAT_OFFSET);
+ putreg32(I2C_CONCLR_SIC,priv->base+LPC17_I2C_CONCLR_OFFSET);
+ priv->state=state;
+ state &=0xf8;
+ switch (state)
+ {
+ case 0x00: //Bus Error
+ case 0x20:
+ case 0x30:
+ case 0x38:
+ case 0x48:
+ i2c_stop(priv);
+ break;
+ case 0x08: //START
+ case 0x10: //Repeat START
+ putreg32(priv->msg.addr,priv->base+LPC17_I2C_DAT_OFFSET);
+ putreg32(I2C_CONCLR_STAC,priv->base+LPC17_I2C_CONCLR_OFFSET);
+ break;
+ case 0x18:
+ priv->wrcnt=0;
+ putreg32(priv->msg.buffer[0],priv->base+LPC17_I2C_DAT_OFFSET);
+ break;
+ case 0x28:
+ priv->wrcnt++;
+ if(priv->wrcnt<priv->msg.length)
+ putreg32(priv->msg.buffer[priv->wrcnt],priv->base+LPC17_I2C_DAT_OFFSET);
+ else
+ i2c_stop(priv);
+ break;
+ case 0x40:
+ priv->rdcnt=-1;
+ putreg32(I2C_CONSET_AA,priv->base+LPC17_I2C_CONSET_OFFSET);
+ break;
+ case 0x50:
+ priv->rdcnt++;
+ if(priv->rdcnt<priv->msg.length)
+ priv->msg.buffer[priv->rdcnt]=getreg32(priv->base+LPC17_I2C_BUFR_OFFSET);
+ if(priv->rdcnt>=priv->msg.length-1)
+ putreg32(I2C_CONCLR_AAC|I2C_CONCLR_SIC,priv->base+LPC17_I2C_CONCLR_OFFSET);
+ break;
+ case 0x58:
+ i2c_stop(priv);
+ break;
+ default:
+ i2c_stop(priv);
+ break;
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+
+/*******************************************************************************
+ * Name: up_i2cinitialize
+ *
+ * Description:
+ * Initialise an I2C device
+ *
+ *******************************************************************************/
+
+struct i2c_dev_s *up_i2cinitialize(int port)
+{
+ struct lpc17_i2cdev_s *priv;
+
+ if (port>2)
+ {
+ dbg("lpc I2C Only support 0,1,2\n");
+ return NULL;
+ }
+
+ irqstate_t flags;
+ uint32_t regval;
+
+ flags = irqsave();
+
+ priv= &i2cdevices[port];
+#ifdef CONFIG_LPC17_I2C0
+ if (port==0)
+ {
+ priv= (FAR struct lpc17_i2cdev_s *)&i2cdevices[0];
+ priv->base = LPC17_I2C0_BASE;
+ priv->irqid = LPC17_IRQ_I2C0;
+
+ regval = getreg32(LPC17_SYSCON_PCONP);
+ regval |= SYSCON_PCONP_PCI2C0;
+ putreg32(regval, LPC17_SYSCON_PCONP);
+
+ regval = getreg32(LPC17_SYSCON_PCLKSEL0);
+ regval &= ~SYSCON_PCLKSEL0_I2C0_MASK;
+ regval |= (SYSCON_PCLKSEL_CCLK << SYSCON_PCLKSEL0_I2C0_SHIFT);
+ putreg32(regval, LPC17_SYSCON_PCLKSEL0);
+
+ lpc17_configgpio(GPIO_I2C0_SCL);
+ lpc17_configgpio(GPIO_I2C0_SDA);
+
+ putreg32 (LPC17_CCLK/CONFIG_I2C0_FREQ/2, priv->base + LPC17_I2C_SCLH_OFFSET);
+ putreg32 (LPC17_CCLK/CONFIG_I2C0_FREQ/2, priv->base + LPC17_I2C_SCLL_OFFSET);
+
+ }
+ else
+#endif
+#ifdef CONFIG_LPC17_I2C1
+ if(port==1)
+ {
+ priv= (FAR struct lpc17_i2cdev_s *)&i2cdevices[1];
+ priv->base = LPC17_I2C1_BASE;
+ priv->irqid = LPC17_IRQ_I2C1;
+
+ regval = getreg32(LPC17_SYSCON_PCONP);
+ regval |= SYSCON_PCONP_PCI2C1;
+ putreg32(regval, LPC17_SYSCON_PCONP);
+
+ regval = getreg32(LPC17_SYSCON_PCLKSEL1);
+ regval &= ~SYSCON_PCLKSEL1_I2C1_MASK;
+ regval |= (SYSCON_PCLKSEL_CCLK << SYSCON_PCLKSEL1_I2C1_SHIFT);
+ putreg32(regval, LPC17_SYSCON_PCLKSEL1);
+
+ lpc17_configgpio(GPIO_I2C1_SCL);
+ lpc17_configgpio(GPIO_I2C1_SDA);
+
+ putreg32 (LPC17_CCLK/CONFIG_I2C1_FREQ/2, priv->base + LPC17_I2C_SCLH_OFFSET);
+ putreg32 (LPC17_CCLK/CONFIG_I2C1_FREQ/2, priv->base + LPC17_I2C_SCLL_OFFSET);
+ }
+ else
+#endif
+#ifdef CONFIG_LPC17_I2C2
+ if(port==2)
+ {
+ priv= (FAR struct lpc17_i2cdev_s *)&i2cdevices[2];
+ priv->base = LPC17_I2C2_BASE;
+ priv->irqid = LPC17_IRQ_I2C2;
+
+ regval = getreg32(LPC17_SYSCON_PCONP);
+ regval |= SYSCON_PCONP_PCI2C2;
+ putreg32(regval, LPC17_SYSCON_PCONP);
+
+ regval = getreg32(LPC17_SYSCON_PCLKSEL1);
+ regval &= ~SYSCON_PCLKSEL1_I2C2_MASK;
+ regval |= (SYSCON_PCLKSEL_CCLK << SYSCON_PCLKSEL1_I2C2_SHIFT);
+ putreg32(regval, LPC17_SYSCON_PCLKSEL1);
+
+ lpc17_configgpio(GPIO_I2C2_SCL);
+ lpc17_configgpio(GPIO_I2C2_SDA);
+
+ putreg32 (LPC17_CCLK/CONFIG_I2C2_FREQ/2, priv->base + LPC17_I2C_SCLH_OFFSET);
+ putreg32 (LPC17_CCLK/CONFIG_I2C2_FREQ/2, priv->base + LPC17_I2C_SCLL_OFFSET);
+ }
+ else
+#endif
+ {
+ return NULL;
+ }
+ putreg32(I2C_CONSET_I2EN,priv->base+LPC17_I2C_CONSET_OFFSET);
+
+ sem_init (&priv->mutex, 0, 1);
+ sem_init (&priv->wait, 0, 0);
+
+ /* Allocate a watchdog timer */
+ priv->timeout = wd_create();
+
+ DEBUGASSERT(priv->timeout != 0);
+
+ /* Attach Interrupt Handler */
+ irq_attach (priv->irqid, i2c_interrupt);
+
+ /* Enable Interrupt Handler */
+ up_enable_irq(priv->irqid);
+
+ /* Install our operations */
+ priv->dev.ops = &lpc17_i2c_ops;
+
+ return &priv->dev;
+}
+
+/*******************************************************************************
+ * Name: up_i2cuninitalize
+ *
+ * Description:
+ * Uninitialise an I2C device
+ *
+ *******************************************************************************/
+
+int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
+{
+ struct lpc17_i2cdev_s *priv = (struct lpc17_i2cdev_s *) dev;
+
+ putreg32(I2C_CONCLRT_I2ENC,priv->base+LPC17_I2C_CONCLR_OFFSET);
+ up_disable_irq(priv->irqid);
+ irq_detach (priv->irqid);
+ return OK;
+}
+
+#endif
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index 2a1143158..2f4b9e86d 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -38,6 +38,10 @@
CSRCS += at45db.c flash_eraseall.c ftl.c m25px.c rammtd.c ramtron.c
+ifeq ($(CONFIG_MTD_AT24XX),y)
+CSRCS += at24xx.c
+endif
+
# Include MTD driver support
DEPPATH += --dep-path mtd
diff --git a/nuttx/drivers/mtd/at24xx.c b/nuttx/drivers/mtd/at24xx.c
new file mode 100755
index 000000000..2aa116d83
--- /dev/null
+++ b/nuttx/drivers/mtd/at24xx.c
@@ -0,0 +1,349 @@
+/************************************************************************************
+ * drivers/mtd/at24xx.c
+ * Driver for I2C-based at24cxx EEPROM(at24c32,at24c64,at24c128,at24c256)
+ *
+ * Copyright (C) 2011 Li Zhuoyi. All rights reserved.
+ * Author: Li Zhuoyi <lzyy.cn@gmail.com>
+ * History: 0.1 2011-08-20 initial version
+ *
+ * Derived from drivers/mtd/m25px.c
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/ioctl.h>
+#include <nuttx/i2c.h>
+#include <nuttx/mtd.h>
+
+#ifdef CONFIG_MTD_AT24XX
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+#ifndef CONFIG_AT24XX_SIZE
+#define CONFIG_AT24XX_SIZE 64
+#endif
+#ifndef CONFIG_AT24XX_ADDR
+#define CONFIG_AT24XX_ADDR 0x50
+#endif
+
+#if CONFIG_AT24XX_SIZE == 32
+#define AT24XX_NPAGES 128
+#define AT24XX_PAGESIZE 32
+#elif CONFIG_AT24XX_SIZE == 64
+#define AT24XX_NPAGES 256
+#define AT24XX_PAGESIZE 32
+#elif CONFIG_AT24XX_SIZE == 128
+#define AT24XX_NPAGES 256
+#define AT24XX_PAGESIZE 64
+#elif CONFIG_AT24XX_SIZE == 256
+#define AT24XX_NPAGES 512
+#define AT24XX_PAGESIZE 64
+#endif
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/* This type represents the state of the MTD device. The struct mtd_dev_s
+ * must appear at the beginning of the definition so that you can freely
+ * cast between pointers to struct mtd_dev_s and struct at24c_dev_s.
+ */
+
+struct at24c_dev_s
+{
+ struct mtd_dev_s mtd; /* MTD interface */
+ FAR struct i2c_dev_s *dev; /* Saved I2C interface instance */
+ uint8_t addr;
+ uint16_t pagesize; /* 32,63 */
+ uint16_t npages; /* 128,256,512,1024 */
+};
+
+/************************************************************************************
+ * Private Function Prototypes
+ ************************************************************************************/
+
+/* MTD driver methods */
+
+static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
+static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,size_t nblocks, FAR uint8_t *buf);
+static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,size_t nblocks, FAR const uint8_t *buf);
+static ssize_t at24c_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,FAR uint8_t *buffer);
+static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+static struct at24c_dev_s g_at24c =
+{
+ .addr = CONFIG_AT24XX_ADDR,
+ .pagesize = AT24XX_PAGESIZE,
+ .npages = AT24XX_NPAGES,
+};
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+static int at24c_eraseall(FAR struct at24c_dev_s *priv)
+{
+ int blocksleft = priv->pagesize;
+ int startblock = 0;
+ uint8_t buf[66];
+ memset(&buf[2],0xff,priv->pagesize);
+ I2C_SETADDRESS(priv->dev,priv->addr,7);
+ I2C_SETFREQUENCY(priv->dev,100000);
+ while (blocksleft-- > 0)
+ {
+ uint16_t offset=startblock*priv->pagesize;
+ buf[1]=offset&0xff;
+ buf[0]=(offset>>8)&0xff;
+
+ while (I2C_WRITE(priv->dev,buf,2)<0)
+ {
+ usleep(1000);
+ }
+ I2C_WRITE(priv->dev, buf, priv->pagesize+2);
+ startblock++;
+ }
+ return OK;
+}
+
+/************************************************************************************
+ * Name: at24c_erase
+ ************************************************************************************/
+
+static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
+{
+ /*
+ * EEprom need not erase
+ */
+ return (int)nblocks;
+}
+
+/************************************************************************************
+ * Name: at24c_bread
+ ************************************************************************************/
+
+static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR uint8_t *buffer)
+{
+ FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
+ size_t blocksleft = nblocks;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ if (startblock >= priv->npages)
+ {
+ return 0;
+ }
+
+ if (startblock + nblocks > priv->npages)
+ {
+ nblocks = priv->npages - startblock;
+ }
+
+ I2C_SETADDRESS(priv->dev,priv->addr,7);
+ I2C_SETFREQUENCY(priv->dev,100000);
+ int tail;
+ while (blocksleft-- > 0)
+ {
+ uint16_t offset=startblock*priv->pagesize;
+ uint8_t buf[2];
+ buf[1]=offset&0xff;
+ buf[0]=(offset>>8)&0xff;
+ while (I2C_WRITE(priv->dev,buf,2)<0)
+ {
+ fvdbg("wait\n");
+ usleep(1000);
+ }
+ I2C_READ(priv->dev, buffer,priv->pagesize);
+ startblock++;
+ buffer+=priv->pagesize;
+ }
+ return nblocks;
+}
+
+/************************************************************************************
+ * Name: at24c_bwrite
+ ************************************************************************************/
+
+static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const uint8_t *buffer)
+{
+ FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
+ size_t blocksleft = nblocks;
+ uint8_t buf[66];
+
+ if (startblock >= priv->npages)
+ {
+ return 0;
+ }
+
+ if (startblock + nblocks > priv->npages)
+ {
+ nblocks = priv->npages - startblock;
+ }
+
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+ I2C_SETADDRESS(priv->dev,priv->addr,7);
+ I2C_SETFREQUENCY(priv->dev,100000);
+ while (blocksleft-- > 0)
+ {
+ uint16_t offset=startblock*priv->pagesize;
+ while (I2C_WRITE(priv->dev,(uint8_t *)&offset,2)<0)
+ {
+ fvdbg("wait\n");
+ usleep(1000);
+ }
+ buf[1]=offset&0xff;
+ buf[0]=(offset>>8)&0xff;
+ memcpy(&buf[2],buffer,priv->pagesize);
+
+ I2C_WRITE(priv->dev, buf, priv->pagesize+2);
+ startblock++;
+ buffer+=priv->pagesize;
+ }
+ return nblocks;
+}
+
+/************************************************************************************
+ * Name: at24c_ioctl
+ ************************************************************************************/
+
+static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
+{
+ FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
+ int ret = -EINVAL; /* Assume good command with bad parameters */
+
+ fvdbg("cmd: %d \n", cmd);
+
+ switch (cmd)
+ {
+ case MTDIOC_GEOMETRY:
+ {
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg);
+ if (geo)
+ {
+ /* Populate the geometry structure with information need to know
+ * the capacity and how to access the device.
+ *
+ * NOTE: that the device is treated as though it where just an array
+ * of fixed size blocks. That is most likely not true, but the client
+ * will expect the device logic to do whatever is necessary to make it
+ * appear so.
+ */
+
+ geo->blocksize = priv->pagesize;
+ geo->erasesize = priv->pagesize;
+ geo->neraseblocks = priv->npages;
+ ret = OK;
+
+ fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
+ geo->blocksize, geo->erasesize, geo->neraseblocks);
+ }
+ }
+ break;
+
+ case MTDIOC_BULKERASE:
+ ret=at24c_eraseall(priv);
+ break;
+
+ case MTDIOC_XIPBASE:
+ default:
+ ret = -ENOTTY; /* Bad command */
+ break;
+ }
+
+ return ret;
+}
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: at24c_initialize
+ *
+ * Description:
+ * Create an initialize MTD device instance. MTD devices are not registered
+ * in the file system, but are created as instances that can be bound to
+ * other functions (such as a block or character driver front end).
+ *
+ ************************************************************************************/
+
+FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev)
+{
+ FAR struct at24c_dev_s *priv;
+ int ret;
+
+ fvdbg("dev: %p\n", dev);
+
+ /* Allocate a state structure (we allocate the structure instead of using
+ * a fixed, static allocation so that we can handle multiple FLASH devices.
+ * The current implementation would handle only one FLASH part per SPI
+ * device (only because of the SPIDEV_FLASH definition) and so would have
+ * to be extended to handle multiple FLASH parts on the same SPI bus.
+ */
+
+ priv = &g_at24c;
+ if (priv)
+ {
+ /* Initialize the allocated structure */
+
+ priv->mtd.erase = at24c_erase;
+ priv->mtd.bread = at24c_bread;
+ priv->mtd.bwrite = at24c_bwrite;
+ priv->mtd.ioctl = at24c_ioctl;
+ priv->dev = dev;
+ }
+ /* Return the implementation-specific state structure as the MTD device */
+ fvdbg("Return %p\n", priv);
+ return (FAR struct mtd_dev_s *)priv;
+}
+
+#endif
diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h
index 95286dee5..4dc76e1ef 100644
--- a/nuttx/include/nuttx/mtd.h
+++ b/nuttx/include/nuttx/mtd.h
@@ -196,6 +196,18 @@ EXTERN FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev);
EXTERN FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *dev);
+/****************************************************************************
+ * Name: at24c_initialize
+ *
+ * Description:
+ * Create an initialize MTD device instance. MTD devices are not registered
+ * in the file system, but are created as instances that can be bound to
+ * other functions (such as a block or character driver front end).
+ *
+ ****************************************************************************/
+
+EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
+
#undef EXTERN
#ifdef __cplusplus
}