diff --git a/ChangeLog b/ChangeLog
index bd84e519fe0c57663803411dbde25f496f12b279..d8fc1d643b0446452584a1a167fa1ebc0db3989f 100644
--- a/ChangeLog
+++ b/ChangeLog
@@ -2007,4 +2007,5 @@
 	* 8/18/2011: The basic port to the FreeScale Kinetics TWR-K60N512 board is
 	  now functional.
 	* confgs/twr-k60n512: Add Kinetics TWR-K60N512 NSH configuration.
-
+	* drivers/analog and include/nuttx/analog: Add ADC driver infrastructure
+	  and TI ADS1255 driver developed and submitted by Li Zhouy (Lzzy)).
diff --git a/drivers/Makefile b/drivers/Makefile
index 2ba6c8f2284bafa56af7731497374834d783f3e4..d1361e3b5e4e4507698a13ab8cafbd54e826e675 100644
--- a/drivers/Makefile
+++ b/drivers/Makefile
@@ -48,6 +48,7 @@ VPATH = .
 # files to the source file list, add its DEPPATH info, and will add
 # the appropriate paths to the VPATH variable
 
+include analog/Make.defs
 include bch/Make.defs
 include input/Make.defs
 include lcd/Make.defs
diff --git a/drivers/analog/Make.defs b/drivers/analog/Make.defs
new file mode 100755
index 0000000000000000000000000000000000000000..4702fc8d89c1c644a0a136ba8f43aa0df9d18974
--- /dev/null
+++ b/drivers/analog/Make.defs
@@ -0,0 +1,76 @@
+############################################################################
+# drivers/analog/Make.defs
+#
+#   Copyright (C) 2011 Gregory Nutt. All rights reserved.
+#   Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+#    notice, this list of conditions and the following disclaimer in
+#    the documentation and/or other materials provided with the
+#    distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+#    used to endorse or promote products derived from this software
+#    without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Don't build anything if there is no support for analog devices
+
+# Check for DAC devices
+
+ifeq ($(CONFIG_DAC),y)
+
+# Include the common ADC character driver
+
+# Include DAC device drivers
+
+endif
+
+# Check for ADC devices
+
+ifeq ($(CONFIG_ADC),y)
+
+# Include the common ADC character driver
+
+CSRCS += adc.c
+
+# Include ADC device drivers
+
+ifeq ($(CONFIG_ADC_ADS125X),y)
+  CSRCS += ads1255.c
+endif
+endif
+
+# Add analog driver build support (the nested if-then-else implements an OR)
+
+ifeq ($(CONFIG_DAC),y)
+  DEPPATH += --dep-path analog
+  VPATH += :analog
+  CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog}
+else
+ifeq ($(CONFIG_ADC),y)
+  DEPPATH += --dep-path analog
+  VPATH += :analog
+  CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/analog}
+endif
+endif
+
diff --git a/drivers/analog/adc.c b/drivers/analog/adc.c
new file mode 100644
index 0000000000000000000000000000000000000000..5505a282d03d42c168958882505f373e21c760a6
--- /dev/null
+++ b/drivers/analog/adc.c
@@ -0,0 +1,405 @@
+/****************************************************************************
+ * drivers/adc/adc.c
+ *
+ *   Copyright (C) 2011 Li Zhuoyi. All rights reserved.
+ *   Author: Li Zhuoyi <lzyy.cn@gmail.com>
+ *   History: 0.1 2011-08-04 initial version
+ *
+ * Derived from drivers/can.c
+ *
+ *   Copyright (C) 2008-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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <string.h>
+#include <semaphore.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/fs.h>
+#include <nuttx/arch.h>
+#include <nuttx/analog/adc.h>
+
+#include <arch/irq.h>
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int     adc_open(FAR struct file *filep);
+static int     adc_close(FAR struct file *filep);
+static ssize_t adc_read(FAR struct file *, FAR char *, size_t);
+static ssize_t adc_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
+static int     adc_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct file_operations adc_fops =
+{
+    adc_open,     /* open */
+    adc_close,    /* close */
+    adc_read,     /* read */
+    adc_write,    /* write */
+    0,            /* seek */
+    adc_ioctl     /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+    , 0           /* poll */
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/************************************************************************************
+ * Name: adc_open
+ *
+ * Description:
+ *   This function is called whenever the ADC device is opened.
+ *
+ ************************************************************************************/
+
+static int adc_open(FAR struct file *filep)
+{
+    FAR struct inode     *inode = filep->f_inode;
+    FAR struct adc_dev_s *dev   = inode->i_private;
+    uint8_t               tmp;
+    int                   ret   = OK;
+
+    /* If the port is the middle of closing, wait until the close is finished */
+
+    if (sem_wait(&dev->cd_closesem) != OK)
+    {
+        ret = -errno;
+    }
+    else
+    {
+        /* Increment the count of references to the device.  If this the first
+         * time that the driver has been opened for this device, then initialize
+         * the device.
+         */
+
+        tmp = dev->cd_ocount + 1;
+        if (tmp == 0)
+        {
+            /* More than 255 opens; uint8_t overflows to zero */
+
+            ret = -EMFILE;
+        }
+        else
+        {
+            /* Check if this is the first time that the driver has been opened. */
+
+            if (tmp == 1)
+            {
+                /* Yes.. perform one time hardware initialization. */
+
+                irqstate_t flags = irqsave();
+                ret = dev->cd_ops->ao_setup(dev);
+                if (ret == OK)
+                {
+                    /* Mark the FIFOs empty */
+
+                    dev->cd_recv.af_head = 0;
+                    dev->cd_recv.af_tail = 0;
+
+                    /* Finally, Enable the CAN RX interrupt */
+
+                    dev->cd_ops->ao_rxint(dev, true);
+
+                    /* Save the new open count on success */
+
+                    dev->cd_ocount = tmp;
+                }
+                irqrestore(flags);
+            }
+        }
+        sem_post(&dev->cd_closesem);
+    }
+    return ret;
+}
+
+/************************************************************************************
+ * Name: adc_close
+ *
+ * Description:
+ *   This routine is called when the ADC device is closed.
+ *   It waits for the last remaining data to be sent.
+ *
+ ************************************************************************************/
+
+static int adc_close(FAR struct file *filep)
+{
+    FAR struct inode     *inode = filep->f_inode;
+    FAR struct adc_dev_s *dev   = inode->i_private;
+    irqstate_t            flags;
+    int                   ret = OK;
+
+    if (sem_wait(&dev->cd_closesem) != OK)
+    {
+        ret = -errno;
+    }
+    else
+    {
+        /* Decrement the references to the driver.  If the reference count will
+         * decrement to 0, then uninitialize the driver.
+         */
+
+        if (dev->cd_ocount > 1)
+        {
+            dev->cd_ocount--;
+            sem_post(&dev->cd_closesem);
+        }
+        else
+        {
+            /* There are no more references to the port */
+
+            dev->cd_ocount = 0;
+
+
+            /* Free the IRQ and disable the ADC device */
+
+            flags = irqsave();       /* Disable interrupts */
+            dev->cd_ops->ao_shutdown(dev);       /* Disable the ADC */
+            irqrestore(flags);
+
+            sem_post(&dev->cd_closesem);
+        }
+    }
+    return ret;
+}
+
+/****************************************************************************
+ * Name: adc_read
+ ****************************************************************************/
+
+static ssize_t adc_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
+{
+    FAR struct inode     *inode = filep->f_inode;
+    FAR struct adc_dev_s *dev   = inode->i_private;
+    size_t                nread;
+    irqstate_t            flags;
+    int                   ret   = 0;
+    int 					msglen;
+
+    if (buflen % 5 ==0 )
+        msglen=5;
+    else if (buflen % 4 ==0 )
+        msglen=4;
+    else if (buflen % 3 ==0 )
+        msglen=3;
+    else if (buflen % 2 ==0 )
+        msglen=2;
+    else if (buflen == 1)
+        msglen=1;
+    else
+        msglen=5;
+
+    if (buflen >= msglen)
+    {
+        /* Interrupts must be disabled while accessing the cd_recv FIFO */
+
+        flags = irqsave();
+        while (dev->cd_recv.af_head == dev->cd_recv.af_tail)
+        {
+            /* The receive FIFO is empty -- was non-blocking mode selected? */
+
+            if (filep->f_oflags & O_NONBLOCK)
+            {
+                ret = -EAGAIN;
+                goto return_with_irqdisabled;
+            }
+
+            /* Wait for a message to be received */
+
+			dev->cd_nrxwaiters++;
+            ret = sem_wait(&dev->cd_recv.af_sem);
+			dev->cd_nrxwaiters--;
+            if (ret < 0)
+            {
+                ret = -errno;
+                goto return_with_irqdisabled;
+            }
+        }
+
+        /* The cd_recv FIFO is not empty.  Copy all buffered data that will fit
+         * in the user buffer.
+         */
+
+        nread = 0;
+        do
+        {
+            FAR struct adc_msg_s *msg = &dev->cd_recv.af_buffer[dev->cd_recv.af_head];
+
+            /* Will the next message in the FIFO fit into the user buffer? */
+
+            if (ret + msglen > buflen)
+            {
+                break;
+            }
+
+            /* Copy the message to the user buffer */
+
+            if (msglen==1)
+            {
+                buffer[nread]=msg->am_data>>24;                //Only one channel,read highest 8bits
+            }
+            else if (msglen==2)
+            {
+                *(int16_t *)&buffer[nread]=msg->am_data>>16;   //Only one channel,read highest 16bits
+            }
+            else if (msglen==3)
+            {
+                buffer[nread]=msg->am_channel;
+                *(int16_t *)&buffer[nread+1]=msg->am_data>>16; //read channel highest 16bits
+            }
+            else if (msglen==4)
+            {
+                *(int32_t *)&buffer[nread]=msg->am_data;       //read channel highest 24bits
+                buffer[nread]=msg->am_channel;
+            }
+            else
+            {
+                *(int32_t *)&buffer[nread+1]=msg->am_data;     //read all
+                buffer[nread]=msg->am_channel;
+            }
+            nread += msglen;
+
+            /* Increment the head of the circular message buffer */
+
+            if (++dev->cd_recv.af_head >= CONFIG_ADC_FIFOSIZE)
+            {
+                dev->cd_recv.af_head = 0;
+            }
+        }
+        while (dev->cd_recv.af_head != dev->cd_recv.af_tail);
+
+        /* All on the messages have bee transferred.  Return the number of bytes
+         * that were read.
+         */
+
+        ret = nread;
+
+return_with_irqdisabled:
+        irqrestore(flags);
+    }
+    return ret;
+}
+
+/************************************************************************************
+ * Name: adc_write
+ ************************************************************************************/
+
+static ssize_t adc_write(FAR struct file *filep, FAR const char *buffer, size_t buflen)
+{
+    return 0;
+}
+
+/************************************************************************************
+ * Name: adc_ioctl
+ ************************************************************************************/
+
+static int adc_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+    FAR struct inode     *inode = filep->f_inode;
+    FAR struct adc_dev_s *dev   = inode->i_private;
+    int               ret   = OK;
+
+    ret = dev->cd_ops->ao_ioctl(dev, cmd, arg);
+    return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data)
+{
+    FAR struct adc_fifo_s *fifo = &dev->cd_recv;
+    int                    nexttail;
+    int                    err = -ENOMEM;
+
+    /* Check if adding this new message would over-run the drivers ability to enqueue
+     * read data.
+     */
+
+    nexttail = fifo->af_tail + 1;
+    if (nexttail >= CONFIG_ADC_FIFOSIZE)
+    {
+        nexttail = 0;
+    }
+
+    /* Refuse the new data if the FIFO is full */
+
+    if (nexttail != fifo->af_head)
+    {
+        /* Add the new, decoded CAN message at the tail of the FIFO */
+
+        fifo->af_buffer[fifo->af_tail].am_channel = ch;
+        fifo->af_buffer[fifo->af_tail].am_data=data;
+
+        /* Increment the tail of the circular buffer */
+
+        fifo->af_tail = nexttail;
+
+		if(	dev->cd_nrxwaiters>0)
+			sem_post(&fifo->af_sem);
+        err = OK;
+    }
+    return err;
+}
+
+int adc_register(FAR const char *path, FAR struct adc_dev_s *dev)
+{
+    /* Initialize the ADC device structure */
+
+    dev->cd_ocount = 0;
+
+    sem_init(&dev->cd_recv.af_sem, 0, 0);
+    sem_init(&dev->cd_closesem, 0, 1);
+
+    dev->cd_ops->ao_reset(dev);
+
+    return register_driver(path, &adc_fops, 0444, dev);
+}
+
diff --git a/drivers/analog/ads1255.c b/drivers/analog/ads1255.c
new file mode 100644
index 0000000000000000000000000000000000000000..adc053a9353893508701a941fdd202bf6b116646
--- /dev/null
+++ b/drivers/analog/ads1255.c
@@ -0,0 +1,334 @@
+/************************************************************************************
+ * arch/drivers/adc/ads1255.c
+ *
+ *   Copyright (C) 2011 Li Zhuoyi. All rights reserved.
+ *   Author: Li Zhuoyi <lzyy.cn@gmail.com>
+ *   History: 0.1 2011-08-05 initial version
+ *
+ * This file is a part of NuttX:
+ *
+ *   Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/analog/adc.h>
+
+#if defined(CONFIG_ADC_ADS1255)
+
+#define ADS125X_BUFON   0x02
+#define ADS125X_BUFOFF  0x00
+
+#define ADS125X_PGA1    0x00
+#define ADS125X_PGA2    0x01
+#define ADS125X_PGA4    0x02
+#define ADS125X_PGA8    0x03
+#define ADS125X_PGA16   0x04
+#define ADS125X_PGA32   0x05
+#define ADS125X_PGA64   0x06
+
+#define ADS125X_RDATA     0x01    //Read Data
+#define ADS125X_RDATAC    0x03    //Read Data Continuously
+#define ADS125X_SDATAC    0x0F    //Stop Read Data Continuously
+#define ADS125X_RREG      0x10    //Read from REG
+#define ADS125X_WREG      0x50    //Write to REG
+#define ADS125X_SELFCAL   0xF0    //Offset and Gain Self-Calibration
+#define ADS125X_SELFOCAL  0xF1    //Offset Self-Calibration
+#define ADS125X_SELFGCAL  0xF2    //Gain Self-Calibration
+#define ADS125X_SYSOCAL   0xF3    //System Offset Calibration
+#define ADS125X_SYSGCAL   0xF4    //System Gain Calibration
+#define ADS125X_SYNC      0xFC    //Synchronize the A/D Conversion
+#define ADS125X_STANDBY   0xFD    //Begin Standby Mode
+#define ADS125X_RESET     0xFE    //Reset to Power-Up Values
+#define ADS125X_WAKEUP    0xFF    //Completes SYNC and Exits Standby Mode
+
+#ifndef CONFIG_ADS1255_FREQUENCY
+#define CONFIG_ADS1255_FREQUENCY  1000000
+#endif
+#ifndef CONFIG_ADS1255_MUX
+#define CONFIG_ADS1255_MUX      0x01
+#endif
+#ifndef CONFIG_ADS1255_CHMODE
+#define CONFIG_ADS1255_CHMODE   0x00
+#endif
+#ifndef CONFIG_ADS1255_BUFON
+#define CONFIG_ADS1255_BUFON    1
+#endif
+#ifndef CONFIG_ADS1255_PGA
+#define CONFIG_ADS1255_PGA      ADS125X_PGA2
+#endif
+#ifndef CONFIG_ADS1255_SPS
+#define CONFIG_ADS1255_SPS      50
+#endif
+
+/****************************************************************************
+ * cd_private Types
+ ****************************************************************************/
+
+struct up_dev_s
+{
+    uint8_t channel;
+    uint8_t sps;
+    uint8_t pga;
+    uint8_t buf;
+    const uint8_t *mux;
+    int irq;
+    int devno;
+    FAR struct spi_dev_s  *spi;      /* Cached SPI device reference */
+};
+
+/****************************************************************************
+ * cd_private Function Prototypes
+ ****************************************************************************/
+
+/* ADC methods */
+
+static void adc_reset(FAR struct adc_dev_s *dev);
+static int  adc_setup(FAR struct adc_dev_s *dev);
+static void adc_shutdown(FAR struct adc_dev_s *dev);
+static void adc_rxint(FAR struct adc_dev_s *dev, bool enable);
+static int  adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg);
+static int  adc_interrupt(int irq, void *context);
+
+/****************************************************************************
+ * cd_private Data
+ ****************************************************************************/
+
+static const struct adc_ops_s g_adcops =
+{
+    adc_reset,     /* ao_reset */
+    adc_setup,     /* ao_setup */
+    adc_shutdown,  /* ao_shutdown */
+    adc_rxint,     /* ao_rxint */
+    adc_ioctl      /* ao_read */
+};
+
+static struct up_dev_s g_adcpriv =
+{
+    .mux  = (const uint8_t [])
+    {
+        CONFIG_ADS1255_MUX,0
+    },
+    .sps  = CONFIG_ADS1255_SPS,
+    .channel = 0,
+    .irq  = CONFIG_ADS1255_IRQ,
+};
+
+static struct adc_dev_s g_adcdev =
+{
+    .cd_ops = &g_adcops,
+    .cd_priv= &g_adcpriv,
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static uint8_t getspsreg(uint16_t sps)
+{
+    static const unsigned short sps_tab[]=
+    {
+        3,7,12,20,27,40,55,80,300,750,1500,3000,5000,10000,20000,65535,
+    };
+    static const unsigned char sps_reg[]=
+    {
+        0x03,0x13,0x23,0x33,0x43,0x53,0x63,0x72,0x82,0x92,0xa1,0xb0,0xc0,0xd0,0xe0,0xf0,
+    };
+    int i;
+    for (i=0; i<16; i++)
+    {
+        if (sps<sps_tab[i])
+            break;
+    }
+    return sps_reg[i];
+}
+
+/****************************************************************************
+ * cd_private Functions
+ ****************************************************************************/
+/* Reset the ADC device.  Called early to initialize the hardware. This
+* is called, before ao_setup() and on error conditions.
+*/
+
+static void adc_reset(FAR struct adc_dev_s *dev)
+{
+    FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
+    FAR struct spi_dev_s *spi = priv->spi;
+
+    SPI_SETMODE(spi, SPIDEV_MODE1);
+    SPI_SETBITS(spi, 8);
+    SPI_SETFREQUENCY(spi, CONFIG_ADS1255_FREQUENCY);
+    usleep(1000);
+    SPI_SELECT(spi, priv->devno, true);
+    SPI_SEND(spi,ADS125X_WREG+0x03);    //WRITE SPS REG
+    SPI_SEND(spi,0x00);                 //count=1
+    SPI_SEND(spi,0x63);
+    SPI_SELECT(spi, priv->devno, false);
+}
+
+/* Configure the ADC. This method is called the first time that the ADC
+* device is opened.  This will occur when the port is first opened.
+* This setup includes configuring and attaching ADC interrupts.  Interrupts
+* are all disabled upon return.
+*/
+
+static int  adc_setup(FAR struct adc_dev_s *dev)
+{
+    FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
+    FAR struct spi_dev_s *spi = priv->spi;
+    int ret = irq_attach(priv->irq, adc_interrupt);
+    if (ret == OK)
+    {
+        SPI_SELECT(spi, priv->devno, true);
+        SPI_SEND(spi,ADS125X_WREG);         //WRITE REG from 0
+        SPI_SEND(spi,0x03);                 //count=4+1
+        if (priv->buf)
+            SPI_SEND(spi,ADS125X_BUFON);    //REG0 STATUS BUFFER ON
+        else
+            SPI_SEND(spi,ADS125X_BUFOFF);
+        SPI_SEND(spi,priv->mux[0]);
+        SPI_SEND(spi,priv->pga);            //REG2 ADCON PGA=2
+        SPI_SEND(spi,getspsreg(priv->sps));
+        usleep(1000);
+        SPI_SEND(spi,ADS125X_SELFCAL);
+        SPI_SELECT(spi, priv->devno, false);
+        up_enable_irq(priv->irq);
+    }
+    return ret;
+}
+
+/* Disable the ADC.  This method is called when the ADC device is closed.
+* This method reverses the operation the setup method.
+*/
+
+static void adc_shutdown(FAR struct adc_dev_s *dev)
+{
+    FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
+    up_disable_irq(priv->irq);
+    irq_detach(priv->irq);
+}
+
+/* Call to enable or disable RX interrupts */
+
+static void adc_rxint(FAR struct adc_dev_s *dev, bool enable)
+{
+    FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
+    if (enable)
+        up_enable_irq(priv->irq);
+    else
+        up_disable_irq(priv->irq);
+}
+
+/* All ioctl calls will be routed through this method */
+
+static int  adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg)
+{
+    dbg("Fix me:Not Implemented\n");
+    return 0;
+}
+
+static int adc_interrupt(int irq, void *context)
+{
+    uint32_t regval;
+    FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.cd_priv;
+    FAR struct spi_dev_s *spi = priv->spi;
+    unsigned char buf[4];
+    unsigned char ch;
+
+    SPI_SELECT(spi, priv->devno, true);
+    SPI_SEND(spi,ADS125X_RDATA);
+    up_udelay(10);
+    buf[3]=SPI_SEND(spi,0xff);
+    buf[2]=SPI_SEND(spi,0xff);
+    buf[1]=SPI_SEND(spi,0xff);
+    buf[0]=0;
+
+    priv->channel++;
+    ch = priv->mux[priv->channel];
+    if ( ch == 0 )
+    {
+        priv->channel=0;
+        ch = priv->mux[0];
+    }
+
+    SPI_SEND(spi,ADS125X_WREG+0x01);
+    SPI_SEND(spi,0x00);
+    SPI_SEND(spi,ch);
+    SPI_SEND(spi,ADS125X_SYNC);
+    up_udelay(2);
+    SPI_SEND(spi,ADS125X_WAKEUP);
+    SPI_SELECT(spi, priv->devno, false);
+
+    adc_receive(&g_adcdev,priv->channel,*(int32_t *)buf);
+    return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ads1255initialize
+ *
+ * Description:
+ *   Initialize the selected adc port
+ *
+ * Input Parameter:
+ *   Port number (for hardware that has mutiple adc interfaces)
+ *
+ * Returned Value:
+ *   Valid can device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi, unsigned int devno)
+{
+    FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.cd_priv;
+
+    /* Driver state data */
+
+    priv->spi      = spi;
+    priv->devno    = devno;
+    return &g_adcdev;
+}
+#endif
+
diff --git a/include/nuttx/analog/adc.h b/include/nuttx/analog/adc.h
new file mode 100755
index 0000000000000000000000000000000000000000..c820e762d3716a40b6df06dfe26934c57905b3a6
--- /dev/null
+++ b/include/nuttx/analog/adc.h
@@ -0,0 +1,188 @@
+/************************************************************************************
+ * include/nuttx/analog/adc.h
+ *
+ *   Copyright (C) 2011 Li Zhuoyi. All rights reserved.
+ *   Author: Li Zhuoyi <lzyy.cn@gmail.com>
+ *   History: 0.1 2011-08-04 initial version
+ *
+ * Derived from include/nuttx/can.h
+ *   Copyright (C) 2008, 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 __INCLUDE_NUTTX_ANALOG_ADC_H
+#define __INCLUDE_NUTTX_ANALOG_ADC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <nuttx/fs.h>
+#include <nuttx/spi.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Default configuration settings that may be overridden in the board configuration.
+ * file.  The configured size is limited to 255 to fit into a uint8_t.
+ */
+
+#if !defined(CONFIG_ADC_FIFOSIZE)
+#  define CONFIG_ADC_FIFOSIZE 8
+#elif CONFIG_ADC_FIFOSIZE > 255
+#  undef  CONFIG_ADC_FIFOSIZE
+#  define CONFIG_ADC_FIFOSIZE 255
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+struct adc_msg_s
+{
+  uint8_t      am_channel;               /* The 8-bit ADC Channel */
+  int32_t      am_data;                  /* ADC convert result (4 bytes) */
+}__attribute__((__packed__));
+
+struct adc_fifo_s
+{
+  sem_t        af_sem;                   /* Counting semaphore */
+  uint8_t      af_head;                  /* Index to the head [IN] index in the circular buffer */
+  uint8_t      af_tail;                  /* Index to the tail [OUT] index in the circular buffer */
+                                         /* Circular buffer of CAN messages */
+  struct adc_msg_s af_buffer[CONFIG_ADC_FIFOSIZE];
+};
+
+/* This structure defines all of the operations providd by the architecture specific
+ * logic.  All fields must be provided with non-NULL function pointers by the
+ * caller of can_register().
+ */
+
+struct adc_dev_s;
+struct adc_ops_s
+{
+  /* Reset the ADC device.  Called early to initialize the hardware. This
+   * is called, before ao_setup() and on error conditions.
+   */
+
+  CODE void (*ao_reset)(FAR struct adc_dev_s *dev);
+
+  /* Configure the ADC. This method is called the first time that the ADC
+   * device is opened.  This will occur when the port is first opened. 
+   * This setup includes configuring and attaching ADC interrupts.  Interrupts
+   * are all disabled upon return.
+   */
+
+  CODE int (*ao_setup)(FAR struct adc_dev_s *dev);
+
+  /* Disable the ADC.  This method is called when the ADC device is closed.
+   * This method reverses the operation the setup method.
+   */
+
+  CODE void (*ao_shutdown)(FAR struct adc_dev_s *dev);
+
+  /* Call to enable or disable RX interrupts */
+
+  CODE void (*ao_rxint)(FAR struct adc_dev_s *dev, bool enable);
+ 
+  CODE int (*ao_read)(FAR struct adc_dev_s *dev, char *buffer,int len);
+
+  /* All ioctl calls will be routed through this method */
+
+  CODE int (*ao_ioctl)(FAR struct adc_dev_s *dev, int cmd, unsigned long arg);
+
+};
+
+/* This is the device structure used by the driver.  The caller of
+ * can_register() must allocate and initialize this structure.  The
+ * calling logic need only set all fields to zero except:
+ *
+ *   The elements of 'cd_ops', and 'cd_priv'
+ *
+ * The common logic will initialize all semaphores.
+ */
+
+struct adc_dev_s
+{
+  uint8_t              cd_ocount;        /* The number of times the device has been opened */
+  uint8_t              cd_nrxwaiters;    /* Number of threads waiting to enqueue a message */
+  sem_t                cd_closesem;      /* Locks out new opens while close is in progress */
+  sem_t                cd_recvsem;       /* Used to wakeup user waiting for space in cd_recv.buffer */
+  struct adc_fifo_s    cd_recv;          /* Describes receive FIFO */
+  const struct adc_ops_s *cd_ops;        /* Arch-specific operations */
+  void                *cd_priv;          /* Used by the arch-specific logic */
+};
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/************************************************************************************
+ * Name: adc_register
+ *
+ * Description:
+ *   Register a adc driver.
+ *
+ ************************************************************************************/
+
+int adc_register(FAR const char *path, FAR struct adc_dev_s *dev);
+
+int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data);
+
+/************************************************************************************
+ * Name: up_ads1255initialize
+ *
+ * Description:
+ *   Initialize the TI ADS 125X lower half driver
+ *
+ ************************************************************************************/
+
+FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi, unsigned int devno);
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_ANALOG_ADC_H */