SPI bus master driver for the Freescale MPC52xx.

Note: This patch as it stands right now will compile cleanly, but may
not bind the driver to the PSC.  arch/ppc/syslib/mpc52xx_devices.c
needs to be modified to rename the desired PSC platform devices to
match the driver.  (rename  to "mpc52xx-psc:spi")  This is a board
specific hack, and I need to make it cleaner before I resubmit this
patch.

Signed-off-by: Grant Likely <grant.likely at gdcanada.com>

diff -ruNp linux-spi/arch/ppc/platforms/lite5200.c
linux-spi-mpc5200/arch/ppc/platforms/lite5200.c
--- linux-spi/arch/ppc/platforms/lite5200.c     2005-06-17 15:48:29.000000000 
-0400
+++ linux-spi-mpc5200/arch/ppc/platforms/lite5200.c     2005-07-23
03:17:39.000000000 -0400
@@ -76,6 +76,21 @@ lite5200_map_irq(struct pci_dev *dev, un
 }
 #endif
 
+#if defined(CONFIG_SPI_BUS_MPC52XX_PSC) ||
defined(CONFIG_SPI_BUS_MPC52XX_PSC_MODULE)
+void
+spi_mpc52xx_psc_slave_select(int psc_id, int slave_id)
+{
+}
+
+void
+spi_mpc52xx_psc_slave_deselect(int psc_id)
+{
+}
+
+EXPORT_SYMBOL(spi_mpc52xx_psc_slave_select);
+EXPORT_SYMBOL(spi_mpc52xx_psc_slave_deselect);
+#endif
+
 static void __init
 lite5200_setup_cpu(void)
 {
@@ -107,15 +122,30 @@ lite5200_setup_cpu(void)
        else
                out_be16(&cdm->fd_counters, 0x5555);
 
+       /* Setup clocks for PSC3 SPI mode */
+       out_be16(&cdm->mclken_div_psc3, 0x8020);  /* Enable MClk for PSC3 */
+
        /* Get port mux config */
        port_config = in_be32(&gpio->port_config);
 
        /* 48Mhz internal, pin is GPIO */
-       port_config &= ~0x00800000;
+       port_config &= ~PORT_CONFIG_IR_USB_CLK;
 
-       /* USB port */
-       port_config &= ~0x00007000;     /* Differential mode - USB1 only */
-       port_config |=  0x00001000;
+       /* USB port: Differential mode; USB1 only */
+       port_config &= ~(PORT_CONFIG_USB_SE | PORT_CONFIG_USB_MASK);
+       port_config |=  PORT_CONFIG_USB_USB;
+
+       /* PSC2 (I2S Codec mode) */
+       port_config &= ~PORT_CONFIG_PSC2_MASK;
+       port_config |=  PORT_CONFIG_PSC2_CODEC; /* Codec mode */
+
+       /* PSC3 (SPI Codec mode) */
+       port_config &= ~PORT_CONFIG_PSC3_MASK;
+       port_config |=  PORT_CONFIG_PSC3_CODEC; /* Codec mode */
+
+       /* PSC6 (I2S Codec mode) */
+       port_config &= ~PORT_CONFIG_IRDA_MASK;
+       port_config |=  PORT_CONFIG_IRDA_CODEC; /* Codec mode */
 
        /* Commit port config */
        out_be32(&gpio->port_config, port_config);
diff -ruNp linux-spi/drivers/spi/Kconfig linux-spi-mpc5200/drivers/spi/Kconfig
--- linux-spi/drivers/spi/Kconfig       2005-07-22 17:08:00.000000000 -0400
+++ linux-spi-mpc5200/drivers/spi/Kconfig       2005-07-22 17:16:13.000000000 
-0400
@@ -20,6 +20,13 @@ config SPI
 comment "SPI Bus Drivers"
        depends on SPI
 
+config SPI_BUS_MPC52XX_PSC
+       tristate "SPI bus via MPC52xx PSC port"
+       depends on SPI && PPC_MPC52xx
+       help
+         Say Y here if you want to use an MPC52xx PSC port as an SPI bus
+         master.
+
 comment "SPI slaves"
        depends on SPI
 
diff -ruNp linux-spi/drivers/spi/Makefile linux-spi-mpc5200/drivers/spi/Makefile
--- linux-spi/drivers/spi/Makefile      2005-07-22 17:08:00.000000000 -0400
+++ linux-spi-mpc5200/drivers/spi/Makefile      2005-07-22 17:16:13.000000000 
-0400
@@ -3,3 +3,4 @@
 #
 
 obj-$(CONFIG_SPI)                      += spi-core.o
+obj-$(CONFIG_SPI_BUS_MPC52XX_PSC)      += spi-mpc52xx-psc.o
diff -ruNp linux-spi/drivers/spi/spi-mpc52xx-psc.c
linux-spi-mpc5200/drivers/spi/spi-mpc52xx-psc.c
--- linux-spi/drivers/spi/spi-mpc52xx-psc.c     1969-12-31 19:00:00.000000000 
-0500
+++ linux-spi-mpc5200/drivers/spi/spi-mpc52xx-psc.c     2005-07-22
17:16:13.000000000 -0400
@@ -0,0 +1,307 @@
+/*
+ * drivers/spi/mpc5xxx-psc.c
+ *
+ * Driver for the SPI mode of the MPC52xx PSC peripherals
+ *
+ * Maintainer : Grant Likely <glikely at gmail.com>
+ *
+ * This file is in the public domain
+ */
+
+/* Platform device Usage :
+ * (Blatantly copied from drivers/serial/mpc52xx_uart.c)
+ *
+ * Since PSCs can have multiple function, the correct driver for each one
+ * is selected based on the name assigned to the psc.  By convention, the
+ * function is appended to the device name in the board setup code.  For
+ * example, this spi psc driver will only bind to mpc52xx_psc.spi devices.
+ *
+ * The driver init all necessary registers to place the PSC in spi mode.
+ * However, the pin multiplexing aren't changed and should be set either
+ * by the bootloader or in the platform init code.
+ */
+
+#include <linux/device.h>
+#include <linux/module.h>
+#include <linux/fs.h>
+#include <linux/interrupt.h>
+#include <linux/spi.h>
+
+#include <asm/io.h>
+#include <asm/mpc52xx.h>
+#include <asm/mpc52xx_psc.h>
+
+
+/* The magic data is all in this structure.  This structure contains
+ * everything we need to keep track of the PSC
+ */
+struct mpc52xx_psc_spi_port {
+       struct platform_device *pdev;           /* PSC dev (on platform bus) */
+       struct mpc52xx_psc __iomem *psc;        /* PSC registers */
+       struct spi_bus spi_bus;
+       int irq;                                /* Assigned irq */
+
+       /* Current state variables */
+       struct semaphore sema; /* mutex to enforce one transfer at a time */
+       wait_queue_head_t wait_queue; /* Wait on this queue during transfer */
+
+       /* Warning: The following fields are not protected by a mutex.
+        * They can only be changed before a transfer starts or after
+        * a transfer ends.  During a transfer the isr will fiddle with
+        * them */
+       int rx_count;           /* remaining bytes to be received */
+       uint8_t *rx_ptr;        /* pointer for next RX character */
+};
+#define to_spi_port(bus) container_of(bus, struct
mpc52xx_psc_spi_port, spi_bus);
+
+struct mpc52xx_psc_spi_port mpc52xx_psc_spi_ports[MPC52xx_PSC_MAXNUM];
+
+
+/* Dynamically update the alarm level so interrupts don't occur too fast */
+static void mpc52xx_psc_spi_adjust_alarm(struct mpc52xx_psc_spi_port *port)
+{
+       struct mpc52xx_psc __iomem *psc = port->psc;
+       int alarm;
+
+       alarm = 0x200 - port->rx_count;
+       if (alarm < 0) alarm = 0;
+       if (alarm > 0x1ff) alarm = 0x1ff;
+       out_be16(&psc->rfalarm, alarm);
+}
+
+static irqreturn_t
+mpc52xx_psc_spi_isr(int irq, void *dev_id, struct pt_regs *regs)
+{
+       struct mpc52xx_psc_spi_port *port = (struct uart_port *)dev_id;
+       struct mpc52xx_psc __iomem *psc = port->psc;
+       int num, i;
+
+       if ( irq != port->irq ) {
+               printk( KERN_WARNING "mpc52xx_psc_spi: " \
+                       "Received wrong int %d. Waiting for %d\n",
+                      irq, port->irq);
+               return IRQ_NONE;
+       }
+       
+       if (in_be16(&psc->mpc52xx_psc_isr) & MPC52xx_PSC_IMR_RXRDY)
+       {
+               num = in_be16(&psc->rfnum);
+
+               /* Discard unexpected rx data */
+               if ((!port->rx_count) || (!port->rx_ptr))
+               {
+                       printk(KERN_WARNING "mpc52xx_psc_spi: "
+                               "discarding %i unexpected bytes\n", num);
+                       for (i = 0; i < num; i++)
+                               in_8(&psc->mpc52xx_psc_buffer_8);
+                       return IRQ_NONE;
+               }
+
+               /* Don't overflow the buffer */
+               if (num > port->rx_count)
+                       num = port->rx_count;
+
+               /* Transfer data into rx buffer */
+               ioread8_rep(&psc->mpc52xx_psc_buffer_8, port->rx_ptr, num);
+               port->rx_ptr += num;
+               port->rx_count -= num;
+
+               /* Dynamically update the alarm level so interrupts don't
+                * occur too frequently */
+               mpc52xx_psc_spi_adjust_alarm(port);
+
+               /* Only wakeup process if data transfer is complete */
+               if (port->rx_count == 0)
+                       wake_up_interruptible(&port->wait_queue);
+       }
+
+       return IRQ_NONE;
+}
+
+static int mpc52xx_psc_spi_startup(struct mpc52xx_psc_spi_port *port)
+{
+       int ret;
+       struct mpc52xx_psc __iomem *psc = port->psc;
+
+       ret = request_irq(port->irq, mpc52xx_psc_spi_isr,
+               SA_INTERRUPT | SA_SAMPLE_RANDOM, "mpc52xx_psc_spi", port);
+       if (ret)
+       {
+               printk(KERN_ALERT "mpc52xx_psc_spi: request_irq failed (%i)\n",
+                       ret);
+               return ret;
+       }
+
+       init_MUTEX(&port->sema);
+       init_waitqueue_head(&port->wait_queue);
+       port->rx_count = 0;
+       port->rx_ptr = NULL;
+
+       /* Reset the PSC into a known state */
+       out_8(&psc->command, MPC52xx_PSC_RST_RX);
+       out_8(&psc->command, MPC52xx_PSC_RST_TX);
+       out_8(&psc->command, MPC52xx_PSC_TX_DISABLE | MPC52xx_PSC_RX_DISABLE);
+
+       /* Interrupts must be based on alarm levels */
+       out_8(&psc->command, MPC52xx_PSC_SEL_MODE_REG_1);
+       out_8(&psc->mode, MPC52xx_PSC_MODE_FFULL);
+
+       /* Configure 8bit codec mode as an SPI master and use EOF flags */
+       out_be32(&psc->sicr, MPC52xx_PSC_SICR_SIM_CODEC8 |
+                            MPC52xx_PSC_SICR_GENCLK |
+                            MPC52xx_PSC_SICR_SPI |
+                            MPC52xx_PSC_SICR_MSTR |
+                            MPC52xx_PSC_SICR_USEEOF );
+       out_be16(&psc->ccr, 0x070F);
+
+       /* Set 2ms DTL delay */
+       out_8(&psc->ctur, 0x00);
+       out_8(&psc->ctlr, 0x84);
+}
+
+static int mpc52xx_psc_spi_transfer(struct spi_bus *bus, int id, int clkedge,
+                               uint8_t *in, const uint8_t *out, size_t count)
+{
+       struct mpc52xx_psc_spi_port *port;
+       struct mpc52xx_psc __iomem *psc;
+       uint32_t        sicr;
+       int err;
+
+       port = to_spi_port(bus);
+       psc = port->psc;
+
+       //printk(KERN_ALERT "mpc52xx_psc_spi: transfer; count=%i\n", count);
+
+       if (count < 1)
+               return -1;
+
+       /* Grab the semaphore, only one transfer allowed at a time */
+       err = down_interruptible(&port->sema);
+       if (err)
+               return err;
+
+       /* Disable SPI interrupts so rx buffer can be manipulated */
+       out_be16(&psc->mpc52xx_psc_imr, 0);
+
+       /* Set the clock polarity */
+       sicr = in_be32(&psc->sicr);
+       if (clkedge == SPI_CLKEDGE_RISING)
+               sicr &= ~MPC52xx_PSC_SICR_CPOL; /* Clear means rising edge */
+       else
+               sicr |= MPC52xx_PSC_SICR_CPOL; /* Set means falling edge */
+       out_be32(&psc->sicr, sicr);
+
+       /* Initialize the receive buffer; this can be done without locking
+        * because the ISR doesn't touch it until after interrupts are
+        * enabled
+        */
+       port->rx_ptr = in;
+       port->rx_count = count;
+       mpc52xx_psc_spi_adjust_alarm(port);
+
+       /* Select the slave, start the engine and transfer data to fifo */
+       spi_mpc52xx_psc_slave_select(port->pdev->id, id);
+       iowrite8(MPC52xx_PSC_RX_ENABLE | MPC52xx_PSC_TX_ENABLE, &psc->command);
+       if (count > 1)
+               iowrite8_rep(&psc->mpc52xx_psc_buffer_8, out, count-1);
+
+       /* Signal EOF for the last byte to terminate the transfer */
+       iowrite8(MPC52xx_PSC_IRCR2_NXTEOF, &psc->ircr2);
+       iowrite8(out[count-1], &psc->mpc52xx_psc_buffer_8);
+
+       /* Enable interrupts and go to sleep until transfer is complete*/
+       out_be16(&psc->mpc52xx_psc_imr, MPC52xx_PSC_IMR_RXRDY);
+       err = wait_event_interruptible(port->wait_queue, port->rx_count == 0);
+
+       /* Terminate the transfer, and deselect the slave */
+       port->rx_ptr = NULL;
+       out_8(&psc->command, MPC52xx_PSC_TX_DISABLE | MPC52xx_PSC_RX_DISABLE);
+       spi_mpc52xx_psc_slave_deselect(port->pdev->id);
+
+       /* Release the semaphore to allow other transfers */
+       up(&port->sema);
+       return err;
+}
+
+static struct spi_bus_ops mpc52xx_psc_spi_ops = {
+       .transfer = mpc52xx_psc_spi_transfer,
+};
+
+static int __devinit
+mpc52xx_psc_spi_probe(struct device *dev)
+{
+       struct platform_device *pdev = to_platform_device(dev);
+       struct resource *res = pdev->resource;
+       struct mpc52xx_psc_spi_port *port;
+       int idx = pdev->id;
+       int i;
+
+       printk(KERN_ALERT "mpc52xx-psc-spi: probing idx=%i\n", idx);
+
+       if ((idx != 0) && (idx != 1) && (idx !=2) && (idx != 5))
+       {
+               printk(KERN_ALERT "mpc52xx-psc-spi: PSC%i can't do SPI\n",
+                      idx+1);
+               return -ENODEV;
+       }
+
+       port = &mpc52xx_psc_spi_ports[idx];
+       port->pdev = pdev;
+       for (i = 0; i < pdev->num_resources; i++, res++)
+       {
+               if (res->flags & IORESOURCE_MEM)
+                       port->psc = (struct mpc52xx_psc __iomem *) res->start;
+               else if (res->flags & IORESOURCE_IRQ)
+                       port->irq = res->start;
+       }
+
+       mpc52xx_psc_spi_startup(port);
+       port->spi_bus.ops = &mpc52xx_psc_spi_ops;
+       port->spi_bus.dev.parent = dev;  /* The psc is the parent of the bus */
+       spi_bus_register(&port->spi_bus);
+
+       /* Ahhh!!! Run away from the board specific hack (This won't be 
+        * part of the real patch)
+        */
+       spi_device_create(&port->spi_bus, "ks8995m_spi", 0);
+       spi_device_create(&port->spi_bus, "tlv320aic26", 1);
+       return 0;
+}
+
+static int 
+mpc52xx_psc_spi_remove(struct device *dev)
+{
+       return 0;
+}
+
+static struct device_driver mpc52xx_psc_spi_platform_driver = {
+       .name           = "mpc52xx-psc:spi",
+       .bus            = &platform_bus_type,
+       .probe          = mpc52xx_psc_spi_probe,
+       .remove         = mpc52xx_psc_spi_remove,
+};
+
+static int __init mpc52xx_psc_spi_init(void)
+{
+       int ret;
+
+       printk(KERN_ALERT "mpc52xx_psc_spi: initializing\n");
+
+       ret = driver_register(&mpc52xx_psc_spi_platform_driver);
+       return ret;
+
+
+}
+
+static void __exit mpc52xx_psc_spi_exit(void)
+{
+       driver_unregister(&mpc52xx_psc_spi_platform_driver);
+       printk(KERN_ALERT "mpc52xx_psc_spi: exiting\n");
+}
+
+module_init(mpc52xx_psc_spi_init);
+module_exit(mpc52xx_psc_spi_exit);
+
+MODULE_AUTHOR("Grant Likely <glikely at gmail.com>");
+MODULE_DESCRIPTION("Freescale MPC52xx PSC driver for SPI mode");
+MODULE_LICENSE("Dual BSD/GPL");
diff -ruNp linux-spi/include/asm-ppc/mpc52xx.h
linux-spi-mpc5200/include/asm-ppc/mpc52xx.h
--- linux-spi/include/asm-ppc/mpc52xx.h 2005-06-17 15:48:29.000000000 -0400
+++ linux-spi-mpc5200/include/asm-ppc/mpc52xx.h 2005-07-23
02:29:41.000000000 -0400
@@ -146,6 +146,28 @@ enum ppc_sys_devices {
 #define MPC52xx_XLB_ARB_IRQ            (MPC52xx_PERP_IRQ_BASE + 21)
 #define MPC52xx_BDLC_IRQ               (MPC52xx_PERP_IRQ_BASE + 22)
 
+/* CDM Cloke enable bits */
+#define MPC52xx_CDM_CLKENABLE_MEM_CLK          (0x00080000)
+#define MPC52xx_CDM_CLKENABLE_PCI_CLK          (0x00040000)
+#define MPC52xx_CDM_CLKENABLE_LPC_CLK          (0x00020000)
+#define MPC52xx_CDM_CLKENABLE_SIT_CLK          (0x00010000)
+#define MPC52xx_CDM_CLKENABLE_SCOM_CLK         (0x00008000)
+#define MPC52xx_CDM_CLKENABLE_ATA_CLK          (0x00004000)
+#define MPC52xx_CDM_CLKENABLE_ETH_CLK          (0x00002000)
+#define MPC52xx_CDM_CLKENABLE_USB_CLK          (0x00001000)
+#define MPC52xx_CDM_CLKENABLE_SPI_CLK          (0x00000800)
+#define MPC52xx_CDM_CLKENABLE_BDLC_CLK         (0x00000400)
+#define MPC52xx_CDM_CLKENABLE_IRRX_CLK         (0x00000200)
+#define MPC52xx_CDM_CLKENABLE_IRTX_CLK         (0x00000100)
+#define MPC52xx_CDM_CLKENABLE_PSC345_CLK       (0x00000080)
+#define MPC52xx_CDM_CLKENABLE_PSC2_CLK         (0x00000040)
+#define MPC52xx_CDM_CLKENABLE_PSC1_CLK         (0x00000020)
+#define MPC52xx_CDM_CLKENABLE_PSC6_CLK         (0x00000010)
+#define MPC52xx_CDM_CLKENABLE_MSCAN_CLK                (0x00000008)
+#define MPC52xx_CDM_CLKENABLE_I2C_CLK          (0x00000004)
+#define MPC52xx_CDM_CLKENABLE_TIMER_CLK                (0x00000002)
+#define MPC52xx_CDM_CLKENABLE_GPIO_CLK         (0x00000001)
+
 
 
 /* ======================================================================== */
@@ -266,6 +288,49 @@ struct mpc52xx_rtc {
 };
 
 /* GPIO */
+#define PORT_CONFIG_CS1                        0x80000000
+#define PORT_CONFIG_ALT_MASK           0x30000000
+#define PORT_CONFIG_CS7                        0x08000000
+#define PORT_CONFIG_CS6                        0x04000000
+#define PORT_CONFIG_ATA                        0x03000000
+#define PORT_CONFIG_IR_USB_CLK         0x00800000
+#define PORT_CONFIG_IRDA_MASK          0x00700000 /* PSC6 */
+#define PORT_CONFIG_IRDA_GPIO          0x00000000
+#define PORT_CONFIG_IRDA_UART          0x00500000
+#define PORT_CONFIG_IRDA_CODEC         0x00700000
+#define PORT_CONFIG_ETHER_MASK         0x000F0000
+#define PORT_CONFIG_PCI_DIS            0x00008000
+#define PORT_CONFIG_USB_SE             0x00004000 /* Single ended mode */
+#define PORT_CONFIG_USB_MASK           0x00004000 /* (USB1 or 2 UARTs) */
+#define PORT_CONFIG_USB_USB            0x00001000
+#define PORT_CONFIG_USB_2UART          0x00002000
+#define PORT_CONFIG_PSC3_MASK          0x00000F00
+#define PORT_CONFIG_PSC3_GPIO          0x00000000
+#define PORT_CONFIG_PSC3_USB2          0x00000100
+#define PORT_CONFIG_PSC3_UART          0x00000400
+#define PORT_CONFIG_PSC3_UARTE_CD      0x00000500
+#define PORT_CONFIG_PSC3_CODEC         0x00000600
+#define PORT_CONFIG_PSC3_CODEC_MCLK    0x00000700
+#define PORT_CONFIG_PSC3_SPI           0x00000800
+#define PORT_CONFIG_PSC3_SPI_UART      0x00000C00
+#define PORT_CONFIG_PSC3_SPI_UARTE     0x00000D00
+#define PORT_CONFIG_PSC3_SPI_CODEC     0x00000E00
+#define PORT_CONFIG_PSC2_MASK          0x00000070
+#define PORT_CONFIG_PSC2_GPIO          0x00000000
+#define PORT_CONFIG_PSC2_CAN           0x00000010
+#define PORT_CONFIG_PSC2_AC97          0x00000020
+#define PORT_CONFIG_PSC2_UART          0x00000040
+#define PORT_CONFIG_PSC2_UARTE_CD      0x00000050
+#define PORT_CONFIG_PSC2_CODEC         0x00000060
+#define PORT_CONFIG_PSC2_CODEC_MCLK    0x00000070
+#define PORT_CONFIG_PSC1_MASK          0x00000007
+#define PORT_CONFIG_PSC1_GPIO          0x00000000
+#define PORT_CONFIG_PSC1_AC97          0x00000002
+#define PORT_CONFIG_PSC1_UART          0x00000004
+#define PORT_CONFIG_PSC1_UARTE_CD      0x00000005
+#define PORT_CONFIG_PSC1_CODEC         0x00000006
+#define PORT_CONFIG_PSC1_CODEC_MCLK    0x00000007
+
 struct mpc52xx_gpio {
        u32     port_config;    /* GPIO + 0x00 */
        u32     simple_gpioe;   /* GPIO + 0x04 */
diff -ruNp linux-spi/include/asm-ppc/mpc52xx_psc.h
linux-spi-mpc5200/include/asm-ppc/mpc52xx_psc.h
--- linux-spi/include/asm-ppc/mpc52xx_psc.h     2005-06-17 15:48:29.000000000 
-0400
+++ linux-spi-mpc5200/include/asm-ppc/mpc52xx_psc.h     2005-07-22
17:16:13.000000000 -0400
@@ -72,6 +72,51 @@
 #define MPC52xx_PSC_D_CTS              0x10
 #define MPC52xx_PSC_D_DCD              0x20
 
+/* PSC Serial Interface Control Register (SICR) bits */
+/* SICR Field masks */
+#define MPC52xx_PSC_SICR_ACRB          0x80000000
+#define MPC52xx_PSC_SICR_AWR           0x40000000
+#define MPC52xx_PSC_SICR_DTS1          0x20000000
+#define MPC52xx_PSC_SICR_SHDIR         0x10000000
+#define MPC52xx_PSC_SICR_SIM           0x0F000000
+#define MPC52xx_PSC_SICR_GENCLK                0x00800000
+#define MPC52xx_PSC_SICR_MULTIWD       0x00400000
+#define MPC52xx_PSC_SICR_CLKPOL                0x00200000
+#define MPC52xx_PSC_SICR_SYNCPOL       0x00100000
+#define MPC52xx_PSC_SICR_CELLSLAVE     0x00080000
+#define MPC52xx_PSC_SICR_CELL2XCLK     0x00040000
+#define MPC52xx_PSC_SICR_SPI           0x00008000
+#define MPC52xx_PSC_SICR_MSTR          0x00004000
+#define MPC52xx_PSC_SICR_CPOL          0x00002000
+#define MPC52xx_PSC_SICR_CPHA          0x00001000
+#define MPC52xx_PSC_SICR_USEEOF                0x00000800
+/* Operation modes */
+#define MPC52xx_PSC_SICR_SIM_UART              0x00000000
+#define MPC52xx_PSC_SICR_SIM_UART_DCD          0x08000000
+#define MPC52xx_PSC_SICR_SIM_CODEC8            0x01000000
+#define MPC52xx_PSC_SICR_SIM_CODEC16           0x02000000
+#define MPC52xx_PSC_SICR_SIM_AC97              0x03000000
+#define MPC52xx_PSC_SICR_SIM_SIR               0x04000000
+#define MPC52xx_PSC_SICR_SIM_SIR_DCD           0x0C000000
+#define MPC52xx_PSC_SICR_SIM_MIR               0x05000000
+#define MPC52xx_PSC_SICR_SIM_FIR               0x06000000
+#define MPC52xx_PSC_SICR_SIM_CODEC24           0x07000000
+#define MPC52xx_PSC_SICR_SIM_CODEC32           0x0F000000
+
+/* IRCR1 bit masks */
+#define MPC52xx_PSC_IRCR1_FD                   0x04
+#define MPC52xx_PSC_IRCR1_SIPEN                        0x02
+#define MPC52xx_PSC_IRCR1_SPUL                 0x01
+
+/* IRCR2 bit masks */
+#define MPC52xx_PSC_IRCR2_SIPREQ               0x04
+#define MPC52xx_PSC_IRCR2_ABORT                        0x02
+#define MPC52xx_PSC_IRCR2_NXTEOF               0x01
+
+/* Codec Clock Register fields */
+#define MPC52xx_PSC_CCR_FRAME_SYNC_DIV         0xFF00
+#define MPC52xx_PSC_CCR_BIT_CLK_DIV            0xFF00
+
 /* PSC mode fields */
 #define MPC52xx_PSC_MODE_5_BITS                        0x00
 #define MPC52xx_PSC_MODE_6_BITS                        0x01
@@ -187,5 +232,10 @@ struct mpc52xx_psc {
        u16             tflwfptr;       /* PSC + 0x9e */
 };
 
+#if defined(CONFIG_SPI_BUS_MPC52XX_PSC) ||
defined(CONFIG_SPI_BUS_MPC52XX_PSC_MODULE)
+/* Helper functions for selecting slaves SPI mode */
+extern void spi_mpc52xx_psc_slave_select(int psc_id, int slave_id);
+extern void spi_mpc52xx_psc_slave_deselect(int psc_id);
+#endif
 
 #endif  /* __ASM_MPC52xx_PSC_H__ */

Reply via email to