diff -Naur linux-2.6.25/drivers/i2c/busses/i2c-ep93xx.c linux-2.6.25.ep93xx/drivers/i2c/busses/i2c-ep93xx.c
--- linux-2.6.25/drivers/i2c/busses/i2c-ep93xx.c	1969-12-31 18:00:00.000000000 -0600
+++ linux-2.6.25.ep93xx/drivers/i2c/busses/i2c-ep93xx.c	2008-08-18 14:05:42.000000000 -0500
@@ -0,0 +1,194 @@
+/* ------------------------------------------------------------------------ *
+ * i2c-ep933xx.c I2C bus glue for Cirrus EP93xx                             *
+ * ------------------------------------------------------------------------ *
+
+   Copyright (C) 2004 Michael Burian
+   
+   Based on i2c-parport-light.c
+   Copyright (C) 2003-2004 Jean Delvare <khali@linux-fr.org>
+  
+   This program is free software; you can redistribute it and/or modify
+   it under the terms of the GNU General Public License as published by
+   the Free Software Foundation; either version 2 of the License, or
+   (at your option) any later version.
+
+   This program is distributed in the hope that it will be useful,
+   but WITHOUT ANY WARRANTY; without even the implied warranty of
+   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+   GNU General Public License for more details.
+
+   You should have received a copy of the GNU General Public License
+   along with this program; if not, write to the Free Software
+   Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
+ * ------------------------------------------------------------------------ */
+
+
+//#include <linux/config.h>
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/init.h>
+#include <linux/ioport.h>
+#include <linux/delay.h>
+#include <linux/i2c.h>
+#include <linux/i2c-algo-bit.h>
+#include <asm/io.h>
+#include <asm/arch/hardware.h>
+
+//1/(2*clockfrequency)
+#define EE_DELAY_USEC       50
+#define GPIOG_EECLK 1
+#define GPIOG_EEDAT 2
+
+/* ----- I2C algorithm call-back functions and structures ----------------- */
+
+// TODO: optimize
+static void ep93xx_setscl(void *data, int state)
+{
+	unsigned int uiPGDR, uiPGDDR;
+
+	uiPGDR = inl(GPIO_PGDR);
+	uiPGDDR = inl(GPIO_PGDDR);
+
+	/* Configure the clock line as output. */
+	uiPGDDR |= GPIOG_EECLK;
+	outl(uiPGDDR, GPIO_PGDDR);
+
+	/* Set clock line to state */
+	if(state)
+		uiPGDR |= GPIOG_EECLK;
+	else
+		uiPGDR &= ~GPIOG_EECLK;
+	
+	outl(uiPGDR, GPIO_PGDR);
+}
+
+static void ep93xx_setsda(void *data, int state)
+{
+	unsigned int uiPGDR, uiPGDDR;
+	
+	uiPGDR = inl(GPIO_PGDR);
+	uiPGDDR = inl(GPIO_PGDDR);
+
+	/* Configure the data line as output. */
+	uiPGDDR |= GPIOG_EEDAT;
+	outl(uiPGDDR, GPIO_PGDDR);
+
+	/* Set data line to state */
+	if(state)
+		uiPGDR |= GPIOG_EEDAT;
+	else
+		uiPGDR &= ~GPIOG_EEDAT;
+	
+	outl(uiPGDR, GPIO_PGDR);
+}
+
+static int ep93xx_getscl(void *data)
+{
+	unsigned int uiPGDR, uiPGDDR;
+	
+	uiPGDR = inl(GPIO_PGDR);
+	uiPGDDR = inl(GPIO_PGDDR);
+
+	/* Configure the clock line as input */
+	uiPGDDR &= ~GPIOG_EECLK;
+	outl(uiPGDDR, GPIO_PGDDR);
+	
+	/* Return state of the clock line */
+	return (inl(GPIO_PGDR) & GPIOG_EECLK) ? 1 : 0;
+}
+
+static int ep93xx_getsda(void *data)
+{
+	unsigned int uiPGDR, uiPGDDR;
+	uiPGDR = inl(GPIO_PGDR);
+	uiPGDDR = inl(GPIO_PGDDR);
+
+	/* Configure the data line as input */
+	uiPGDDR &= ~GPIOG_EEDAT;
+	outl(uiPGDDR, GPIO_PGDDR);
+
+	/* Return state of the data line */
+	return (inl(GPIO_PGDR) & GPIOG_EEDAT) ? 1 : 0;
+}
+
+/* ------------------------------------------------------------------------
+ * Encapsulate the above functions in the correct operations structure.
+ * This is only done when more than one hardware adapter is supported.
+ */
+
+/* last line (us, ms, timeout)
+ * us dominates the bit rate: 10us  means: 100Kbit/sec(25 means 40kbps)
+ *                            10ms  not known
+ *                            100ms timeout
+ */
+static struct i2c_algo_bit_data ep93xx_data = {
+	.setsda		= ep93xx_setsda,
+	.setscl		= ep93xx_setscl,
+	.getsda		= ep93xx_getsda,
+	.getscl		= ep93xx_getscl,
+	.udelay		= 10,
+	//.mdelay		= 10,
+	.timeout	= HZ,
+};
+
+/* ----- I2c structure ---------------------------------------------------- */
+static struct i2c_adapter ep93xx_adapter = {
+	.owner		= THIS_MODULE,
+	.class		= I2C_CLASS_HWMON,
+	.id		= I2C_HW_B_LP,
+	.algo_data	= &ep93xx_data,
+	.name		= "EP93XX I2C bit-bang interface",
+};
+
+/* ----- Module loading, unloading and information ------------------------ */
+
+static int __init i2c_ep93xx_init(void)
+{
+	unsigned long uiPGDR, uiPGDDR;
+	
+	/* Read the current value of the GPIO data and data direction registers. */
+	uiPGDR = inl(GPIO_PGDR);
+	uiPGDDR = inl(GPIO_PGDDR);
+	
+	/* If the GPIO pins have not been configured since reset, the data 
+	 * and clock lines will be set as inputs and with data value of 0.
+	 * External pullup resisters are pulling them high.
+	 * Set them both high before configuring them as outputs. */
+	uiPGDR |= (GPIOG_EEDAT | GPIOG_EECLK);
+	outl(uiPGDR, GPIO_PGDR);
+
+	/* Delay to meet the EE Interface timing specification. */
+	udelay(EE_DELAY_USEC);
+
+	
+	/* Configure the EE data and clock lines as outputs. */
+	uiPGDDR |= (GPIOG_EEDAT | GPIOG_EECLK);
+	outl(uiPGDDR, GPIO_PGDDR);
+
+	/* Delay to meet the EE Interface timing specification. */
+	udelay(EE_DELAY_USEC);
+
+	/* Reset hardware to a sane state (SCL and SDA high) */
+	ep93xx_setsda(NULL, 1);
+	ep93xx_setscl(NULL, 1);
+
+	if (i2c_bit_add_bus(&ep93xx_adapter) > 0) {
+		printk(KERN_ERR "i2c-ep93xx: Unable to register with I2C\n");
+		return -ENODEV;
+	}
+	
+	return 0;
+}
+
+static void __exit i2c_ep93xx_exit(void)
+{
+	//i2c_bit_del_bus(&ep93xx_adapter);
+	i2c_del_adapter(&ep93xx_adapter);
+}
+
+MODULE_AUTHOR("Michael Burian");
+MODULE_DESCRIPTION("I2C bus glue for Cirrus EP93xx processors");
+MODULE_LICENSE("GPL");
+
+module_init(i2c_ep93xx_init);
+module_exit(i2c_ep93xx_exit);
diff -Naur linux-2.6.25/drivers/i2c/busses/Kconfig linux-2.6.25.ep93xx/drivers/i2c/busses/Kconfig
--- linux-2.6.25/drivers/i2c/busses/Kconfig	2008-04-16 21:49:44.000000000 -0500
+++ linux-2.6.25.ep93xx/drivers/i2c/busses/Kconfig	2008-08-18 14:05:42.000000000 -0500
@@ -4,6 +4,10 @@
 
 menu "I2C Hardware Bus support"
 
+config I2C_EP93XX
+	tristate "EP93XX I2C"
+	depends on I2C && ARCH_EP93XX
+
 config I2C_ALI1535
 	tristate "ALI 1535"
 	depends on PCI
diff -Naur linux-2.6.25/drivers/i2c/busses/Makefile linux-2.6.25.ep93xx/drivers/i2c/busses/Makefile
--- linux-2.6.25/drivers/i2c/busses/Makefile	2008-04-16 21:49:44.000000000 -0500
+++ linux-2.6.25.ep93xx/drivers/i2c/busses/Makefile	2008-08-18 14:05:42.000000000 -0500
@@ -52,6 +52,7 @@
 obj-$(CONFIG_I2C_VOODOO3)	+= i2c-voodoo3.o
 obj-$(CONFIG_SCx200_ACB)	+= scx200_acb.o
 obj-$(CONFIG_SCx200_I2C)	+= scx200_i2c.o
+obj-$(CONFIG_I2C_EP93XX)        += i2c-ep93xx.o
 
 ifeq ($(CONFIG_I2C_DEBUG_BUS),y)
 EXTRA_CFLAGS += -DDEBUG
diff -Naur linux-2.6.25/drivers/input/touchscreen/ep93xx_ts.c linux-2.6.25.ep93xx/drivers/input/touchscreen/ep93xx_ts.c
--- linux-2.6.25/drivers/input/touchscreen/ep93xx_ts.c	1969-12-31 18:00:00.000000000 -0600
+++ linux-2.6.25.ep93xx/drivers/input/touchscreen/ep93xx_ts.c	2008-08-18 14:05:42.000000000 -0500
@@ -0,0 +1,1119 @@
+/*
+ *  linux/drivers/char/ep93xx_ts.c
+ *
+ *  Copyright (C) 2003-2004 Cirrus Corp.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ */
+ 
+#include <linux/module.h>
+#include <linux/types.h>
+#include <linux/delay.h>
+#include <linux/wait.h>
+#include <linux/fs.h>
+#include <linux/sched.h>
+#include <linux/poll.h>
+#include <linux/miscdevice.h>
+#include <linux/init.h>
+#include <linux/compiler.h>
+#include <linux/timer.h>
+#include <linux/interrupt.h>
+#include <linux/syscalls.h>
+#include <linux/input.h>
+#include <asm/irq.h>
+#include <asm/hardware.h>
+#include <asm/io.h>
+
+//
+// To customize for a new touchscreen, there are various macros that
+// have to be set.  If you allow UART_HACK_DEBUG to be defined, you
+// will get real time ts data scrolling up your serial terminal
+// screen that will help you empirically determine good values for these.  
+//
+
+//
+// These are used as trigger levels to know when we have pen up/down
+//
+// The rules:
+// 1.  TS_HEAVY_INV_PRESSURE < TS_LIGHT_INV_PRESSURE because these
+//    are Inverse pressure.  
+// 2.  Any touch lighter than TS_LIGHT_INV_PRESSURE is a pen up.
+// 3.  Any touch heavier than TS_HEAVY_INV_PRESSURE is a pen down.
+//
+#define   TS_HEAVY_INV_PRESSURE 0xFE0 //C00
+#define   TS_LIGHT_INV_PRESSURE 0xFFF //e00
+
+//
+// If the x, y, or inverse pressure changes more than these values
+// between two succeeding points, the point is not reported.
+//
+#define   TS_MAX_VALID_XY_CHANGE 0x300
+#define   TS_MAX_VALID_PRESSURE_CHANGE  0x100
+
+//
+// This is the minimum Z1 Value that is valid.
+//
+#define     MIN_Z1_VALUE                    0x50
+
+//
+// Settling delay for taking each ADC measurement.  Increase this
+// if ts is jittery.
+//
+#define EP93XX_TS_ADC_DELAY_USEC 2000
+
+//
+// Delay between TS points.
+//
+#define EP93XX_TS_PER_POINT_DELAY_USEC 10000
+
+//-----------------------------------------------------------------------------
+// Debug messaging thru the UARTs
+//-----------------------------------------------------------------------------
+/*
+ *  Hello there!  Are you trying to get this driver to work with a new
+ *  touschscreen?  Turn this on and you will get useful info coming
+ *  out of your serial port.
+ */
+//#define PRINT_CALIBRATION_FACTORS //NZG mod
+
+
+#ifdef PRINT_CALIBRATION_FACTORS
+#define UART_HACK_DEBUG 1
+int iMaxX=0, iMaxY=0, iMinX = 0xfff, iMinY = 0xfff;
+#endif
+
+/*
+ * For debugging, let's spew messages out serial port 1 or 3 at 57,600 baud.
+ */
+//#define UART_HACK_DEBUG 1 
+#if 0
+#ifdef UART_HACK_DEBUG
+static char szBuf[256];
+void UARTWriteString(char * msg);
+#define DPRINTK( x... )   \
+    sprintf( szBuf, ##x ); \
+    UARTWriteString( szBuf );
+#else
+static char szBuf[256];
+#define DPRINTK( x... )  \
+    sprintf( szBuf, ##x ); \
+    printk( szBuf );
+#endif
+#endif // 0
+
+#ifdef UART_HACK_DEBUG //NZG mod, use printk instead
+#define DPRINTK(fmt, args...) printk(fmt, ## args)
+#else
+#define DPRINTK( x... ) 
+#endif 
+
+//-----------------------------------------------------------------------------
+// A few more macros...
+//-----------------------------------------------------------------------------
+#define TSSETUP_DEFAULT  ( TSSETUP_NSMP_32 | TSSETUP_DEV_64 |  \
+                           ((128<<TSSETUP_SDLY_SHIFT) & TSSETUP_SDLY_MASK) | \
+                           ((128<<TSSETUP_DLY_SHIFT)  & TSSETUP_DLY_MASK) )
+
+#define TSSETUP2_DEFAULT (TSSETUP2_NSIGND)
+
+//
+// For now, we use one of the minor numbers from the local/experimental
+// range.
+//
+#define EP93XX_TS_MINOR 240
+
+//-----------------------------------------------------------------------------
+// Static Declarations
+//-----------------------------------------------------------------------------
+static unsigned int   guiLastX, guiLastY;
+static unsigned int   guiLastInvPressure;
+
+struct TouchScreenSample
+{
+    int     currentX;
+    int     currentY;
+    int     currentButton;
+    int     currentPressure;
+    struct timeval currentTime;
+};
+
+//
+// This must match the structure in tslib.
+//
+struct ts_sample {
+    int     x;
+    int     y;
+    unsigned int    pressure;
+    struct timeval  tv;
+};
+
+
+static struct TouchScreenSample gSample;
+
+// static int currentX, currentY, currentButton;
+// static int gPressure;
+// static struct timeval  gtime;
+
+static int bFreshTouchData;
+static int bCurrentPenDown;
+
+
+
+static DECLARE_WAIT_QUEUE_HEAD(queue);
+static DECLARE_MUTEX(open_sem);
+static spinlock_t event_buffer_lock = SPIN_LOCK_UNLOCKED;
+static struct fasync_struct *ep93xx_fasync;
+
+//-----------------------------------------------------------------------------
+// Typedef Declarations
+//-----------------------------------------------------------------------------
+typedef enum {
+    TS_MODE_UN_INITIALIZED,
+    TS_MODE_HARDWARE_SCAN,
+    TS_MODE_SOFT_SCAN
+} ts_mode_t;
+
+static ts_mode_t      gScanningMode;
+
+typedef enum{
+    TS_STATE_STOPPED = 0,
+    TS_STATE_Z1,
+    TS_STATE_Z2,
+    TS_STATE_Y,
+    TS_STATE_X,
+    TS_STATE_DONE
+} ts_states_t;
+
+typedef struct 
+{
+    unsigned int   uiX;
+    unsigned int   uiY;
+    unsigned int   uiZ1;
+    unsigned int   uiZ2;
+    ts_states_t    state;
+} ts_struct_t;
+
+static ts_struct_t sTouch;
+
+/*
+ * From the spec, here's how to set up the touch screen's switch registers.
+ */
+typedef struct 
+{
+    unsigned int uiDetect;
+    unsigned int uiDischarge;
+    unsigned int uiXSample;
+    unsigned int uiYSample;
+    unsigned int uiSwitchZ1;
+    unsigned int uiSwitchZ2;
+}SwitchStructType;
+
+//
+// Here's the switch settings for a 4-wire touchscreen.  See the spec
+// for how to handle a 4, 7, or 8-wire.
+//
+const static SwitchStructType sSwitchSettings = 
+/*     s28en=0
+ *   TSDetect    TSDischarge  TSXSample  TSYSample    SwitchZ1   SwitchZ2
+ */
+    {0x00403604, 0x0007fe04, 0x00081604, 0x00104601, 0x00101601, 0x00101608};   
+
+
+//-----------------------------------------------------------------------------
+// Function Declarations
+//-----------------------------------------------------------------------------
+static void ep93xx_ts_set_direct( unsigned int uiADCSwitch );
+static irqreturn_t ep93xx_ts_isr(int irq, void *dev_id, struct pt_regs *regs);
+static irqreturn_t ep93xx_timer2_isr(int irq, void *dev_id, struct pt_regs *regs);
+static void ee93xx_ts_evt_add( int button, int dX, int dY, int Pressure );
+static ssize_t ep93xx_ts_read(struct file *filp, char *buf, 
+        size_t count, loff_t *l);
+static unsigned int ep93xx_ts_poll(struct file *filp, poll_table *wait);
+static int ep93xx_ts_open(struct inode *inode, struct file *filp);
+static int ep93xx_ts_fasync(int fd, struct file *filp, int on);
+static int ep93xx_ts_release(struct inode *inode, struct file *filp);
+static ssize_t ep93xx_ts_write(struct file *file, const char *buffer, 
+                size_t count, loff_t *ppos);
+static void ep93xx_ts_setup(void);
+static void ep93xx_ts_shutdown(void);
+int __init ep93xx_ts_init(void);
+void __exit ep93xx_ts_exit(void);
+static unsigned int CalculateInvPressure( void );
+static unsigned int ADCGetData( unsigned int uiSamples, unsigned int uiMaxDiff);
+static void TS_Soft_Scan_Mode(void);
+static void TS_Hardware_Scan_Mode(void);
+static void ProcessPointData(void);
+static void Set_Timer2_uSec( unsigned int Delay_mSec );
+static void Stop_Timer2(void);
+
+
+
+//-----------------------------------------------------------------------------
+//  Debug stuff...
+//-----------------------------------------------------------------------------
+
+#if 0 //NZG mod
+//#ifdef UART_HACK_DEBUG
+
+// This "array" is a cheap-n-easy way of getting access to the UART registers.
+static unsigned int * const pDebugUART=(unsigned int *)IO_ADDRESS(UART1_BASE);
+//static unsigned int * const pDebugUART=(unsigned int *)IO_ADDRESS(UART3_BASE);
+static int bUartInitialized = 0; 
+
+void SendChar(char value)
+{
+    // wait for Tx fifo full flag to clear.
+    while (pDebugUART[0x18>>2] & 0x20);
+
+    // send a char to the uart               
+    pDebugUART[0] = value;
+}
+
+void UARTWriteString(char * msg) 
+{
+    int index = 0;
+    unsigned int uiTemp;
+
+    //if((pDebugUART[0x14>>2] & 0x1) == 0)
+    if( bUartInitialized == 0 )
+    {
+        uiTemp = inl(SYSCON_DEVCFG);
+        uiTemp |= SYSCON_DEVCFG_U1EN;
+        //uiTemp |= SYSCON_DEVCFG_U3EN;
+        SysconSetLocked(SYSCON_DEVCFG, uiTemp);  
+        pDebugUART[0x10>>2] = 0xf;
+        pDebugUART[0xc>>2] = 0;
+        pDebugUART[0x8>>2] = 0x70;
+        pDebugUART[0x14>>2] = 0x1;
+        bUartInitialized = 1;
+    }
+    while (msg[index] != 0)
+    {
+        if (msg[index] == '\n')
+        {
+            SendChar('\r');
+            SendChar('\n');
+        }
+        else 
+        {
+            SendChar(msg[index]);
+        }
+        index++;
+    }
+}
+#endif // UART_HACK_DEBUG
+
+/*
+ *  ep93xx_ts_isr
+ */
+static irqreturn_t ep93xx_ts_isr(int irq, void *dev_id, struct pt_regs *regs)
+{
+    DPRINTK("isr\n");
+
+    // 
+    // Note that we don't clear the interrupt here.  The interrupt
+    // gets cleared in TS_Soft_Scan_Mode when the TS ENABLE
+    // bit is cleared.
+    //
+
+    //
+    // Set the ts to manual polling mode and schedule a callback.
+    // That way we can return from the isr in a reasonable amount of
+    // time and process the touch in the callback after a brief delay.
+    //
+    TS_Soft_Scan_Mode();
+    
+    return(IRQ_HANDLED);
+}
+ 
+/*
+ * Save the current ts 'event' in an atomic fashion.
+ */
+static void ee93xx_ts_evt_add( int buttons, int iX, int iY, int iPressure )
+{
+
+#ifdef PRINT_CALIBRATION_FACTORS
+    if( iX > iMaxX ) iMaxX = iX;
+    if( iX < iMinX ) iMinX = iX;
+    if( iY > iMaxY ) iMaxY = iY;
+    if( iY < iMinY ) iMinY = iY;
+#endif
+    
+    //DPRINTK("cb\n");
+    /*
+     * Note the event, but use spinlocks to keep it from getting
+     * halfway read if we get interrupted.
+     */  
+    
+    spin_lock(&event_buffer_lock);
+    gSample.currentX        = iX;
+    gSample.currentY        = iY;
+    gSample.currentButton   = buttons;
+    gSample.currentPressure = iPressure;
+    bFreshTouchData         = 1;
+    do_gettimeofday(&gSample.currentTime);
+
+    spin_unlock(&event_buffer_lock);
+
+    kill_fasync(&ep93xx_fasync, SIGIO, POLL_IN);
+    wake_up_interruptible(&queue);
+
+}
+
+
+static ssize_t ep93xx_ts_read(struct file *filp, char *buf, size_t count, loff_t *l)
+{
+
+    unsigned short data[3];
+    struct  ts_sample   ts_data;
+    int     iReturn = -EFAULT;
+
+#ifdef PRINT_CALIBRATION_FACTORS
+    static int lala=0;
+    if( bFreshTouchData && (lala++ > 9) )
+    {
+        //DPRINTK("%4d, %4d - range [%4d to %4d],[%4d to %4d]\n",f, currentY, iMinX, iMaxX, iMinY, iMaxY );
+        DPRINTK("%4d, %4d - range [%4d to %4d],[%4d to %4d]\n",gSample.currentX, gSample.currentY, iMinX, iMaxX, iMinY, iMaxY );//NZG mod
+        lala = 0;
+    }
+#endif
+    if( !bFreshTouchData)
+    {
+        iReturn = 0;
+    }        
+    else if( (count == sizeof(data)) )
+    {
+        spin_lock_irq(&event_buffer_lock);
+        bFreshTouchData = 0;
+        data[0] = gSample.currentX;
+        data[1] = gSample.currentY;
+        data[2] = gSample.currentButton;
+        
+        spin_unlock_irq(&event_buffer_lock);
+
+        if (copy_to_user(buf, data, sizeof data))
+	{
+             DPRINTK("read returning error 1\n");
+	     return -EFAULT;
+	}
+
+        count -= sizeof(data);
+
+        /* return the # of bytes that got read */
+        iReturn = sizeof(data) ;
+	DPRINTK("read returning %d bytes read\n", iReturn);
+    }
+    else if (count == sizeof(struct ts_sample) )
+    {
+        spin_lock_irq(&event_buffer_lock);
+        bFreshTouchData = 0;
+        ts_data.x           = gSample.currentX;
+        ts_data.y           = gSample.currentY;
+        ts_data.pressure    = gSample.currentPressure;
+        ts_data.tv          = gSample.currentTime;
+        spin_unlock_irq(&event_buffer_lock);
+        
+        if (copy_to_user(buf, &ts_data, sizeof(struct ts_sample)))
+        {
+	    DPRINTK("read returning error\n");
+            iReturn = -EFAULT;
+        }
+        else
+        {                
+            count -= sizeof(ts_data);
+            iReturn = sizeof(ts_data);
+	    DPRINTK("read returning %d as sizeof(ts_data)\n", iReturn);
+        }            
+
+    }
+
+    return iReturn;
+}
+
+static unsigned int ep93xx_ts_poll(struct file *filp, poll_table *wait)
+{
+    // printk("ep93xx_ts_poll\n");
+    poll_wait(filp, &queue, wait);
+
+    if( bFreshTouchData )
+    {
+        return POLLIN | POLLRDNORM;
+    }
+    
+    return 0;
+}
+
+static int ep93xx_ts_open(struct inode *inode, struct file *filp)
+{
+    DPRINTK("ep93xx_ts_open\n");
+
+    if( down_trylock(&open_sem) )
+    {
+        return -EBUSY;
+    }
+
+    ep93xx_ts_setup();
+
+    return 0;
+}
+
+/*
+ * Asynchronous I/O support.
+ */
+static int ep93xx_ts_fasync(int fd, struct file *filp, int on)
+{
+    int retval;
+
+    retval = fasync_helper(fd, filp, on, &ep93xx_fasync);
+    if (retval < 0)
+    {
+        return retval;
+    }
+    
+    return 0;
+}
+
+static int ep93xx_ts_release(struct inode *inode, struct file *filp)
+{
+    Stop_Timer2();
+
+    /*
+     * Call our async I/O support to request that this file 
+     * cease to be used for async I/O.
+     */
+    ep93xx_ts_fasync(-1, filp, 0);
+
+    ep93xx_ts_shutdown();
+    
+    up(&open_sem);
+    
+    return 0;
+}
+
+static ssize_t ep93xx_ts_write(struct file *file, const char *buffer, size_t count,
+               loff_t *ppos)
+{
+    return -EINVAL;
+}
+
+
+static int ep93xx_ts_ioctl(struct inode *inode, struct file *file, uint command, ulong u)
+{
+    static const int         version = EV_VERSION;   
+    static const u_int32_t   bit =(1 << EV_ABS);
+    static const u_int32_t   absbit = (1 << ABS_X) | (1 << ABS_Y) | (1 << ABS_PRESSURE);
+    int         iReturn ;
+    int         i = 0;
+    
+    switch(command)
+    {
+        case EVIOCGVERSION:
+            DPRINTK("ep93xx_ts_ioctl command = EVIOCGVERSION\r\n");
+            i = copy_to_user((void __user *)u, (void *)version, sizeof(version));
+            iReturn = i ? -EFAULT : 0;
+            break;
+            
+        case EVIOCGBIT(0,sizeof(u_int32_t) * 8) :
+            DPRINTK("ep93xx_ts_ioctl command = EVIOCGBIT(0,sizeof(uint32) * 8)\r\n");
+            i = copy_to_user((void __user *)u, (void *)bit, sizeof(bit));
+            iReturn = i ? -EFAULT : 0;
+            break;
+            
+        case EVIOCGBIT(EV_ABS, sizeof(absbit) * 8):
+            DPRINTK("ep93xx_ts_ioctl command = EVIOCGBIT(0,sizeof(uint32) * 8)\r\n");
+            copy_to_user((void __user *)u, (void *)absbit, sizeof(absbit));
+            iReturn = i ? -EFAULT : 0;
+            break;
+        default:
+            DPRINTK(" ep93xx_ts_ioctl unknown command = %d\n",u);           
+            iReturn = -1;
+            break;
+    }            
+    
+    return iReturn;
+}
+
+static struct file_operations ep93xx_ts_fops = {
+    owner:      THIS_MODULE,
+    read:       ep93xx_ts_read,
+    write:      ep93xx_ts_write,
+    poll:       ep93xx_ts_poll,
+    open:       ep93xx_ts_open,
+    ioctl:      ep93xx_ts_ioctl,
+    release:    ep93xx_ts_release,
+    fasync:     ep93xx_ts_fasync,
+};
+
+static struct miscdevice ep93xx_ts_miscdev = 
+{
+        EP93XX_TS_MINOR,
+        "ep93xx_ts",
+        &ep93xx_ts_fops
+};
+
+void ep93xx_ts_setup(void)
+{
+    unsigned int uiKTDIV, uiTSXYMaxMin;
+    DPRINTK("ep93xx_hw_setup\n");
+    
+    /*
+     * Set the TSEN bit in KTDIV so that we are enabling the clock
+     * for the touchscreen.
+     */    
+    uiKTDIV = inl(SYSCON_KTDIV);
+    uiKTDIV |= SYSCON_KTDIV_TSEN;
+    SysconSetLocked( SYSCON_KTDIV, uiKTDIV );    
+
+    //
+    // Program the TSSetup and TSSetup2 registers.
+    //
+    outl( TSSETUP_DEFAULT, TSSetup );
+    outl( TSSETUP2_DEFAULT, TSSetup2 );
+
+    //
+    // Set the the touch settings. 
+    //
+    outl( 0xaa, TSSWLock );
+    outl( sSwitchSettings.uiDischarge, TSDirect );
+
+    outl( 0xaa, TSSWLock );
+    outl( sSwitchSettings.uiDischarge, TSDischarge );
+
+    outl( 0xaa, TSSWLock );
+    outl( sSwitchSettings.uiSwitchZ1, TSXSample );
+
+    outl( 0xaa, TSSWLock );
+    outl( sSwitchSettings.uiSwitchZ2, TSYSample );
+
+    outl( 0xaa, TSSWLock );
+    outl( sSwitchSettings.uiDetect, TSDetect );
+
+    //
+    // X,YMin set to 0x40 = have to drag that many pixels for a new irq.
+    // X,YMax set to 0x40 = 1024 pixels is the maximum movement within the
+    // time scan limit.
+    //
+    uiTSXYMaxMin =  (50   << TSMAXMIN_XMIN_SHIFT) & TSMAXMIN_XMIN_MASK;
+    uiTSXYMaxMin |= (50   << TSMAXMIN_YMIN_SHIFT) & TSMAXMIN_YMIN_MASK;
+    uiTSXYMaxMin |= (0xff << TSMAXMIN_XMAX_SHIFT) & TSMAXMIN_XMAX_MASK;
+    uiTSXYMaxMin |= (0xff << TSMAXMIN_YMAX_SHIFT) & TSMAXMIN_YMAX_MASK;
+    outl( uiTSXYMaxMin, TSXYMaxMin );
+    
+    bCurrentPenDown = 0;
+    bFreshTouchData = 0;
+    guiLastX = 0;
+    guiLastY = 0;
+    guiLastInvPressure = 0xffffff;
+    
+    //
+    // Enable the touch screen scanning engine.
+    //
+    TS_Hardware_Scan_Mode();
+}
+
+/*
+ * ep93xx_ts_shutdown
+ *
+ */
+static void
+ep93xx_ts_shutdown(void)
+{
+    unsigned int uiKTDIV;
+    
+    DPRINTK("ep93xx_ts_shutdown\n");
+    
+    sTouch.state = TS_STATE_STOPPED;
+    Stop_Timer2();
+
+    /*
+     * Disable the scanning engine.
+     */
+    outl( 0, TSSetup );
+    outl( 0, TSSetup2 );
+
+    /*
+     * Clear the TSEN bit in KTDIV so that we are disabling the clock
+     * for the touchscreen.
+     */    
+    uiKTDIV = inl(SYSCON_KTDIV);
+    uiKTDIV &= ~SYSCON_KTDIV_TSEN;
+    SysconSetLocked( SYSCON_KTDIV, uiKTDIV );    
+
+} /* ep93xx_ts_shutdown */
+
+static irqreturn_t ep93xx_timer2_isr(int irq, void *dev_id, struct pt_regs *regs)
+{
+    DPRINTK("state: %d\n", (int)sTouch.state );
+
+    switch( sTouch.state )
+    {
+        case TS_STATE_STOPPED:
+            TS_Hardware_Scan_Mode();
+            break;
+            
+        //
+        // Get the Z1 value for pressure measurement and set up
+        // the switch register for getting the Z2 measurement.
+        //
+        case TS_STATE_Z1:
+            Set_Timer2_uSec( EP93XX_TS_ADC_DELAY_USEC );
+            sTouch.uiZ1 = ADCGetData( 2, 200 );
+            ep93xx_ts_set_direct( sSwitchSettings.uiSwitchZ2 );
+            sTouch.state = TS_STATE_Z2;
+            break;
+        
+        //
+        // Get the Z2 value for pressure measurement and set up
+        // the switch register for getting the Y measurement.
+        //
+        case TS_STATE_Z2:
+            sTouch.uiZ2 = ADCGetData( 2, 200 );
+            ep93xx_ts_set_direct( sSwitchSettings.uiYSample );
+            sTouch.state = TS_STATE_Y;
+            break;
+        
+        //
+        // Get the Y value and set up the switch register for 
+        // getting the X measurement.
+        //
+        case TS_STATE_Y:
+            sTouch.uiY = ADCGetData( 4, 20 );
+            ep93xx_ts_set_direct( sSwitchSettings.uiXSample );
+            sTouch.state = TS_STATE_X;
+            break;
+        
+        //
+        // Read the X value.  This is the last of the 4 adc values
+        // we need so we continue on to process the data.
+        //
+        case TS_STATE_X:
+            Stop_Timer2();
+            
+            sTouch.uiX = ADCGetData( 4, 20 );
+            
+            outl( 0xaa, TSSWLock );
+            outl( sSwitchSettings.uiDischarge, TSDirect );
+            
+            sTouch.state = TS_STATE_DONE;
+        
+            /*
+             * Process this set of ADC readings.
+             */
+            ProcessPointData();
+            
+            break;
+
+
+        //
+        // Shouldn't get here.  But if we do, we can recover...
+        //
+        case TS_STATE_DONE:
+            TS_Hardware_Scan_Mode();
+            break;
+    } 
+
+    //
+    // Clear the timer2 interrupt.
+    //
+    outl( 1, TIMER2CLEAR );
+    return(IRQ_HANDLED);
+}
+
+/*---------------------------------------------------------------------
+ * ProcessPointData
+ *
+ * This routine processes the ADC data into usable point data and then
+ * puts the driver into hw or sw scanning mode before returning.
+ *
+ * We calculate inverse pressure (lower number = more pressure) then
+ * do a hystheresis with the two pressure values 'light' and 'heavy'.
+ *
+ * If we are above the light, we have pen up.
+ * If we are below the heavy we have pen down.
+ * As long as the pressure stays below the light, pen stays down.
+ * When we get above the light again, pen goes back up.
+ *
+ */
+static void ProcessPointData(void)
+{
+    int  bValidPoint = 0;
+    unsigned int   uiXDiff, uiYDiff, uiInvPressureDiff;
+    unsigned int   uiInvPressure;
+
+    //
+    // Calculate the current pressure.
+    //
+    uiInvPressure = CalculateInvPressure();
+
+    DPRINTK(" X=0x%x, Y=0x%x, Z1=0x%x, Z2=0x%x, InvPressure=0x%x",
+            sTouch.uiX, sTouch.uiY, sTouch.uiZ1, sTouch.uiZ2, uiInvPressure ); 
+
+    //
+    // If pen pressure is so light that it is greater than the 'max' setting
+    // then we consider this to be a pen up.
+    //
+    if( uiInvPressure >= TS_LIGHT_INV_PRESSURE )
+    {
+        DPRINTK(" -- up \n");
+        bCurrentPenDown = 0;
+                ee93xx_ts_evt_add( 0, guiLastX, guiLastY, 0 );
+        TS_Hardware_Scan_Mode();
+        return;
+    }
+
+    //
+    // Hystheresis:
+    // If the pen pressure is hard enough to be less than the 'min' OR
+    // the pen is already down and is still less than the 'max'...
+    //
+    if( (uiInvPressure < TS_HEAVY_INV_PRESSURE) ||
+        ( bCurrentPenDown && (uiInvPressure < TS_LIGHT_INV_PRESSURE) )  )
+    {
+        if( bCurrentPenDown )
+        {
+            //
+            // If pen was previously down, check the difference between
+            // the last sample and this one... if the difference between 
+            // samples is too great, ignore the sample.
+            //
+            uiXDiff = abs(guiLastX - sTouch.uiX);
+            uiYDiff = abs(guiLastY - sTouch.uiY);
+            uiInvPressureDiff = abs(guiLastInvPressure - uiInvPressure);
+            
+            if( (uiXDiff < TS_MAX_VALID_XY_CHANGE) && (uiYDiff < TS_MAX_VALID_XY_CHANGE) &&
+                (uiInvPressureDiff < TS_MAX_VALID_PRESSURE_CHANGE) )
+            {
+                DPRINTK(" -- valid(two) \n");
+                bValidPoint = 1;
+            }
+            else
+            {
+                DPRINTK(" -- INvalid(two) \n");
+            }
+        }
+        else
+        {
+            DPRINTK(" -- valid \n");
+            bValidPoint = 1;
+        }
+        
+        /*
+         * If either the pen was put down or dragged make a note of it.
+         */
+        if( bValidPoint )
+        {
+            guiLastX = sTouch.uiX;
+            guiLastY = sTouch.uiY;
+            guiLastInvPressure = uiInvPressure;
+            bCurrentPenDown = 1;
+	    DPRINTK("calling ee93xx_ts_evt_add\n");
+            ee93xx_ts_evt_add( 1, sTouch.uiX, sTouch.uiY, (0x7000000 /uiInvPressure) );
+        }
+
+        TS_Soft_Scan_Mode();
+        return;
+    }
+
+    DPRINTK(" -- fallout \n");
+    TS_Hardware_Scan_Mode();
+}
+
+static void ep93xx_ts_set_direct( unsigned int uiADCSwitch )
+{
+    unsigned int uiResult;
+    
+    //
+    // Set the switch settings in the direct register.
+    //
+    outl( 0xaa, TSSWLock );
+    outl( uiADCSwitch, TSDirect );
+
+    //
+    // Read and throw away the first sample.
+    //
+    do {
+        uiResult = inl(TSXYResult);
+    } while( !(uiResult & TSXYRESULT_SDR) );
+    
+}
+
+static unsigned int ADCGetData
+( 
+    unsigned int uiSamples, 
+    unsigned int uiMaxDiff 
+)
+{
+    unsigned int   uiResult, uiValue, uiCount, uiLowest, uiHighest, uiSum, uiAve;
+
+    do
+    {
+        //
+        //Initialize our values.
+        //
+        uiLowest        = 0xfffffff;
+        uiHighest       = 0;
+        uiSum           = 0;
+        
+        for( uiCount = 0 ; uiCount < uiSamples ; uiCount++ )
+        {
+            //
+            // Read the touch screen four more times and average.
+            //
+            do {
+                uiResult = inl(TSXYResult);
+            } while( !(uiResult & TSXYRESULT_SDR) );
+            
+            uiValue = (uiResult & TSXYRESULT_AD_MASK) >> TSXYRESULT_AD_SHIFT;
+            uiValue = ((uiValue >> 4) + ((1 + TSXYRESULT_X_MASK)>>1))  & TSXYRESULT_X_MASK; 
+
+            //
+            // Add up the values.
+            //
+            uiSum += uiValue;
+
+            //
+            // Get the lowest and highest values.
+            //
+            if( uiValue < uiLowest )
+            {
+                uiLowest = uiValue;
+            }
+            if( uiValue > uiHighest )
+            {
+                uiHighest = uiValue;
+            }
+        }
+
+    } while( (uiHighest - uiLowest) > uiMaxDiff );
+
+    //
+    // Calculate the Average value.
+    //
+    uiAve = uiSum / uiSamples;
+
+    return uiAve;    
+}
+
+//****************************************************************************
+// CalculateInvPressure
+//****************************************************************************
+// Is the Touch Valid.  Touch is not valid if the X or Y value is not 
+// in range and the pressure is not  enough.
+// 
+// Touch resistance can be measured by the following formula:
+//
+//          Rx * X *     Z2
+// Rtouch = --------- * (-- - 1)
+//           4096        Z1
+//
+// This is simplified in the ration of Rtouch to Rx.  The lower the value, the
+// higher the pressure.
+//
+//                     Z2
+// InvPressure =  X * (-- - 1)
+//                     Z1
+//
+static unsigned int CalculateInvPressure(void)
+{
+    unsigned int   uiInvPressure;
+
+    //
+    // Check to see if the point is valid.
+    //
+    if( sTouch.uiZ1 < MIN_Z1_VALUE )
+    {
+        uiInvPressure = 0x10000;
+    }
+
+    //
+    // Can omit the pressure calculation if you need to get rid of the division.
+    //
+    else
+    {
+        uiInvPressure = ((sTouch.uiX * sTouch.uiZ2) / sTouch.uiZ1) - sTouch.uiX;
+    }    
+    if (uiInvPressure == 0) {
+    	DPRINTK("Setting InvPressure to 1\n");
+        uiInvPressure = 1;
+    }
+    return uiInvPressure;
+}
+
+
+
+//****************************************************************************
+// TS_Hardware_Scan_Mode
+//****************************************************************************
+// Enables the ep93xx ts scanning engine so that when the pen goes down
+// we will get an interrupt.
+// 
+//
+static void TS_Hardware_Scan_Mode(void)
+{
+    unsigned int   uiDevCfg;
+
+    DPRINTK("S\n");
+
+    //
+    // Disable the soft scanning engine.
+    //
+    sTouch.state = TS_STATE_STOPPED;
+    Stop_Timer2();
+    
+    //
+    // Clear the TIN (Touchscreen INactive) bit so we can go to
+    // automatic scanning mode.
+    //
+    uiDevCfg = inl( SYSCON_DEVCFG );
+    SysconSetLocked( SYSCON_DEVCFG, (uiDevCfg & ~SYSCON_DEVCFG_TIN) );    
+
+    //
+    // Enable the touch screen scanning state machine by setting
+    // the ENABLE bit.
+    //
+    outl( (TSSETUP_DEFAULT | TSSETUP_ENABLE), TSSetup );
+
+    //
+    // Set the flag to show that we are in interrupt mode.
+    //
+    gScanningMode = TS_MODE_HARDWARE_SCAN;
+
+    //
+    // Initialize TSSetup2 register.
+    //
+    outl( TSSETUP2_DEFAULT, TSSetup2 );
+
+}
+
+//****************************************************************************
+// TS_Soft_Scan_Mode
+//****************************************************************************
+// Sets the touch screen to manual polling mode.
+// 
+//
+static void TS_Soft_Scan_Mode(void)
+{
+    unsigned int   uiDevCfg;
+
+    DPRINTK("M\n");
+
+    if( gScanningMode != TS_MODE_SOFT_SCAN )
+    {
+        //
+        // Disable the touch screen scanning state machine by clearing
+        // the ENABLE bit.
+        //
+        outl( TSSETUP_DEFAULT, TSSetup );
+
+        //
+        // Set the TIN bit so we can do manual touchscreen polling.
+        //
+        uiDevCfg = inl( SYSCON_DEVCFG );
+        SysconSetLocked( SYSCON_DEVCFG, (uiDevCfg | SYSCON_DEVCFG_TIN) );    
+    }
+
+    //
+    // Set the switch register up for the first ADC reading
+    //
+    ep93xx_ts_set_direct( sSwitchSettings.uiSwitchZ1 );
+    
+    //
+    // Initialize our software state machine to know which ADC
+    // reading to take
+    //
+    sTouch.state = TS_STATE_Z1;
+    
+    //
+    // Set the timer so after a mSec or two settling delay it will 
+    // take the first ADC reading.
+    // 
+    Set_Timer2_uSec( EP93XX_TS_PER_POINT_DELAY_USEC );
+    
+    //
+    // Note that we are in sw scanning mode not hw scanning mode.
+    //
+    gScanningMode = TS_MODE_SOFT_SCAN;
+
+}
+
+static void Set_Timer2_uSec( unsigned int uiDelay_uSec )
+{
+    unsigned int uiClockTicks;
+
+    /*
+     * Stop timer 2
+     */
+    outl( 0, TIMER2CONTROL );
+
+    uiClockTicks = ((uiDelay_uSec * 508) + 999) / 1000;
+    outl( uiClockTicks, TIMER2LOAD );
+    outl( uiClockTicks, TIMER2VALUE );
+
+    /*
+     * Set up Timer 2 for 508 kHz clock and periodic mode.
+     */ 
+    outl( 0xC8, TIMER2CONTROL );
+
+}
+
+static void Stop_Timer2(void)
+{
+    outl( 0, TIMER2CONTROL );
+}
+
+/*
+ * Initialization and exit routines
+ */
+int __init ep93xx_ts_init(void)
+{
+    int retval;
+
+    DPRINTK("ep93xx_ts_init\n");
+
+    DPRINTK("request Touchscreen interrupt.\n");
+    retval = request_irq( IRQ_EP93XX_TOUCH, ep93xx_ts_isr, IRQF_DISABLED, "ep93xx_ts", 0);
+    if( retval )
+    {
+        DPRINTK(KERN_WARNING "ep93xx_ts: failed to get touchscreen IRQ\n");
+        return retval;
+    }
+
+    DPRINTK("Request Timer interrupt.\n");
+    retval = request_irq( IRQ_EP93XX_TIMER2, ep93xx_timer2_isr,
+                        IRQF_DISABLED, "ep93xx_timer2", 0);
+    if( retval )
+    {
+        DPRINTK(KERN_WARNING "ep93xx_ts: failed to get timer2 IRQ\n");
+        return retval;
+    }
+
+    DPRINTK("Register Touchscreen Driver\n");
+    misc_register(&ep93xx_ts_miscdev);
+
+    sTouch.state = TS_STATE_STOPPED;
+    gScanningMode = TS_MODE_UN_INITIALIZED;
+    
+    DPRINTK(KERN_NOTICE "EP93xx touchscreen driver configured for 4-wire operation\n");
+
+    return 0;
+}
+void __exit
+ep93xx_ts_exit(void)
+{
+    DPRINTK("ep93xx_ts_exit\n");
+    
+    Stop_Timer2();
+
+    free_irq(IRQ_EP93XX_TOUCH, 0);
+    free_irq(IRQ_EP93XX_TIMER2, 0);
+    
+    misc_deregister(&ep93xx_ts_miscdev);
+}
+
+module_init(ep93xx_ts_init);
+module_exit(ep93xx_ts_exit);
+
+MODULE_DESCRIPTION("Cirrus EP93xx touchscreen driver");
+MODULE_SUPPORTED_DEVICE("touchscreen/ep93xx");
diff -Naur linux-2.6.25/drivers/input/touchscreen/Kconfig linux-2.6.25.ep93xx/drivers/input/touchscreen/Kconfig
--- linux-2.6.25/drivers/input/touchscreen/Kconfig	2008-04-16 21:49:44.000000000 -0500
+++ linux-2.6.25.ep93xx/drivers/input/touchscreen/Kconfig	2008-08-18 14:05:42.000000000 -0500
@@ -263,4 +263,8 @@
 	bool "GoTop Super_Q2/GogoPen/PenPower tablet device support" if EMBEDDED
 	depends on TOUCHSCREEN_USB_COMPOSITE
 
+config TOUCHSCREEN_EP93XX
+        tristate "EP93xx Touchscreen"
+        depends on ARM && INPUT && ARCH_EP93XX
+
 endif
diff -Naur linux-2.6.25/drivers/input/touchscreen/Makefile linux-2.6.25.ep93xx/drivers/input/touchscreen/Makefile
--- linux-2.6.25/drivers/input/touchscreen/Makefile	2008-04-16 21:49:44.000000000 -0500
+++ linux-2.6.25.ep93xx/drivers/input/touchscreen/Makefile	2008-08-18 14:05:42.000000000 -0500
@@ -13,6 +13,7 @@
 obj-$(CONFIG_TOUCHSCREEN_MTOUCH)	+= mtouch.o
 obj-$(CONFIG_TOUCHSCREEN_MK712)		+= mk712.o
 obj-$(CONFIG_TOUCHSCREEN_HP600)		+= hp680_ts_input.o
+obj-$(CONFIG_TOUCHSCREEN_EP93XX)	+= ep93xx_ts.o
 obj-$(CONFIG_TOUCHSCREEN_HP7XX)		+= jornada720_ts.o
 obj-$(CONFIG_TOUCHSCREEN_USB_COMPOSITE)	+= usbtouchscreen.o
 obj-$(CONFIG_TOUCHSCREEN_PENMOUNT)	+= penmount.o
diff -Naur linux-2.6.25/drivers/ioex/boardspec.c linux-2.6.25.ep93xx/drivers/ioex/boardspec.c
--- linux-2.6.25/drivers/ioex/boardspec.c	1969-12-31 18:00:00.000000000 -0600
+++ linux-2.6.25.ep93xx/drivers/ioex/boardspec.c	2008-08-18 14:05:42.000000000 -0500
@@ -0,0 +1,52 @@
+ /***************************************************************************
+                          		boardspec.c    
+			Registration of board specific classes & devices. 
+			Registers and calls a function pointer from the arch's platform device
+			Important in that it allows for a proper module loading order, which may be
+			required as some methods call other modules (specifically Xenamai)             
+                             -------------------
+	author				 : NZG
+    begin                : Tue May 15 2007
+    copyright          	 : (C) 2007 by EMAC.Inc
+    email                : support@emacinc.com
+ ***************************************************************************/
+#include <linux/kernel.h>
+#include <linux/autoconf.h>
+#include <linux/ioport.h>
+#include <linux/device.h>
+#include <linux/ioex/ecoreex.h>
+#include <linux/platform_device.h>
+#include <asm/io.h> 
+ 
+#define DRV_MODULE_NAME 	"boardspec"
+#define DRV_MODULE_VERSION 	"1.0"
+
+static int boardspec_probe(struct platform_device *pdev){
+	int (*device_init)(void);
+	if (pdev == NULL)return -ENODEV;
+	device_init = pdev->dev.platform_data;
+	return device_init();
+}
+
+//driver currently has no removal method.
+static struct platform_driver boardspec_driver = {
+	.probe		= boardspec_probe,
+	.driver		= {
+		.name	= "boardspec",
+	},
+};
+
+static int __init boardspec_init_module(void)
+{
+	printk(KERN_INFO DRV_MODULE_NAME " version " DRV_MODULE_VERSION " loading\n");
+	return platform_driver_register(&boardspec_driver);
+}
+
+static void __exit boardspec_cleanup_module(void)
+{
+	platform_driver_unregister(&boardspec_driver);
+}
+
+
+module_init(boardspec_init_module);
+module_exit(boardspec_cleanup_module);
diff -Naur linux-2.6.25/drivers/ioex/ecoreex.c linux-2.6.25.ep93xx/drivers/ioex/ecoreex.c
--- linux-2.6.25/drivers/ioex/ecoreex.c	1969-12-31 18:00:00.000000000 -0600
+++ linux-2.6.25.ep93xx/drivers/ioex/ecoreex.c	2008-12-08 12:37:17.000000000 -0600
@@ -0,0 +1,271 @@
+/***************************************************************************
+                          		ecoreex.c    
+					EMAC soft cores device registration             
+                             -------------------
+	author				 : NZG
+    rewrite              : Tue May 15 2007
+    copyright          	 : (C) 2007 by EMAC.Inc
+    email                : support@emacinc.com
+ ***************************************************************************/
+ 
+#include <linux/kernel.h>
+#include <linux/autoconf.h>
+#include <linux/ioport.h>
+#include <linux/device.h>
+#include <linux/platform_device.h>
+#include <linux/class/gpio.h>
+#include <linux/class/pwm.h>
+#include <linux/class/mmcprot.h>
+#include <linux/ioex/ecoreex.h>
+#include <linux/ioex/pwmd.h>
+#include <asm/io.h>
+
+//---------------------------------------------------------------------------------
+#ifdef CONFIG_ECOREEX_TGPIO
+#define CPLD_BASE_NAME "iPac GPI/O expansion R1.0" 
+#define CPLD_BASE 0xA0
+
+#define CPLD_BASE_NAME_11 "iPac GPI/O expansion R1.1" 
+#define CPLD_BASE_11 0xA3
+
+static inline int CPLD_BASE_map(unsigned long phys_addr,u8 *virt_addr,unsigned long size,const char *name){
+	
+	if(request_mem_region(phys_addr,size,name)==NULL){
+		printk("could not obtain physical memory at %lx for EMAC core\n",phys_addr);
+		iounmap(virt_addr);
+		return -1;
+		}			
+	//add appropriate class devices for this version to the system
+	printk("%s detected at %lx\n",name,phys_addr);
+
+#ifdef CONFIG_GPIOCLASS
+	gpio_declare();
+	gpio_device_create(&virt_addr[0], &virt_addr[1],"portw");
+	gpio_device_create(&virt_addr[2], &virt_addr[3],"portx");
+	gpio_device_create(&virt_addr[4], &virt_addr[5],"porty");
+	gpio_device_create(&virt_addr[6], &virt_addr[7],"portz");
+#endif
+				
+return 0;
+}
+#endif //CONFIG_ECOREEX_TGPIO
+//---------------------------------------------------------------------------------
+#ifdef CONFIG_ECOREEX_SGPWM
+#define CPLD_GPWM_NAME "iPac Shadow GPI/O & PWM expansion R1.0"
+#define CPLD_GPWM 0xA1
+
+#define CPLD_GPWM_NAME_11 "iPac Shadow GPI/O & PWM expansion R1.1"
+#define CPLD_GPWM_11 0xA2
+
+#define CPLD_GPWM_NAME_12 "iPac Shadow GPI/O & PWM expansion R1.2"
+#define CPLD_GPWM_12 0xA4
+
+static int gpwm_carddetect(mmcslot_t *s){
+	u8 status = atomic_gpio_data_read(s->pd[MMCCD]);
+	return (status&1)?0:1;
+}
+
+static int gpwm_writeprotect(mmcslot_t *s){
+	u8 status = atomic_gpio_data_read(s->pd[MMCWP]);
+	return (status&2)?1:0;
+}
+
+static inline int CPLD_GPWM_map(unsigned long phys_addr,u8 *virt_addr,unsigned long size,const char *name,struct ecoreex_data *e){
+	if(request_mem_region(phys_addr,size,name)==NULL){
+		printk("could not obtain physical memory at %lx for EMAC core\n",phys_addr);
+		iounmap(virt_addr);
+		return -1;
+		}
+	
+	printk("%s detected at %lx\n",name,phys_addr);			
+	//add appropriate class devices for this version to the system
+
+#ifdef CONFIG_GPIOCLASS	
+{
+	struct class_device *status = gpi_device_create(&virt_addr[6],"status");
+	gpi_device_create(&virt_addr[0],"portw");
+	gpo_device_create(&virt_addr[1],"portx");
+	gpo_device_create(&virt_addr[2],"porty");
+	gpi_device_create(&virt_addr[3],"portz");
+	gpo_device_create(&virt_addr[7],"control");
+	 
+	if(e->mmcslot){//implement MMC CD and WP functions
+		e->mmcslot->carddetect = gpwm_carddetect;
+		e->mmcslot->writeprotect = gpwm_writeprotect;
+		e->mmcslot->pd[MMCWP]=e->mmcslot->pd[MMCCD]=status->class_data;//pass back gpio class structures
+	}
+}
+#endif	//CONFIG_GPIOCLASS
+
+#ifdef CONFIG_PWMCLASS
+	pwmd_device_create(&virt_addr[4],"gpwma",e->read_periodusa);
+	pwmd_device_create(&virt_addr[5],"gpwmb",e->read_periodusa);
+#endif	
+
+
+
+return 0;
+}
+
+#endif //CONFIG_ECOREEX_SGPWM
+
+//---------------------------------------------------------------------------------
+#ifdef CONFIG_ECOREEX_GCMB
+#define CPLD_GCMB_NAME_10 "GCMB CPLD expansion R1.0"
+#define CPLD_GCMB 0xB0
+
+static inline int CPLD_GCMB_map(unsigned long phys_addr,u8 *virt_addr,unsigned long size,const char *name){
+	
+	if(request_mem_region(phys_addr,size,name)==NULL){
+		printk("could not obtain physical memory at %lx for EMAC core\n",phys_addr);
+		iounmap(virt_addr);
+		return -1;
+		}
+	
+	printk("%s detected at %lx\n",name,phys_addr);			
+	//add appropriate class devices for this version to the system
+
+#ifdef CONFIG_GPIOCLASS	
+	gpio_declare();
+	gpo_device_create(&virt_addr[0],"dlais321");
+	gpi_device_create(&virt_addr[4],"rlwc3210");
+	gpio_device_create(&virt_addr[2], NULL,"spi_7730");
+#endif	//CONFIG_GPIOCLASS
+
+return 0;
+}
+
+#endif //CONFIG_ECOREEX_GCMB
+
+#ifdef CONFIG_ECOREEX_SOM200
+#define CPLD_SOM200_NAME "EMAC SoM-200ES GPI/O expansion R1.0"
+#define CPLD_SOM200 0xDE
+static inline int CPLD_SOM200_map(unsigned long phys_addr, u8 *virt_addr, 
+		unsigned long size, const char *name, struct ecoreex_data *data)
+{   
+	gpio_t *gpio_porta;
+	gpio_t *gpio_portb;
+	gpio_t *gpio_portc;
+	gpio_t *gpio_control;
+
+
+	if (request_mem_region(phys_addr, size, name) == NULL) {
+		printk("Could not obtain physical memory at %lx for EMAC core\n", phys_addr);
+		iounmap(virt_addr);
+	}
+
+	printk("%s detected at %lx\n",name,phys_addr);
+
+	gpio_declare();
+
+	gpio_porta = gpio_device_create_unregistered(&virt_addr[0], &virt_addr[1], "porta");
+	gpio_porta->index_write = NULL;
+	gpio_porta->index_read = NULL;
+	ecoreex_setup_data_access(data->e_access, gpio_porta);
+
+	gpio_portb = gpio_device_create_unregistered(&virt_addr[2], &virt_addr[3], "portb");
+	gpio_portb->index_write = NULL;
+	gpio_portb->index_read = NULL;
+	ecoreex_setup_data_access(data->e_access, gpio_portb);
+
+	/* High Drive */
+	gpio_portc = gpio_device_create_unregistered(&virt_addr[4], NULL, "portc");
+	gpio_portc->index_write = NULL;
+	gpio_portc->index_read = NULL;
+	ecoreex_setup_data_access(data->e_access, gpio_portc);
+
+	gpio_control = gpio_device_create_unregistered(&virt_addr[6], NULL, "control");
+	gpio_control->index_write = NULL;
+	gpio_control->index_read = NULL;
+	ecoreex_setup_data_access(data->e_access, gpio_control);
+
+	gpio_register_class_device(gpio_porta);
+	gpio_register_class_device(gpio_portb);
+	gpio_register_class_device(gpio_portc);
+	gpio_register_class_device(gpio_control);
+
+	return 0;
+}
+#endif
+/************************************************************
+ * core mappings based upon a key
+ */
+static inline void map_core(unsigned long phys_addr, unsigned long size, struct ecoreex_data *data)
+{
+	u8 *virt_addr = ioremap_nocache(phys_addr,size);
+	int version;
+	if(virt_addr==NULL)printk("could not remap physical memory at %lx for EMAC core\n",phys_addr);
+	else{
+		version =ioread8(&virt_addr[data->key_offset]);
+		//printk("EMAC core version %x detected at %lx\n",version,phys_addr+data->key_offset );
+		switch(version){
+			//-----------------------------------------------------------
+			#ifdef CONFIG_ECOREEX_TGPIO
+			case CPLD_BASE:
+				CPLD_BASE_map(phys_addr,virt_addr,size,CPLD_BASE_NAME);
+			break;
+			case CPLD_BASE_11:
+				CPLD_BASE_map(phys_addr,virt_addr,size,CPLD_BASE_NAME_11);
+			break;
+			#endif //CONFIG_ECOREEX_TGPIO
+			//-----------------------------------------------------------
+			#ifdef CONFIG_ECOREEX_SGPWM
+			case CPLD_GPWM:
+				CPLD_GPWM_map(phys_addr,virt_addr,size,CPLD_GPWM_NAME,data);
+			break;
+			case CPLD_GPWM_11:
+				CPLD_GPWM_map(phys_addr,virt_addr,size,CPLD_GPWM_NAME_11,data);
+			break;
+			case CPLD_GPWM_12:
+				CPLD_GPWM_map(phys_addr,virt_addr,size,CPLD_GPWM_NAME_12,data);
+			break;
+			#endif //CONFIG_ECOREEX_SGPWM
+			//-----------------------------------------------------------
+			#ifdef CONFIG_ECOREEX_GCMB
+			case CPLD_GCMB:
+				CPLD_GCMB_map(phys_addr,virt_addr,size,CPLD_GCMB_NAME_10);
+			break;
+			#endif //CONFIG_ECOREEX_GCMB
+			#ifdef CONFIG_ECOREEX_SOM200
+			case CPLD_SOM200:
+				CPLD_SOM200_map(phys_addr,virt_addr,size,CPLD_SOM200_NAME,data);
+			break;
+			#endif
+			//-----------------------------------------------------------			
+			default://unrecognized CPLD or no CPLD available, silently fail and the physical memory region
+				iounmap(virt_addr);
+			}
+		}
+}
+
+static int ecoreex_probe(struct platform_device *pdev){
+	//printk("ecoreex_probe\n");	
+	if (pdev == NULL)return -ENODEV;
+	map_core(pdev->resource->start,(pdev->resource->end-pdev->resource->start+1),pdev->dev.platform_data);
+	return 0;
+}
+
+//driver currently has no removal method.
+static struct platform_driver ecoreex_driver = {
+	.probe		= ecoreex_probe,
+	.driver		= {
+		.name	= "ecoreex",
+	},
+};
+
+#define DRV_MODULE_NAME 	"ecoreex"
+#define DRV_MODULE_VERSION 	"1.2"
+static int __init ecoreex_init_module(void)
+{
+	printk(KERN_INFO DRV_MODULE_NAME " version " DRV_MODULE_VERSION " loading\n");
+	return platform_driver_register(&ecoreex_driver);
+}
+
+static void __exit ecoreex_cleanup_module(void)
+{
+	platform_driver_unregister(&ecoreex_driver);
+}
+
+module_init(ecoreex_init_module);
+module_exit(ecoreex_cleanup_module);
+
