linuxppc-dev.lists.ozlabs.org archive mirror
 help / color / mirror / Atom feed
* [PATCH] Updated: CPM2 I2C (SDMA and BitBang)
@ 2005-03-22 21:12 Jason McMullan
  2005-03-28  4:11 ` Eugene Surovegin
  0 siblings, 1 reply; 3+ messages in thread
From: Jason McMullan @ 2005-03-22 21:12 UTC (permalink / raw)
  To: linuxppc-embedded


[-- Attachment #1.1: Type: text/plain, Size: 267 bytes --]

Updated (thanks to a quick eye by ebs) patch to add 
CPM2 SDMA and BitBang I2C support to the MPC85xx

This patch gets rid of some really stupid cut & paste errors
during initialization.

-- 
Jason McMullan <jason.mcmullan@timesys.com>
TimeSys Corporation


[-- Attachment #1.2: driver-i2c-cpm.patch --]
[-- Type: text/x-patch, Size: 24409 bytes --]

#### Auto-generated patch ####
Date:        Tue, 22 Mar 2005 15:59:01 -0500
Maintainer:  Jason McMullan <jmcmullan@timesys.com>
Summary:     CPM/CPM2 I2C driver for Freescale SoC devices
Description: CPM/CPM2 I2C driver for Freescale SoC devices
Depends:
	
###############################

Index of changes:

 drivers/i2c/algos/Kconfig              |    4 
 drivers/i2c/algos/Makefile             |    1 
 drivers/i2c/busses/Kconfig             |   25 +
 drivers/i2c/busses/Makefile            |    1 
 include/linux/i2c-id.h                 |    4 
 linux/drivers/i2c/algos/i2c-algo-cpm.c |  477 +++++++++++++++++++++++++++++++++
 linux/drivers/i2c/busses/i2c-cpm.c     |  219 +++++++++++++++
 linux/include/linux/i2c-algo-cpm.h     |   64 ++++
 8 files changed, 791 insertions(+), 4 deletions(-)


--- linux-orig/drivers/i2c/algos/Kconfig
+++ linux/drivers/i2c/algos/Kconfig
@@ -16,6 +16,10 @@
 	  This support is also available as a module.  If so, the module 
 	  will be called i2c-algo-bit.
 
+config I2C_ALGO_CPM
+	tristate "MPC (8xx and 8xxx) CPM I2C interface"
+	depends on (8xx || 85xx ) && I2C
+
 config I2C_ALGOPCF
 	tristate "I2C PCF 8584 interfaces"
 	depends on I2C
--- linux-orig/drivers/i2c/algos/Makefile
+++ linux/drivers/i2c/algos/Makefile
@@ -3,6 +3,7 @@
 #
 
 obj-$(CONFIG_I2C_ALGOBIT)	+= i2c-algo-bit.o
+obj-$(CONFIG_I2C_ALGO_CPM)	+= i2c-algo-cpm.o
 obj-$(CONFIG_I2C_ALGOPCF)	+= i2c-algo-pcf.o
 obj-$(CONFIG_I2C_ALGOPCA)	+= i2c-algo-pca.o
 obj-$(CONFIG_I2C_ALGOITE)	+= i2c-algo-ite.o
--- /dev/null
+++ linux/drivers/i2c/algos/i2c-algo-cpm.c
@@ -0,0 +1,477 @@
+/*
+ * i2c-algo-cpm.c i2x driver algorithms for Motorola MPC CPM
+ * Copyright (c) 2004 Jason McMullan (jason.mcmullan@timesys.com)
+ * Copyright (c) 1999 Dan Malek (dmalek@jlc.net).
+ *
+ *  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.
+ *
+ * based on i2c-algo-cpm.c
+ */
+
+/* $Id$ */
+
+#include <linux/module.h>
+#include <linux/init.h>
+#include <linux/kernel.h>
+#include <linux/delay.h>
+#include <linux/slab.h>
+#include <linux/version.h>
+#include <linux/ioport.h>
+#include <linux/errno.h>
+#include <linux/sched.h>
+#include <linux/interrupt.h>
+#include <linux/pci.h>
+
+#include <linux/i2c.h>
+#include <linux/i2c-algo-cpm.h>
+
+#include <asm/io.h>
+
+#define I2C_VERSION	"0.1"
+#define I2C_DATE	"Mar 22, 2005"
+
+#define CPM_MAX_READ	513
+/* #define I2C_CHIP_ERRATA */ /* Try uncomment this if you have an older CPU(earlier than rev D4) */
+
+#undef DEBUG
+
+#ifdef DEBUG
+int cpm_debug = 0;
+MODULE_PARM(cpm_debug, "i");
+#define static /**/
+#define DPRINTK(fmt, args...) printk(KERN_INFO fmt ,##args)
+#else
+#define DPRINTK(args...) do { } while (0)
+#endif
+
+static void cpm_i2c_param_reset(struct i2c_algo_cpm_data *cpm_adap)
+{
+	volatile cpm_iic_t	*iip = cpm_adap->iip;
+
+	/* Set up the IIC parameters in the parameter ram.
+	*/
+	iip->iic_rbase = cpm_adap->dp_offset;
+	iip->iic_tbase = cpm_adap->dp_offset + sizeof(cbd_t)*2;
+
+	/* Initialize the parameter ram.
+	 * We need to make sure many things are initialized to zero,
+	 * especially in the case of a microcode patch.
+	 */
+	iip->iic_rstate = 0;
+	iip->iic_rdp = 0;
+	iip->iic_rbptr = 0;
+	iip->iic_rbc = 0;
+	iip->iic_rxtmp = 0;
+	iip->iic_tstate = 0;
+	iip->iic_tdp = 0;
+	iip->iic_tbptr = 0;
+	iip->iic_tbc = 0;
+	iip->iic_txtmp = 0;
+
+	iip->iic_tfcr = CPMFCR_EB | CPMFCR_GBL;
+	iip->iic_rfcr = CPMFCR_EB | CPMFCR_GBL;
+
+	/* Set maximum receive size.
+	*/
+	iip->iic_mrblr = CPM_MAX_READ;
+
+}
+
+static int i2c_cpm_start(struct i2c_algo_cpm_data *cpm)
+{
+	volatile cpm_i2c_t *i2c = cpm->i2c;
+
+	DPRINTK("i2c_cpm_start: Ready (i2cmr=%.2x, i2cer=%.2x, i2com=%.2x, i2mod=%.2x)\n", i2c->i2c_i2cmr,i2c->i2c_i2cer,i2c->i2c_i2com,i2c->i2c_i2mod);
+
+	/* Wait for IIC transfer */
+	cpm->status = -EBUSY;
+	i2c->i2c_i2mod &= ~I2MOD_EN;
+
+	/* Chip bug, set enable here */
+	i2c->i2c_i2cmr = I2CER_MASK;	/* Enable interupts */
+	i2c->i2c_i2cer = I2CER_MASK;
+	i2c->i2c_i2mod = I2MOD_EN;		/* Enable */
+	i2c->i2c_i2com = I2COM_STR | I2COM_MS;	/* Begin transmission */
+	interruptible_sleep_on(&cpm->wait);
+
+	DPRINTK("i2c_cpm_start: Done  (i2cmr=%.2x, i2cer=%.2x, i2com=%.2x, i2mod=%.2x)\n", i2c->i2c_i2cmr,i2c->i2c_i2cer,i2c->i2c_i2com,i2c->i2c_i2mod);
+
+	DPRINTK("i2c_cpm_start: result=%d\n",cpm->status);
+	return cpm->status;
+}
+
+static irqreturn_t i2c_cpm_interrupt(int unused, void *dev_id, struct pt_regs *regs)
+ {
+	struct i2c_algo_cpm_data *cpm_adap = dev_id;
+	uint8_t events;
+
+#ifdef I2C_CHIP_ERRATA
+	/* Chip errata, clear enable.
+	 * This seems to not be needed on rev D4 or newer CPUs.
+	 * Someone with an older CPU needs to verify this.
+	 */
+	cpm_adap->i2c->i2c_i2mod &= ~I2MOD_EN; wmb();
+#endif
+
+	events = cpm_adap->i2c->i2c_i2cer;
+	DPRINTK("i2c_cpm_interrupt: dev_id=0x%p, i2cer=0x%.2x\n", dev_id,events);
+
+
+	if (events & I2CER_TXE) {
+		cpm_adap->status = -ENODEV;
+	} else if (events & I2CER_BSY) {
+		cpm_adap->status = -EAGAIN;
+	} else if (events & (I2CER_RXB | I2CER_TXB)) {
+		cpm_adap->status = 0;
+	}
+
+	/* Clear interrupt.
+	*/
+	cpm_adap->i2c->i2c_i2cer = events; wmb();
+
+	/* Get 'em going again.
+	*/
+	wake_up_interruptible(&cpm_adap->wait);
+
+	return IRQ_HANDLED;
+}
+
+/* Read from IIC...
+ * abyte = address byte, with r/w flag already set
+ */
+static int i2c_cpm_read(struct i2c_algo_cpm_data *cpm, uint8_t abyte, char *buf, int count)
+{
+	volatile cbd_t	*tbdf, *rbdf;
+	uint8_t *tb;
+	dma_addr_t tb_dma[2];
+	int err;
+
+	DPRINTK("i2c_cpm_read: abyte=0x%x(%c)\n", abyte>>1, "wr"[abyte&1]);
+
+	if (count >= CPM_MAX_READ)
+		return -EINVAL;
+
+	/* If we are relocated, we must reset the params */
+	if (cpm->reloc)
+		cpm_i2c_param_reset(cpm);
+
+	rbdf = (void *)cpm_dpram_addr(cpm->iip->iic_rbase);
+	tbdf = (void *)cpm_dpram_addr(cpm->iip->iic_tbase);
+
+	/* To read, we need an empty buffer of the proper length.
+	 * All that is used is the first byte for address, the remainder
+	 * is just used for timing (and doesn't really have to exist).
+	 */
+	tb = cpm->temp;
+	tb[0] = abyte;		/* Device address byte w/rw flag */
+
+
+	tb_dma[0] = dma_map_single(cpm->device, tb, 1, DMA_TO_DEVICE);
+	tbdf->cbd_bufaddr = tb_dma[0];
+	tbdf->cbd_datlen = 1;
+	tbdf->cbd_sc = BD_SC_READY | BD_SC_LAST | BD_SC_WRAP | BD_IIC_START;
+
+	cpm->iip->iic_mrblr = count + 1;
+
+	tb_dma[1] = dma_map_single(cpm->device, buf, count, DMA_FROM_DEVICE);
+	rbdf->cbd_datlen = 0;
+	rbdf->cbd_bufaddr = tb_dma[1];
+	rbdf->cbd_sc = BD_SC_EMPTY | BD_SC_WRAP| BD_SC_INTRPT;
+
+	DPRINTK("tbdf->cbd_sc(0x%p) = 0x%.4x\n",&tbdf->cbd_sc,tbdf->cbd_sc);
+	DPRINTK("rbdf->cbd_sc(0x%p) = 0x%.4x\n",&rbdf->cbd_sc,rbdf->cbd_sc);
+	err = i2c_cpm_start(cpm);
+	dma_unmap_single(cpm->device, tb_dma[1], count, DMA_FROM_DEVICE);
+	dma_unmap_single(cpm->device, tb_dma[0], 1, DMA_TO_DEVICE);
+	DPRINTK("tbdf->cbd_sc(0x%p) = 0x%.4x\n",&tbdf->cbd_sc,tbdf->cbd_sc);
+	DPRINTK("rbdf->cbd_sc(0x%p) = 0x%.4x\n",&rbdf->cbd_sc,rbdf->cbd_sc);
+	if (err)
+		return err;
+
+	if (tbdf->cbd_sc & BD_SC_READY) {
+		DPRINTK("i2c_cpm_read: complete but tbuf ready\n");
+		DPRINTK("\ttx sc %04x, rx sc %04x\n", tbdf->cbd_sc, rbdf->cbd_sc);
+		return -EREMOTEIO;
+	}
+
+	if (tbdf->cbd_sc & BD_SC_NAK) {
+		DPRINTK("i2c_cpm_read: no ack\n");
+		return -EREMOTEIO;
+ 	}
+
+	if (rbdf->cbd_sc & BD_SC_EMPTY) {
+		DPRINTK("i2c_cpm_read: complete but rbuf empty\n");
+		DPRINTK("\ttx sc %04x, rx sc %04x\n", tbdf->cbd_sc, rbdf->cbd_sc);
+		return -EREMOTEIO;
+	}
+
+	if (rbdf->cbd_sc & BD_SC_OV) {
+		DPRINTK("i2c_cpm_read: Overrun\n");
+		return -EREMOTEIO;
+ 	}
+
+	DPRINTK("i2c_cpm_read: read %d bytes\n", rbdf->cbd_datlen);
+
+	if (rbdf->cbd_datlen < count) {
+		DPRINTK("i2c_cpm_read: short, wanted %d got %d\n", count, rbdf->cbd_datlen);
+	}
+
+	return count;
+}
+
+/* Write to IIC...
+ * addr = address byte, with r/w flag already set
+ */
+static int
+i2c_cpm_write(struct i2c_algo_cpm_data *cpm, uint8_t abyte, char *buf,int count)
+{
+	volatile cbd_t *tbdf, *rbdf;
+	uint8_t *tb;
+	dma_addr_t tb_dma[2];
+	int err;
+
+	DPRINTK("i2c_cpm_write: abyte=0x%x(%c)\n", abyte>>1, "wr"[abyte&1]);
+
+	/* If we are relocated, we must reset the params */
+	if (cpm->reloc)
+		cpm_i2c_param_reset(cpm);
+
+	tb = cpm->temp;
+	tb[0] = abyte;		/* Device address byte w/rw flag */
+
+	/* set up 2 descriptors */
+	tbdf = (void *)cpm_dpram_addr(cpm->iip->iic_tbase);
+	rbdf = (void *)cpm_dpram_addr(cpm->iip->iic_rbase);
+
+	tb_dma[0] = dma_map_single(cpm->device, tb, 1, DMA_TO_DEVICE);
+	tbdf[0].cbd_bufaddr = tb_dma[0];
+	tbdf[0].cbd_datlen = 1;
+	tbdf[0].cbd_sc = BD_SC_READY | BD_SC_INTRPT | BD_IIC_START;
+
+	if (count > 0) {
+		tb_dma[1] = dma_map_single(cpm->device, buf, count, DMA_TO_DEVICE);
+		tbdf[1].cbd_bufaddr = tb_dma[1];
+		tbdf[1].cbd_datlen = count;
+		tbdf[1].cbd_sc = BD_SC_READY | BD_SC_INTRPT | BD_SC_LAST | BD_SC_WRAP;
+	} else {
+		tbdf[0].cbd_sc |= BD_SC_INTRPT | BD_SC_LAST | BD_SC_WRAP;
+		tb_dma[1] = 0;
+	}
+
+	rbdf[0].cbd_sc = BD_SC_WRAP;
+
+	DPRINTK("tbdf->cbd_sc(0x%p) = 0x%.4x(%d),0x%.4x(%d)\n",&tbdf->cbd_sc,tbdf[0].cbd_sc,tbdf[0].cbd_datlen,tbdf[1].cbd_sc,tbdf[1].cbd_datlen);
+	err = i2c_cpm_start(cpm);
+
+	if (tb_dma[1])
+		dma_unmap_single(cpm->device, tb_dma[1], count, DMA_TO_DEVICE);
+	dma_unmap_single(cpm->device, tb_dma[0], 1, DMA_TO_DEVICE);
+
+	DPRINTK("tbdf->cbd_sc(0x%p) = 0x%.4x(%d),0x%.4x(%d)\n",&tbdf->cbd_sc,tbdf[0].cbd_sc,tbdf[0].cbd_datlen,tbdf[1].cbd_sc,tbdf[1].cbd_datlen);
+	if (err < 0)
+		return err;
+
+
+	if (tbdf->cbd_sc & BD_SC_NAK) {
+		DPRINTK("i2c_cpm_write; no ack\n");
+		return -ENODEV;
+	}
+
+	if (tbdf->cbd_sc & BD_SC_READY) {
+		DPRINTK("i2c_cpm_write: complete but tbuf ready\n");
+		return -EREMOTEIO;
+	}
+
+	return count;
+}
+
+static int cpm_xfer(struct i2c_adapter *i2c_adap,
+		    struct i2c_msg msgs[],
+		    int num)
+{
+	struct i2c_algo_cpm_data *adap = i2c_adap->algo_data;
+	struct i2c_msg *pmsg;
+	int i, ret;
+	uint8_t addr;
+
+	for (i = 0; i < num; i++) {
+		pmsg = &msgs[i];
+
+		DPRINTK("i2c-algo-cpm: #%d addr=0x%x flags=0x%x len=%d\n buf=%lx\n", i, pmsg->addr, pmsg->flags, pmsg->len, (unsigned long)pmsg->buf);
+
+		addr = pmsg->addr << 1;
+		if (pmsg->flags & I2C_M_RD )
+			addr |= 1;
+		if (pmsg->flags & I2C_M_REV_DIR_ADDR )
+			addr ^= 1;
+
+		if (!(pmsg->flags & I2C_M_NOSTART)) {
+		}
+		if (pmsg->flags & I2C_M_RD ) {
+			/* read bytes into buffer*/
+			ret = i2c_cpm_read(adap, addr, pmsg->buf, pmsg->len);
+			DPRINTK("i2c-algo-cpm: read %d bytes\n", ret);
+			if (ret < pmsg->len ) {
+				return (ret<0)? ret : -EREMOTEIO;
+			}
+		} else {
+			/* write bytes from buffer */
+			ret = i2c_cpm_write(adap, addr, pmsg->buf, pmsg->len);
+			DPRINTK("i2c-algo-cpm: wrote %d\n", ret);
+			if (ret < pmsg->len ) {
+				return (ret<0) ? ret : -EREMOTEIO;
+			}
+		}
+	}
+	return (num);
+}
+
+static int algo_control(struct i2c_adapter *adapter,
+	unsigned int cmd, unsigned long arg)
+{
+	return 0;
+}
+
+static u32 cpm_func(struct i2c_adapter *adap)
+{
+	return I2C_FUNC_SMBUS_EMUL | I2C_FUNC_PROTOCOL_MANGLING;
+}
+
+/* -----exported algorithm data: -------------------------------------	*/
+
+static struct i2c_algorithm cpm_algo = {
+	"CPM2 algorithm",
+	I2C_ALGO_CPM2,
+	cpm_xfer,
+	NULL,
+	NULL,				/* slave_xmit		*/
+	NULL,				/* slave_recv		*/
+	algo_control,			/* ioctl		*/
+	cpm_func,			/* functionality	*/
+};
+
+static int i2c_cpm_init(struct i2c_algo_cpm_data *cpm_adap)
+{
+	volatile cpm_i2c_t	*i2c = cpm_adap->i2c;
+	unsigned char brg;
+
+	DPRINTK("i2c_cpm_init() - iip=%p\n",cpm_adap->iip);
+
+	cpm_adap->dp_offset = cpm_dpalloc(sizeof(cbd_t)*4+1, 16);
+	cpm_adap->temp = cpm_dpram_addr(cpm_adap->dp_offset+sizeof(cbd_t)*4);
+
+	cpm_i2c_param_reset(cpm_adap);
+
+	/* Initialize Tx/Rx parameters.
+	*/
+	if (! cpm_adap->reloc)
+		cpm_cp_command(CPM_CP_I2C, CPM_CR_INIT_TRX);
+
+	/* Select an arbitrary address.  Just make sure it is unique.
+	*/
+	i2c->i2c_i2add = 0xfc; wmb();
+
+	/* Make clock run at 60 KHz.
+	*/
+	brg = (unsigned char) (cpm_adap->intfreq/(32*2*60000) -3);
+	i2c->i2c_i2brg = brg;
+
+	i2c->i2c_i2mod = I2MOD_FLT; /* Enable filter */
+
+	/* Disable interrupts.
+	*/
+	i2c->i2c_i2cmr = 0;
+	i2c->i2c_i2cer = 0xff;
+
+	init_waitqueue_head(&cpm_adap->wait);
+
+	/* Install interrupt handler.
+	*/
+	DPRINTK("%s[%d] Install ISR for IRQ %d\n", __func__,__LINE__, cpm_adap->irq);
+	return request_irq(cpm_adap->irq, i2c_cpm_interrupt, 0, "i2c-algo-cpm", cpm_adap);
+}
+
+
+static int
+i2c_cpm_shutdown(struct i2c_algo_cpm_data *cpm_adap)
+{
+	volatile cpm_i2c_t *i2c = cpm_adap->i2c;
+
+	/* Shut down IIC.
+	*/
+	i2c->i2c_i2mod &= ~I2MOD_EN;
+	i2c->i2c_i2cmr = 0;
+	i2c->i2c_i2cer = I2CER_MASK;
+	free_irq(cpm_adap->irq,cpm_adap);
+	cpm_dpfree(cpm_adap->dp_offset);
+
+	return(0);
+}
+
+/*
+ * registering functions to load algorithms at runtime
+ */
+int i2c_cpm_add_bus(struct i2c_adapter *adap)
+{
+	struct i2c_algo_cpm_data *cpm_adap = adap->algo_data;
+
+	DPRINTK("i2c-algo-cpm: hw routines for %s registered.\n", adap->name);
+
+	/* register new adapter to i2c module... */
+
+	adap->id |= cpm_algo.id;
+	adap->algo = &cpm_algo;
+
+	i2c_add_adapter(adap);
+	i2c_cpm_init(cpm_adap);
+
+	return 0;
+}
+
+int i2c_cpm_del_bus(struct i2c_adapter *adap)
+{
+	int res;
+	struct i2c_algo_cpm_data *cpm_adap = adap->algo_data;
+
+	i2c_cpm_shutdown(cpm_adap);
+
+	if ((res = i2c_del_adapter(adap)) < 0)
+		return res;
+
+	printk("i2c-algo-cpm: adapter unregistered: %s\n",adap->name);
+
+	return 0;
+}
+
+MODULE_LICENSE("GPL");
+EXPORT_SYMBOL(i2c_cpm_add_bus);
+EXPORT_SYMBOL(i2c_cpm_del_bus);
+
+int __init i2c_algo_cpm_init (void)
+{
+	printk("i2c-algo-cpm: CPM2 I2C algorithm module version %s (%s)\n", I2C_VERSION, I2C_DATE);
+	return 0;
+}
+
+
+MODULE_AUTHOR("Jason McMullan <jason.mcmullan@timesys.com>");
+MODULE_DESCRIPTION("I2C-Bus CPM2 algorithm");
+
+static void i2c_algo_cpm_exit(void)
+{
+}
+
+module_init(i2c_algo_cpm_init);
+module_exit(i2c_algo_cpm_exit);

--- linux-orig/drivers/i2c/busses/Kconfig
+++ linux/drivers/i2c/busses/Kconfig
@@ -229,6 +229,21 @@
 	  This driver can also be built as a module.  If so, the module
 	  will be called i2c-mpc.
 
+config I2C_CPM
+	tristate "Motorola MPC8xx and MPC85xx CPM I2C"
+	depends on (8xx || 85xx) && I2C
+	help
+	  This supports the use of the I2C interface in the Motorola
+	  MPC8xx and MPC85xx series embedded processors on the CPM
+	  I2C macrocell.
+
+config I2C_CPM_BIT
+	bool "Bit-Bang only?"
+	depends on I2C_CPM
+	help
+	  Only use the CPM parallel port bit-banging interface, not the
+	  SDMA CPM device.
+
 config I2C_NFORCE2
 	tristate "Nvidia Nforce2"
 	depends on I2C && PCI && EXPERIMENTAL
@@ -317,10 +332,12 @@
 	  This support is also available as a module.  If so, the module 
 	  will be called i2c-prosavage.
 
-config I2C_RPXLITE
-	tristate "Embedded Planet RPX Lite/Classic support"
-	depends on (RPXLITE || RPXCLASSIC) && I2C
-	select I2C_ALGO8XX
+# This appears to be broken...
+#
+#config I2C_RPXLITE
+#	tristate "Embedded Planet RPX Lite/Classic support"
+#	depends on (RPXLITE || RPXCLASSIC) && I2C
+#	select I2C_ALGO8XX
 
 config I2C_S3C2410
 	tristate "S3C2410 I2C Driver"
--- linux-orig/drivers/i2c/busses/Makefile
+++ linux/drivers/i2c/busses/Makefile
@@ -8,6 +8,7 @@
 obj-$(CONFIG_I2C_AMD756)	+= i2c-amd756.o
 obj-$(CONFIG_I2C_AMD756_S4882)	+= i2c-amd756-s4882.o
 obj-$(CONFIG_I2C_AMD8111)	+= i2c-amd8111.o
+obj-$(CONFIG_I2C_CPM)		+= i2c-cpm.o
 obj-$(CONFIG_I2C_AU1550)	+= i2c-au1550.o
 obj-$(CONFIG_I2C_ELEKTOR)	+= i2c-elektor.o
 obj-$(CONFIG_I2C_HYDRA)		+= i2c-hydra.o
--- /dev/null
+++ linux/drivers/i2c/busses/i2c-cpm.c
@@ -0,0 +1,219 @@
+/*
+ * CPM I2C interface.
+ * Copyright (c) 2004 Jason McMullan (jason.mcmullan@timesys.com)
+ * Copyright (c) 1999 Dan Malek (dmalek@jlc.net).
+ *
+ * On-Chip Peripheral version of the Motorola CPM I2C macrocell driver,
+ * used on the MPC8xx and MPC85xx series processors.
+ */
+
+#include <linux/kernel.h>
+#include <linux/ioport.h>
+#include <linux/module.h>
+#include <linux/init.h>
+#include <linux/stddef.h>
+#include <linux/device.h>
+
+#include <linux/i2c.h>
+
+#include <asm/io.h>
+#ifdef CONFIG_CPM2
+#include <asm/cpm2.h>
+#else
+#include <asm/commproc.h>
+#endif
+
+#ifdef CONFIG_I2C_CPM_BIT
+#include <linux/i2c-algo-bit.h>
+
+#define CYCLE_DELAY	10
+#define TIMEOUT		(HZ / 2)
+#endif /* CONFIG_I2C_CPM_BIT */
+
+#ifdef CONFIG_CPM2
+/* SDA and SCL bits on port D */
+#define BIT_SDA (1<<16)
+#define BIT_SCL (1<<17)
+#endif /* CONFIG_CPM2 */
+
+#ifdef CONFIG_I2C_CPM_BIT
+static void bit_cpm_setsda(void *data, int state)
+{
+	if (state)
+		cpm2_immr->im_ioport.iop_pdatd |= BIT_SDA;
+	else
+		cpm2_immr->im_ioport.iop_pdatd &= ~BIT_SDA;
+}
+
+static void bit_cpm_setscl(void *data, int state)
+{
+	if (state)
+		cpm2_immr->im_ioport.iop_pdatd |= BIT_SCL;
+	else
+		cpm2_immr->im_ioport.iop_pdatd &= ~BIT_SCL;
+}
+
+static int bit_cpm_getsda(void *data)
+{
+	return (cpm2_immr->im_ioport.iop_pdatd & BIT_SDA) ? 1 : 0;
+}
+
+static int bit_cpm_getscl(void *data)
+{
+	return (cpm2_immr->im_ioport.iop_pdatd & BIT_SCL) ? 1 : 0;
+}
+
+
+static struct i2c_algo_bit_data cpm_data = {
+	.setsda = bit_cpm_setsda,
+	.setscl = bit_cpm_setscl,
+	.getsda = bit_cpm_getsda,
+	.getscl = bit_cpm_getscl,
+	.udelay = CYCLE_DELAY,
+	.mdelay = CYCLE_DELAY,
+	.timeout = TIMEOUT
+};
+#else /* !CONFIG_I2C_CPM_BIT */
+#include <linux/i2c-algo-cpm.h>
+
+static struct i2c_algo_cpm_data cpm_data = { .irq = -1 };
+#endif /* !CONFIG_I2C_CPM_BIT */
+
+static struct i2c_adapter cpm_ops = {
+	.owner		= THIS_MODULE,
+	.name		= "cpm-i2c",
+	.id		= I2C_HW_CPM2,
+	.algo_data	= &cpm_data,
+};
+
+#ifdef CONFIG_I2C_CPM_BIT
+static int __devinit cpm_i2c_probe_bitbang(struct device *dev)
+{
+#ifdef CONFIG_CPM2
+	if (cpm2_immr->im_ioport.iop_ppard & (BIT_SCL | BIT_SDA)) {
+		printk(KERN_INFO "%s: CPM I/O Port D is not configured for I2C bit-bang mode.\n", pdev->bus_id);
+		return -ENODEV;
+	}
+
+	/* Configure as open drain... */
+	cpm2_immr->im_ioport.iop_podrd |= (BIT_SCL | BIT_SDA);
+
+	/* Inputs... */
+	cpm2_immr->im_ioport.iop_pdird &= ~(BIT_SCL | BIT_SDA);
+#endif
+
+	return i2c_bit_add_bus(&cpm_ops);
+}
+#else
+static int __devinit cpm_i2c_probe_cpm(struct device *dev)
+{
+	struct platform_device *pdev = to_platform_device(dev);
+	struct resource *res;
+	int err;
+	struct i2c_algo_cpm_data *data = &cpm_data;
+	bd_t *binfo = (bd_t *)__res;
+
+	if (data->irq != -1)
+		return -EBUSY;
+
+	res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	if (res == NULL)
+		return -EINVAL;
+
+	data->i2c = (cpm_i2c_t *)ioremap(res->start,sizeof(cpm_i2c_t));
+	if (data->i2c == NULL)
+		return -ENOMEM;
+
+	res = platform_get_resource(pdev, IORESOURCE_MEM, 1);
+	if (res == NULL) {
+		iounmap((void *)data->i2c);
+		return -EINVAL;
+	}
+
+	data->iip = (iic_t *)ioremap(res->start,sizeof(iic_t));
+	if (data->iip == NULL) {
+		iounmap((void *)data->i2c);
+		return -ENOMEM;
+	}
+
+	res = platform_get_resource(pdev, IORESOURCE_IRQ, 0);
+	if (res == NULL) {
+		iounmap((void *)data->iip);
+		iounmap((void *)data->i2c);
+		return -EINVAL;
+	}
+
+	data->irq = res->start;
+
+	data->device = dev;
+	data->intfreq = binfo->bi_intfreq;
+
+#ifdef CONFIG_CPM2
+	/* Configure as peripheral... */
+	cpm2_immr->im_ioport.iop_ppard |= (BIT_SCL | BIT_SDA);
+	cpm2_immr->im_ioport.iop_psord |= (BIT_SCL | BIT_SDA);
+
+	/* Inputs... */
+	cpm2_immr->im_ioport.iop_pdird &= ~(BIT_SCL | BIT_SDA);
+#endif
+
+	err = i2c_cpm_add_bus(&cpm_ops);
+	if (err < 0) {
+		data->irq=-1;
+		iounmap((void *)data->iip);
+		iounmap((void *)data->i2c);
+		return err;
+	}
+
+	return 0;
+}
+#endif
+
+#ifdef CONFIG_I2C_CPM_BIT
+static void __devexit cpm_i2c_remove_bitbang(struct device *dev)
+{
+	i2c_bit_del_bus(&cpm_ops);
+}
+#else
+static void __devexit cpm_i2c_remove_cpm(struct device *dev)
+{
+	struct i2c_algo_cpm_data *data = &cpm_data;
+
+	i2c_cpm_del_bus(&cpm_ops);
+
+	iounmap((void *)data->iip);
+	iounmap((void *)data->i2c);
+}
+#endif
+
+static struct device_driver cpm_i2c_driver = {
+	.name	= "fsl-cpm-i2c",
+	.bus	= &platform_bus_type,
+#ifdef CONFIG_I2C_CPM_BIT
+	.probe	= cpm_i2c_probe_bitbang,
+	.remove	= __devexit_p(cpm_i2c_remove_bitbang),
+#else
+	.probe	= cpm_i2c_probe_cpm,
+	.remove	= __devexit_p(cpm_i2c_remove_cpm),
+#endif
+};
+
+int __init cpm_i2c_init(void)
+{
+	printk(KERN_INFO "%s: CPM2 i2c driver\n",cpm_i2c_driver.name);
+
+	return driver_register(&cpm_i2c_driver);
+}
+
+void __exit cpm_i2c_exit(void)
+{
+	driver_unregister(&cpm_i2c_driver);
+}
+
+MODULE_LICENSE("GPL");
+
+MODULE_AUTHOR("Jason McMullan <jason.mcmullan@timesys.com>");
+MODULE_DESCRIPTION("I2C-Bus (on CPM) adapter routines for MPC8xx and MPC85xx boards");
+
+module_init(cpm_i2c_init);
+module_exit(cpm_i2c_exit);

--- /dev/null
+++ linux/include/linux/i2c-algo-cpm.h
@@ -0,0 +1,64 @@
+/* ------------------------------------------------------------------------- */
+/* i2c-algo-mpc.h i2c driver algorithms for MPC CPMs			     */
+/* ------------------------------------------------------------------------- */
+
+/* $Id$ */
+
+#ifndef I2C_ALGO_MPC_H
+#define I2C_ALGO_MPC_H 1
+
+#include <linux/i2c.h>
+
+#ifdef CONFIG_85xx
+#include <asm/mpc85xx.h>
+#include <asm/cpm2.h>
+#include <asm/immap_85xx.h>
+
+typedef i2c_cpm2_t cpm_i2c_t;
+typedef iic_t cpm_iic_t;
+
+#elif defined(CONFIG_8xx)
+#include <asm/mpc8xx.h>
+#include <asm/commproc.h>
+
+typedef i2c8xx_t cpm_i2c_t;
+typedef iic_t cpm_iic_t;
+#endif
+
+#define I2MOD_EN	0x01
+#define I2MOD_PDIV_MASK	0x06
+#define   I2MOD_PDIV_4	0x06
+#define   I2MOD_PDIV_8	0x04
+#define   I2MOD_PDIV_16	0x02
+#define   I2MOD_PDIV_32	0x00
+#define I2MOD_FLT	0x08
+#define I2MOD_GCD	0x10
+#define I2MOD_REVD	0x20
+
+#define I2COM_MS	0x01
+#define I2COM_STR	0x80
+
+#define I2CER_MASK	0x17
+#define I2CER_TXE	0x10
+#define I2CER_BSY	0x04
+#define I2CER_TXB	0x02
+#define I2CER_RXB	0x01
+
+struct i2c_algo_cpm_data {
+	struct device		*device;
+        dma_addr_t		dp_offset;
+        int 			reloc;
+        volatile cpm_i2c_t	*i2c;
+        volatile cpm_iic_t	*iip;
+	int			irq;
+	int			intfreq;
+        uint8_t			*temp;
+
+	wait_queue_head_t	wait;
+	int			status;
+};
+
+int i2c_cpm_add_bus(struct i2c_adapter *);
+int i2c_cpm_del_bus(struct i2c_adapter *);
+
+#endif /* I2C_ALGO_CPM_H */

--- linux-orig/include/linux/i2c-id.h
+++ linux/include/linux/i2c-id.h
@@ -201,6 +201,7 @@
 #define I2C_ALGO_SIBYTE 0x150000	/* Broadcom SiByte SOCs		*/
 #define I2C_ALGO_SGI	0x160000        /* SGI algorithm                */
 #define I2C_ALGO_AU1550	0x170000        /* Au1550 PSC algorithm		*/
+#define I2C_ALGO_CPM2	0x180000	/* MPC8xxx and MPC8xx CPM I2C */
 
 #define I2C_ALGO_EXP	0x800000	/* experimental			*/
 
@@ -253,6 +254,9 @@
 /* --- ACPI Embedded controller algorithms                              */
 #define I2C_HW_ACPI_EC          0x00
 
+/* --- Motorola MPC CPM2 I2C adapters -- */
+#define I2C_HW_CPM2	0x00
+
 /* --- MPC824x PowerPC adapters						*/
 #define I2C_HW_MPC824X 0x00	/* Motorola 8240 / 8245                 */
 

[-- Attachment #2: This is a digitally signed message part --]
[-- Type: application/pgp-signature, Size: 189 bytes --]

^ permalink raw reply	[flat|nested] 3+ messages in thread

end of thread, other threads:[~2005-03-28 14:17 UTC | newest]

Thread overview: 3+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2005-03-22 21:12 [PATCH] Updated: CPM2 I2C (SDMA and BitBang) Jason McMullan
2005-03-28  4:11 ` Eugene Surovegin
2005-03-28 14:17   ` Jason McMullan

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).