net: ks8851: Implement register, FIFO, lock accessor callbacks
[linux-2.6-microblaze.git] / drivers / net / ethernet / micrel / ks8851.c
index 0088df9..1fa907d 100644 (file)
@@ -64,16 +64,11 @@ union ks8851_tx_hdr {
 /**
  * struct ks8851_net - KS8851 driver private data
  * @netdev: The network device we're bound to
- * @spidev: The spi device we're bound to.
- * @lock: Lock to ensure that the device is not accessed when busy.
  * @statelock: Lock on this structure for tx list.
  * @mii: The MII state information for the mii calls.
  * @rxctrl: RX settings for @rxctrl_work.
- * @tx_work: Work queue for tx packets
  * @rxctrl_work: Work queue for updating RX mode and multicast lists
  * @txq: Queue of packets for transmission.
- * @spi_msg1: pre-setup SPI transfer with one message, @spi_xfer1.
- * @spi_msg2: pre-setup SPI transfer with two messages, @spi_xfer2.
  * @txh: Space for generating packet TX header in DMA-able data
  * @rxd: Space for receiving SPI data, in DMA-able space.
  * @txd: Space for transmitting SPI data, in DMA-able space.
@@ -86,11 +81,15 @@ union ks8851_tx_hdr {
  * @vdd_reg:   Optional regulator supplying the chip
  * @vdd_io: Optional digital power supply for IO
  * @gpio: Optional reset_n gpio
- *
- * The @lock ensures that the chip is protected when certain operations are
- * in progress. When the read or write packet transfer is in progress, most
- * of the chip registers are not ccessible until the transfer is finished and
- * the DMA has been de-asserted.
+ * @lock: Bus access lock callback
+ * @unlock: Bus access unlock callback
+ * @rdreg16: 16bit register read callback
+ * @wrreg16: 16bit register write callback
+ * @rdfifo: FIFO read callback
+ * @wrfifo: FIFO write callback
+ * @start_xmit: start_xmit() implementation callback
+ * @rx_skb: rx_skb() implementation callback
+ * @flush_tx_work: flush_tx_work() implementation callback
  *
  * The @statelock is used to protect information in the structure which may
  * need to be accessed via several sources, such as the network driver layer
@@ -102,8 +101,6 @@ union ks8851_tx_hdr {
  */
 struct ks8851_net {
        struct net_device       *netdev;
-       struct spi_device       *spidev;
-       struct mutex            lock;
        spinlock_t              statelock;
 
        union ks8851_tx_hdr     txh ____cacheline_aligned;
@@ -121,22 +118,61 @@ struct ks8851_net {
        struct mii_if_info      mii;
        struct ks8851_rxctrl    rxctrl;
 
-       struct work_struct      tx_work;
        struct work_struct      rxctrl_work;
 
        struct sk_buff_head     txq;
 
-       struct spi_message      spi_msg1;
-       struct spi_message      spi_msg2;
-       struct spi_transfer     spi_xfer1;
-       struct spi_transfer     spi_xfer2[2];
-
        struct eeprom_93cx6     eeprom;
        struct regulator        *vdd_reg;
        struct regulator        *vdd_io;
        int                     gpio;
+
+       void                    (*lock)(struct ks8851_net *ks,
+                                       unsigned long *flags);
+       void                    (*unlock)(struct ks8851_net *ks,
+                                         unsigned long *flags);
+       unsigned int            (*rdreg16)(struct ks8851_net *ks,
+                                          unsigned int reg);
+       void                    (*wrreg16)(struct ks8851_net *ks,
+                                          unsigned int reg, unsigned int val);
+       void                    (*rdfifo)(struct ks8851_net *ks, u8 *buff,
+                                         unsigned int len);
+       void                    (*wrfifo)(struct ks8851_net *ks,
+                                         struct sk_buff *txp, bool irq);
+       netdev_tx_t             (*start_xmit)(struct sk_buff *skb,
+                                             struct net_device *dev);
+       void                    (*rx_skb)(struct ks8851_net *ks,
+                                         struct sk_buff *skb);
+       void                    (*flush_tx_work)(struct ks8851_net *ks);
+};
+
+/**
+ * struct ks8851_net_spi - KS8851 SPI driver private data
+ * @ks8851: KS8851 driver common private data
+ * @lock: Lock to ensure that the device is not accessed when busy.
+ * @tx_work: Work queue for tx packets
+ * @spidev: The spi device we're bound to.
+ * @spi_msg1: pre-setup SPI transfer with one message, @spi_xfer1.
+ * @spi_msg2: pre-setup SPI transfer with two messages, @spi_xfer2.
+ *
+ * The @lock ensures that the chip is protected when certain operations are
+ * in progress. When the read or write packet transfer is in progress, most
+ * of the chip registers are not ccessible until the transfer is finished and
+ * the DMA has been de-asserted.
+ */
+struct ks8851_net_spi {
+       struct ks8851_net       ks8851;
+       struct mutex            lock;
+       struct work_struct      tx_work;
+       struct spi_device       *spidev;
+       struct spi_message      spi_msg1;
+       struct spi_message      spi_msg2;
+       struct spi_transfer     spi_xfer1;
+       struct spi_transfer     spi_xfer2[2];
 };
 
+#define to_ks8851_spi(ks) container_of((ks), struct ks8851_net_spi, ks8851)
+
 static int msg_enable;
 
 /* SPI frame opcodes */
@@ -151,6 +187,58 @@ static int msg_enable;
 /* turn register number and byte-enable mask into data for start of packet */
 #define MK_OP(_byteen, _reg) (BYTE_EN(_byteen) | (_reg)  << (8+2) | (_reg) >> 6)
 
+/**
+ * ks8851_lock_spi - register access lock for SPI
+ * @ks: The chip state
+ * @flags: Spinlock flags
+ *
+ * Claim chip register access lock
+ */
+static void ks8851_lock_spi(struct ks8851_net *ks, unsigned long *flags)
+{
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
+
+       mutex_lock(&kss->lock);
+}
+
+/**
+ * ks8851_unlock_spi - register access unlock for SPI
+ * @ks: The chip state
+ * @flags: Spinlock flags
+ *
+ * Release chip register access lock
+ */
+static void ks8851_unlock_spi(struct ks8851_net *ks, unsigned long *flags)
+{
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
+
+       mutex_unlock(&kss->lock);
+}
+
+/**
+ * ks8851_lock - register access lock
+ * @ks: The chip state
+ * @flags: Spinlock flags
+ *
+ * Claim chip register access lock
+ */
+static void ks8851_lock(struct ks8851_net *ks, unsigned long *flags)
+{
+       ks->lock(ks, flags);
+}
+
+/**
+ * ks8851_unlock - register access unlock
+ * @ks: The chip state
+ * @flags: Spinlock flags
+ *
+ * Release chip register access lock
+ */
+static void ks8851_unlock(struct ks8851_net *ks, unsigned long *flags)
+{
+       ks->unlock(ks, flags);
+}
+
 /* SPI register read/write calls.
  *
  * All these calls issue SPI transactions to access the chip's registers. They
@@ -159,17 +247,19 @@ static int msg_enable;
  */
 
 /**
- * ks8851_wrreg16 - write 16bit register value to chip
+ * ks8851_wrreg16_spi - write 16bit register value to chip via SPI
  * @ks: The chip state
  * @reg: The register address
  * @val: The value to write
  *
  * Issue a write to put the value @val into the register specified in @reg.
  */
-static void ks8851_wrreg16(struct ks8851_net *ks, unsigned reg, unsigned val)
+static void ks8851_wrreg16_spi(struct ks8851_net *ks, unsigned int reg,
+                              unsigned int val)
 {
-       struct spi_transfer *xfer = &ks->spi_xfer1;
-       struct spi_message *msg = &ks->spi_msg1;
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
+       struct spi_transfer *xfer = &kss->spi_xfer1;
+       struct spi_message *msg = &kss->spi_msg1;
        __le16 txb[2];
        int ret;
 
@@ -180,39 +270,23 @@ static void ks8851_wrreg16(struct ks8851_net *ks, unsigned reg, unsigned val)
        xfer->rx_buf = NULL;
        xfer->len = 4;
 
-       ret = spi_sync(ks->spidev, msg);
+       ret = spi_sync(kss->spidev, msg);
        if (ret < 0)
                netdev_err(ks->netdev, "spi_sync() failed\n");
 }
 
 /**
- * ks8851_wrreg8 - write 8bit register value to chip
+ * ks8851_wrreg16 - write 16bit register value to chip
  * @ks: The chip state
  * @reg: The register address
  * @val: The value to write
  *
  * Issue a write to put the value @val into the register specified in @reg.
  */
-static void ks8851_wrreg8(struct ks8851_net *ks, unsigned reg, unsigned val)
+static void ks8851_wrreg16(struct ks8851_net *ks, unsigned int reg,
+                          unsigned int val)
 {
-       struct spi_transfer *xfer = &ks->spi_xfer1;
-       struct spi_message *msg = &ks->spi_msg1;
-       __le16 txb[2];
-       int ret;
-       int bit;
-
-       bit = 1 << (reg & 3);
-
-       txb[0] = cpu_to_le16(MK_OP(bit, reg) | KS_SPIOP_WR);
-       txb[1] = val;
-
-       xfer->tx_buf = txb;
-       xfer->rx_buf = NULL;
-       xfer->len = 3;
-
-       ret = spi_sync(ks->spidev, msg);
-       if (ret < 0)
-               netdev_err(ks->netdev, "spi_sync() failed\n");
+       ks->wrreg16(ks, reg, val);
 }
 
 /**
@@ -228,6 +302,7 @@ static void ks8851_wrreg8(struct ks8851_net *ks, unsigned reg, unsigned val)
 static void ks8851_rdreg(struct ks8851_net *ks, unsigned op,
                         u8 *rxb, unsigned rxl)
 {
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
        struct spi_transfer *xfer;
        struct spi_message *msg;
        __le16 *txb = (__le16 *)ks->txd;
@@ -236,9 +311,9 @@ static void ks8851_rdreg(struct ks8851_net *ks, unsigned op,
 
        txb[0] = cpu_to_le16(op | KS_SPIOP_RD);
 
-       if (ks->spidev->master->flags & SPI_MASTER_HALF_DUPLEX) {
-               msg = &ks->spi_msg2;
-               xfer = ks->spi_xfer2;
+       if (kss->spidev->master->flags & SPI_MASTER_HALF_DUPLEX) {
+               msg = &kss->spi_msg2;
+               xfer = kss->spi_xfer2;
 
                xfer->tx_buf = txb;
                xfer->rx_buf = NULL;
@@ -249,46 +324,32 @@ static void ks8851_rdreg(struct ks8851_net *ks, unsigned op,
                xfer->rx_buf = trx;
                xfer->len = rxl;
        } else {
-               msg = &ks->spi_msg1;
-               xfer = &ks->spi_xfer1;
+               msg = &kss->spi_msg1;
+               xfer = &kss->spi_xfer1;
 
                xfer->tx_buf = txb;
                xfer->rx_buf = trx;
                xfer->len = rxl + 2;
        }
 
-       ret = spi_sync(ks->spidev, msg);
+       ret = spi_sync(kss->spidev, msg);
        if (ret < 0)
                netdev_err(ks->netdev, "read: spi_sync() failed\n");
-       else if (ks->spidev->master->flags & SPI_MASTER_HALF_DUPLEX)
+       else if (kss->spidev->master->flags & SPI_MASTER_HALF_DUPLEX)
                memcpy(rxb, trx, rxl);
        else
                memcpy(rxb, trx + 2, rxl);
 }
 
 /**
- * ks8851_rdreg8 - read 8 bit register from device
- * @ks: The chip information
- * @reg: The register address
- *
- * Read a 8bit register from the chip, returning the result
-*/
-static unsigned ks8851_rdreg8(struct ks8851_net *ks, unsigned reg)
-{
-       u8 rxb[1];
-
-       ks8851_rdreg(ks, MK_OP(1 << (reg & 3), reg), rxb, 1);
-       return rxb[0];
-}
-
-/**
- * ks8851_rdreg16 - read 16 bit register from device
+ * ks8851_rdreg16_spi - read 16 bit register from device via SPI
  * @ks: The chip information
  * @reg: The register address
  *
  * Read a 16bit register from the chip, returning the result
 */
-static unsigned ks8851_rdreg16(struct ks8851_net *ks, unsigned reg)
+static unsigned int ks8851_rdreg16_spi(struct ks8851_net *ks,
+                                      unsigned int reg)
 {
        __le16 rx = 0;
 
@@ -297,22 +358,16 @@ static unsigned ks8851_rdreg16(struct ks8851_net *ks, unsigned reg)
 }
 
 /**
- * ks8851_rdreg32 - read 32 bit register from device
+ * ks8851_rdreg16 - read 16 bit register from device
  * @ks: The chip information
  * @reg: The register address
  *
- * Read a 32bit register from the chip.
- *
- * Note, this read requires the address be aligned to 4 bytes.
-*/
-static unsigned ks8851_rdreg32(struct ks8851_net *ks, unsigned reg)
+ * Read a 16bit register from the chip, returning the result
+ */
+static unsigned int ks8851_rdreg16(struct ks8851_net *ks,
+                                  unsigned int reg)
 {
-       __le32 rx = 0;
-
-       WARN_ON(reg & 3);
-
-       ks8851_rdreg(ks, MK_OP(0xf, reg), (u8 *)&rx, 4);
-       return le32_to_cpu(rx);
+       return ks->rdreg16(ks, reg);
 }
 
 /**
@@ -368,21 +423,27 @@ static void ks8851_set_powermode(struct ks8851_net *ks, unsigned pwrmode)
 static int ks8851_write_mac_addr(struct net_device *dev)
 {
        struct ks8851_net *ks = netdev_priv(dev);
+       unsigned long flags;
+       u16 val;
        int i;
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
 
        /*
         * Wake up chip in case it was powered off when stopped; otherwise,
         * the first write to the MAC address does not take effect.
         */
        ks8851_set_powermode(ks, PMECR_PM_NORMAL);
-       for (i = 0; i < ETH_ALEN; i++)
-               ks8851_wrreg8(ks, KS_MAR(i), dev->dev_addr[i]);
+
+       for (i = 0; i < ETH_ALEN; i += 2) {
+               val = (dev->dev_addr[i] << 8) | dev->dev_addr[i + 1];
+               ks8851_wrreg16(ks, KS_MAR(i), val);
+       }
+
        if (!netif_running(dev))
                ks8851_set_powermode(ks, PMECR_PM_SOFTDOWN);
 
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 
        return 0;
 }
@@ -396,19 +457,25 @@ static int ks8851_write_mac_addr(struct net_device *dev)
 static void ks8851_read_mac_addr(struct net_device *dev)
 {
        struct ks8851_net *ks = netdev_priv(dev);
+       unsigned long flags;
+       u16 reg;
        int i;
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
 
-       for (i = 0; i < ETH_ALEN; i++)
-               dev->dev_addr[i] = ks8851_rdreg8(ks, KS_MAR(i));
+       for (i = 0; i < ETH_ALEN; i += 2) {
+               reg = ks8851_rdreg16(ks, KS_MAR(i));
+               dev->dev_addr[i] = reg >> 8;
+               dev->dev_addr[i + 1] = reg & 0xff;
+       }
 
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 }
 
 /**
  * ks8851_init_mac - initialise the mac address
  * @ks: The device structure
+ * @np: The device node pointer
  *
  * Get or create the initial mac address for the device and then set that
  * into the station address register. A mac address supplied in the device
@@ -416,12 +483,12 @@ static void ks8851_read_mac_addr(struct net_device *dev)
  * we try that. If no valid mac address is found we use eth_random_addr()
  * to create a new one.
  */
-static void ks8851_init_mac(struct ks8851_net *ks)
+static void ks8851_init_mac(struct ks8851_net *ks, struct device_node *np)
 {
        struct net_device *dev = ks->netdev;
        const u8 *mac_addr;
 
-       mac_addr = of_get_mac_address(ks->spidev->dev.of_node);
+       mac_addr = of_get_mac_address(np);
        if (!IS_ERR(mac_addr)) {
                ether_addr_copy(dev->dev_addr, mac_addr);
                ks8851_write_mac_addr(dev);
@@ -442,7 +509,7 @@ static void ks8851_init_mac(struct ks8851_net *ks)
 }
 
 /**
- * ks8851_rdfifo - read data from the receive fifo
+ * ks8851_rdfifo_spi - read data from the receive fifo via SPI
  * @ks: The device state.
  * @buff: The buffer address
  * @len: The length of the data to read
@@ -450,10 +517,12 @@ static void ks8851_init_mac(struct ks8851_net *ks)
  * Issue an RXQ FIFO read command and read the @len amount of data from
  * the FIFO into the buffer specified by @buff.
  */
-static void ks8851_rdfifo(struct ks8851_net *ks, u8 *buff, unsigned len)
+static void ks8851_rdfifo_spi(struct ks8851_net *ks, u8 *buff,
+                             unsigned int len)
 {
-       struct spi_transfer *xfer = ks->spi_xfer2;
-       struct spi_message *msg = &ks->spi_msg2;
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
+       struct spi_transfer *xfer = kss->spi_xfer2;
+       struct spi_message *msg = &kss->spi_msg2;
        u8 txb[1];
        int ret;
 
@@ -472,7 +541,7 @@ static void ks8851_rdfifo(struct ks8851_net *ks, u8 *buff, unsigned len)
        xfer->tx_buf = NULL;
        xfer->len = len;
 
-       ret = spi_sync(ks->spidev, msg);
+       ret = spi_sync(kss->spidev, msg);
        if (ret < 0)
                netdev_err(ks->netdev, "%s: spi_sync() failed\n", __func__);
 }
@@ -493,6 +562,26 @@ static void ks8851_dbg_dumpkkt(struct ks8851_net *ks, u8 *rxpkt)
                   rxpkt[12], rxpkt[13], rxpkt[14], rxpkt[15]);
 }
 
+/**
+ * ks8851_rx_skb_spi - receive skbuff for SPI
+ * @ks: The device state
+ * @skb: The skbuff
+ */
+static void ks8851_rx_skb_spi(struct ks8851_net *ks, struct sk_buff *skb)
+{
+       netif_rx_ni(skb);
+}
+
+/**
+ * ks8851_rx_skb - receive skbuff
+ * @ks: The device state
+ * @skb: The skbuff
+ */
+static void ks8851_rx_skb(struct ks8851_net *ks, struct sk_buff *skb)
+{
+       ks->rx_skb(ks, skb);
+}
+
 /**
  * ks8851_rx_pkts - receive packets from the host
  * @ks: The device information.
@@ -507,10 +596,9 @@ static void ks8851_rx_pkts(struct ks8851_net *ks)
        unsigned rxfc;
        unsigned rxlen;
        unsigned rxstat;
-       u32 rxh;
        u8 *rxpkt;
 
-       rxfc = ks8851_rdreg8(ks, KS_RXFC);
+       rxfc = (ks8851_rdreg16(ks, KS_RXFCTR) >> 8) & 0xff;
 
        netif_dbg(ks, rx_status, ks->netdev,
                  "%s: %d packets\n", __func__, rxfc);
@@ -526,9 +614,8 @@ static void ks8851_rx_pkts(struct ks8851_net *ks)
         */
 
        for (; rxfc != 0; rxfc--) {
-               rxh = ks8851_rdreg32(ks, KS_RXFHSR);
-               rxstat = rxh & 0xffff;
-               rxlen = (rxh >> 16) & 0xfff;
+               rxstat = ks8851_rdreg16(ks, KS_RXFHSR);
+               rxlen = ks8851_rdreg16(ks, KS_RXFHBCR) & RXFHBCR_CNT_MASK;
 
                netif_dbg(ks, rx_status, ks->netdev,
                          "rx: stat 0x%04x, len 0x%04x\n", rxstat, rxlen);
@@ -557,13 +644,13 @@ static void ks8851_rx_pkts(struct ks8851_net *ks)
 
                                rxpkt = skb_put(skb, rxlen) - 8;
 
-                               ks8851_rdfifo(ks, rxpkt, rxalign + 8);
+                               ks->rdfifo(ks, rxpkt, rxalign + 8);
 
                                if (netif_msg_pktdata(ks))
                                        ks8851_dbg_dumpkkt(ks, rxpkt);
 
                                skb->protocol = eth_type_trans(skb, ks->netdev);
-                               netif_rx_ni(skb);
+                               ks8851_rx_skb(ks, skb);
 
                                ks->netdev->stats.rx_packets++;
                                ks->netdev->stats.rx_bytes += rxlen;
@@ -590,10 +677,11 @@ static void ks8851_rx_pkts(struct ks8851_net *ks)
 static irqreturn_t ks8851_irq(int irq, void *_ks)
 {
        struct ks8851_net *ks = _ks;
-       unsigned status;
        unsigned handled = 0;
+       unsigned long flags;
+       unsigned int status;
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
 
        status = ks8851_rdreg16(ks, KS_ISR);
 
@@ -662,7 +750,7 @@ static irqreturn_t ks8851_irq(int irq, void *_ks)
                ks8851_wrreg16(ks, KS_RXCR1, rxc->rxcr1);
        }
 
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 
        if (status & IRQ_LCI)
                mii_check_link(&ks->mii);
@@ -686,7 +774,7 @@ static inline unsigned calc_txlen(unsigned len)
 }
 
 /**
- * ks8851_wrpkt - write packet to TX FIFO
+ * ks8851_wrpkt_spi - write packet to TX FIFO via SPI
  * @ks: The device state.
  * @txp: The sk_buff to transmit.
  * @irq: IRQ on completion of the packet.
@@ -696,10 +784,12 @@ static inline unsigned calc_txlen(unsigned len)
  * needs, such as IRQ on completion. Send the header and the packet data to
  * the device.
  */
-static void ks8851_wrpkt(struct ks8851_net *ks, struct sk_buff *txp, bool irq)
+static void ks8851_wrpkt_spi(struct ks8851_net *ks, struct sk_buff *txp,
+                            bool irq)
 {
-       struct spi_transfer *xfer = ks->spi_xfer2;
-       struct spi_message *msg = &ks->spi_msg2;
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
+       struct spi_transfer *xfer = kss->spi_xfer2;
+       struct spi_message *msg = &kss->spi_msg2;
        unsigned fid = 0;
        int ret;
 
@@ -726,7 +816,7 @@ static void ks8851_wrpkt(struct ks8851_net *ks, struct sk_buff *txp, bool irq)
        xfer->rx_buf = NULL;
        xfer->len = ALIGN(txp->len, 4);
 
-       ret = spi_sync(ks->spidev, msg);
+       ret = spi_sync(kss->spidev, msg);
        if (ret < 0)
                netdev_err(ks->netdev, "%s: spi_sync() failed\n", __func__);
 }
@@ -755,11 +845,17 @@ static void ks8851_done_tx(struct ks8851_net *ks, struct sk_buff *txb)
  */
 static void ks8851_tx_work(struct work_struct *work)
 {
-       struct ks8851_net *ks = container_of(work, struct ks8851_net, tx_work);
+       struct ks8851_net_spi *kss;
+       struct ks8851_net *ks;
+       unsigned long flags;
        struct sk_buff *txb;
-       bool last = skb_queue_empty(&ks->txq);
+       bool last;
+
+       kss = container_of(work, struct ks8851_net_spi, tx_work);
+       ks = &kss->ks8851;
+       last = skb_queue_empty(&ks->txq);
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
 
        while (!last) {
                txb = skb_dequeue(&ks->txq);
@@ -767,7 +863,7 @@ static void ks8851_tx_work(struct work_struct *work)
 
                if (txb != NULL) {
                        ks8851_wrreg16(ks, KS_RXQCR, ks->rc_rxqcr | RXQCR_SDA);
-                       ks8851_wrpkt(ks, txb, last);
+                       ks->wrfifo(ks, txb, last);
                        ks8851_wrreg16(ks, KS_RXQCR, ks->rc_rxqcr);
                        ks8851_wrreg16(ks, KS_TXQCR, TXQCR_METFE);
 
@@ -775,7 +871,28 @@ static void ks8851_tx_work(struct work_struct *work)
                }
        }
 
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
+}
+
+/**
+ * ks8851_flush_tx_work_spi - flush outstanding TX work for SPI
+ * @ks: The device state
+ */
+static void ks8851_flush_tx_work_spi(struct ks8851_net *ks)
+{
+       struct ks8851_net_spi *kss = to_ks8851_spi(ks);
+
+       flush_work(&kss->tx_work);
+}
+
+/**
+ * ks8851_flush_tx_work - flush outstanding TX work
+ * @ks: The device state
+ */
+static void ks8851_flush_tx_work(struct ks8851_net *ks)
+{
+       if (ks->flush_tx_work)
+               ks->flush_tx_work(ks);
 }
 
 /**
@@ -788,6 +905,7 @@ static void ks8851_tx_work(struct work_struct *work)
 static int ks8851_net_open(struct net_device *dev)
 {
        struct ks8851_net *ks = netdev_priv(dev);
+       unsigned long flags;
        int ret;
 
        ret = request_threaded_irq(dev->irq, NULL, ks8851_irq,
@@ -800,7 +918,7 @@ static int ks8851_net_open(struct net_device *dev)
 
        /* lock the card, even if we may not actually be doing anything
         * else at the moment */
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
 
        netif_dbg(ks, ifup, ks->netdev, "opening\n");
 
@@ -844,23 +962,14 @@ static int ks8851_net_open(struct net_device *dev)
        ks8851_wrreg16(ks, KS_RXQCR, ks->rc_rxqcr);
 
        /* clear then enable interrupts */
-
-#define STD_IRQ (IRQ_LCI |     /* Link Change */       \
-                IRQ_TXI |      /* TX done */           \
-                IRQ_RXI |      /* RX done */           \
-                IRQ_SPIBEI |   /* SPI bus error */     \
-                IRQ_TXPSI |    /* TX process stop */   \
-                IRQ_RXPSI)     /* RX process stop */
-
-       ks->rc_ier = STD_IRQ;
-       ks8851_wrreg16(ks, KS_ISR, STD_IRQ);
-       ks8851_wrreg16(ks, KS_IER, STD_IRQ);
+       ks8851_wrreg16(ks, KS_ISR, ks->rc_ier);
+       ks8851_wrreg16(ks, KS_IER, ks->rc_ier);
 
        netif_start_queue(ks->netdev);
 
        netif_dbg(ks, ifup, ks->netdev, "network device up\n");
 
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
        mii_check_link(&ks->mii);
        return 0;
 }
@@ -876,22 +985,23 @@ static int ks8851_net_open(struct net_device *dev)
 static int ks8851_net_stop(struct net_device *dev)
 {
        struct ks8851_net *ks = netdev_priv(dev);
+       unsigned long flags;
 
        netif_info(ks, ifdown, dev, "shutting down\n");
 
        netif_stop_queue(dev);
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
        /* turn off the IRQs and ack any outstanding */
        ks8851_wrreg16(ks, KS_IER, 0x0000);
        ks8851_wrreg16(ks, KS_ISR, 0xffff);
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 
        /* stop any outstanding work */
-       flush_work(&ks->tx_work);
+       ks8851_flush_tx_work(ks);
        flush_work(&ks->rxctrl_work);
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
        /* shutdown RX process */
        ks8851_wrreg16(ks, KS_RXCR1, 0x0000);
 
@@ -900,7 +1010,7 @@ static int ks8851_net_stop(struct net_device *dev)
 
        /* set powermode to soft power down to save power */
        ks8851_set_powermode(ks, PMECR_PM_SOFTDOWN);
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 
        /* ensure any queued tx buffers are dumped */
        while (!skb_queue_empty(&ks->txq)) {
@@ -918,7 +1028,7 @@ static int ks8851_net_stop(struct net_device *dev)
 }
 
 /**
- * ks8851_start_xmit - transmit packet
+ * ks8851_start_xmit_spi - transmit packet using SPI
  * @skb: The buffer to transmit
  * @dev: The device used to transmit the packet.
  *
@@ -930,12 +1040,15 @@ static int ks8851_net_stop(struct net_device *dev)
  * and secondly so we can round up more than one packet to transmit which
  * means we can try and avoid generating too many transmit done interrupts.
  */
-static netdev_tx_t ks8851_start_xmit(struct sk_buff *skb,
-                                    struct net_device *dev)
+static netdev_tx_t ks8851_start_xmit_spi(struct sk_buff *skb,
+                                        struct net_device *dev)
 {
        struct ks8851_net *ks = netdev_priv(dev);
        unsigned needed = calc_txlen(skb->len);
        netdev_tx_t ret = NETDEV_TX_OK;
+       struct ks8851_net_spi *kss;
+
+       kss = to_ks8851_spi(ks);
 
        netif_dbg(ks, tx_queued, ks->netdev,
                  "%s: skb %p, %d@%p\n", __func__, skb, skb->len, skb->data);
@@ -951,11 +1064,32 @@ static netdev_tx_t ks8851_start_xmit(struct sk_buff *skb,
        }
 
        spin_unlock(&ks->statelock);
-       schedule_work(&ks->tx_work);
+       schedule_work(&kss->tx_work);
 
        return ret;
 }
 
+/**
+ * ks8851_start_xmit - transmit packet
+ * @skb: The buffer to transmit
+ * @dev: The device used to transmit the packet.
+ *
+ * Called by the network layer to transmit the @skb. Queue the packet for
+ * the device and schedule the necessary work to transmit the packet when
+ * it is free.
+ *
+ * We do this to firstly avoid sleeping with the network device locked,
+ * and secondly so we can round up more than one packet to transmit which
+ * means we can try and avoid generating too many transmit done interrupts.
+ */
+static netdev_tx_t ks8851_start_xmit(struct sk_buff *skb,
+                                    struct net_device *dev)
+{
+       struct ks8851_net *ks = netdev_priv(dev);
+
+       return ks->start_xmit(skb, dev);
+}
+
 /**
  * ks8851_rxctrl_work - work handler to change rx mode
  * @work: The work structure this belongs to.
@@ -972,13 +1106,14 @@ static netdev_tx_t ks8851_start_xmit(struct sk_buff *skb,
 static void ks8851_rxctrl_work(struct work_struct *work)
 {
        struct ks8851_net *ks = container_of(work, struct ks8851_net, rxctrl_work);
+       unsigned long flags;
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
 
        /* need to shutdown RXQ before modifying filter parameters */
        ks8851_wrreg16(ks, KS_RXCR1, 0x00);
 
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 }
 
 static void ks8851_set_rx_mode(struct net_device *dev)
@@ -1160,11 +1295,6 @@ static void ks8851_eeprom_regwrite(struct eeprom_93cx6 *ee)
  */
 static int ks8851_eeprom_claim(struct ks8851_net *ks)
 {
-       if (!(ks->rc_ccr & CCR_EEPROM))
-               return -ENOENT;
-
-       mutex_lock(&ks->lock);
-
        /* start with clock low, cs high */
        ks8851_wrreg16(ks, KS_EEPCR, EEPCR_EESA | EEPCR_EECS);
        return 0;
@@ -1181,7 +1311,6 @@ static void ks8851_eeprom_release(struct ks8851_net *ks)
        unsigned val = ks8851_rdreg16(ks, KS_EEPCR);
 
        ks8851_wrreg16(ks, KS_EEPCR, val & ~EEPCR_EESA);
-       mutex_unlock(&ks->lock);
 }
 
 #define KS_EEPROM_MAGIC (0x00008851)
@@ -1191,6 +1320,7 @@ static int ks8851_set_eeprom(struct net_device *dev,
 {
        struct ks8851_net *ks = netdev_priv(dev);
        int offset = ee->offset;
+       unsigned long flags;
        int len = ee->len;
        u16 tmp;
 
@@ -1201,9 +1331,13 @@ static int ks8851_set_eeprom(struct net_device *dev,
        if (ee->magic != KS_EEPROM_MAGIC)
                return -EINVAL;
 
-       if (ks8851_eeprom_claim(ks))
+       if (!(ks->rc_ccr & CCR_EEPROM))
                return -ENOENT;
 
+       ks8851_lock(ks, &flags);
+
+       ks8851_eeprom_claim(ks);
+
        eeprom_93cx6_wren(&ks->eeprom, true);
 
        /* ethtool currently only supports writing bytes, which means
@@ -1223,6 +1357,7 @@ static int ks8851_set_eeprom(struct net_device *dev,
        eeprom_93cx6_wren(&ks->eeprom, false);
 
        ks8851_eeprom_release(ks);
+       ks8851_unlock(ks, &flags);
 
        return 0;
 }
@@ -1232,19 +1367,25 @@ static int ks8851_get_eeprom(struct net_device *dev,
 {
        struct ks8851_net *ks = netdev_priv(dev);
        int offset = ee->offset;
+       unsigned long flags;
        int len = ee->len;
 
        /* must be 2 byte aligned */
        if (len & 1 || offset & 1)
                return -EINVAL;
 
-       if (ks8851_eeprom_claim(ks))
+       if (!(ks->rc_ccr & CCR_EEPROM))
                return -ENOENT;
 
+       ks8851_lock(ks, &flags);
+
+       ks8851_eeprom_claim(ks);
+
        ee->magic = KS_EEPROM_MAGIC;
 
        eeprom_93cx6_multiread(&ks->eeprom, offset/2, (__le16 *)data, len/2);
        ks8851_eeprom_release(ks);
+       ks8851_unlock(ks, &flags);
 
        return 0;
 }
@@ -1318,6 +1459,7 @@ static int ks8851_phy_reg(int reg)
 static int ks8851_phy_read(struct net_device *dev, int phy_addr, int reg)
 {
        struct ks8851_net *ks = netdev_priv(dev);
+       unsigned long flags;
        int ksreg;
        int result;
 
@@ -1325,9 +1467,9 @@ static int ks8851_phy_read(struct net_device *dev, int phy_addr, int reg)
        if (!ksreg)
                return 0x0;     /* no error return allowed, so use zero */
 
-       mutex_lock(&ks->lock);
+       ks8851_lock(ks, &flags);
        result = ks8851_rdreg16(ks, ksreg);
-       mutex_unlock(&ks->lock);
+       ks8851_unlock(ks, &flags);
 
        return result;
 }
@@ -1336,13 +1478,14 @@ static void ks8851_phy_write(struct net_device *dev,
                             int phy, int reg, int value)
 {
        struct ks8851_net *ks = netdev_priv(dev);
+       unsigned long flags;
        int ksreg;
 
        ksreg = ks8851_phy_reg(reg);
        if (ksreg) {
-               mutex_lock(&ks->lock);
+               ks8851_lock(ks, &flags);
                ks8851_wrreg16(ks, ksreg, value);
-               mutex_unlock(&ks->lock);
+               ks8851_unlock(ks, &flags);
        }
 }
 
@@ -1411,32 +1554,20 @@ static int ks8851_resume(struct device *dev)
 
 static SIMPLE_DEV_PM_OPS(ks8851_pm_ops, ks8851_suspend, ks8851_resume);
 
-static int ks8851_probe(struct spi_device *spi)
+static int ks8851_probe_common(struct net_device *netdev, struct device *dev,
+                              int msg_en)
 {
-       struct device *dev = &spi->dev;
-       struct net_device *netdev;
-       struct ks8851_net *ks;
-       int ret;
+       struct ks8851_net *ks = netdev_priv(netdev);
        unsigned cider;
        int gpio;
-
-       netdev = alloc_etherdev(sizeof(struct ks8851_net));
-       if (!netdev)
-               return -ENOMEM;
-
-       spi->bits_per_word = 8;
-
-       ks = netdev_priv(netdev);
+       int ret;
 
        ks->netdev = netdev;
-       ks->spidev = spi;
        ks->tx_space = 6144;
 
        gpio = of_get_named_gpio_flags(dev->of_node, "reset-gpios", 0, NULL);
-       if (gpio == -EPROBE_DEFER) {
-               ret = gpio;
-               goto err_gpio;
-       }
+       if (gpio == -EPROBE_DEFER)
+               return gpio;
 
        ks->gpio = gpio;
        if (gpio_is_valid(gpio)) {
@@ -1444,7 +1575,7 @@ static int ks8851_probe(struct spi_device *spi)
                                            GPIOF_OUT_INIT_LOW, "ks8851_rst_n");
                if (ret) {
                        dev_err(dev, "reset gpio request failed\n");
-                       goto err_gpio;
+                       return ret;
                }
        }
 
@@ -1477,23 +1608,11 @@ static int ks8851_probe(struct spi_device *spi)
                gpio_set_value(gpio, 1);
        }
 
-       mutex_init(&ks->lock);
        spin_lock_init(&ks->statelock);
 
-       INIT_WORK(&ks->tx_work, ks8851_tx_work);
        INIT_WORK(&ks->rxctrl_work, ks8851_rxctrl_work);
 
-       /* initialise pre-made spi transfer messages */
-
-       spi_message_init(&ks->spi_msg1);
-       spi_message_add_tail(&ks->spi_xfer1, &ks->spi_msg1);
-
-       spi_message_init(&ks->spi_msg2);
-       spi_message_add_tail(&ks->spi_xfer2[0], &ks->spi_msg2);
-       spi_message_add_tail(&ks->spi_xfer2[1], &ks->spi_msg2);
-
        /* setup EEPROM state */
-
        ks->eeprom.data = ks;
        ks->eeprom.width = PCI_EEPROM_WIDTH_93C46;
        ks->eeprom.register_read = ks8851_eeprom_regread;
@@ -1507,24 +1626,23 @@ static int ks8851_probe(struct spi_device *spi)
        ks->mii.mdio_read       = ks8851_phy_read;
        ks->mii.mdio_write      = ks8851_phy_write;
 
-       dev_info(dev, "message enable is %d\n", msg_enable);
+       dev_info(dev, "message enable is %d\n", msg_en);
 
        /* set the default message enable */
-       ks->msg_enable = netif_msg_init(msg_enable, (NETIF_MSG_DRV |
-                                                    NETIF_MSG_PROBE |
-                                                    NETIF_MSG_LINK));
+       ks->msg_enable = netif_msg_init(msg_enNETIF_MSG_DRV |
+                                               NETIF_MSG_PROBE |
+                                               NETIF_MSG_LINK);
 
        skb_queue_head_init(&ks->txq);
 
        netdev->ethtool_ops = &ks8851_ethtool_ops;
        SET_NETDEV_DEV(netdev, dev);
 
-       spi_set_drvdata(spi, ks);
+       dev_set_drvdata(dev, ks);
 
        netif_carrier_off(ks->netdev);
        netdev->if_port = IF_PORT_100BASET;
        netdev->netdev_ops = &ks8851_netdev_ops;
-       netdev->irq = spi->irq;
 
        /* issue a global soft reset to reset the device. */
        ks8851_soft_reset(ks, GRR_GSR);
@@ -1541,7 +1659,7 @@ static int ks8851_probe(struct spi_device *spi)
        ks->rc_ccr = ks8851_rdreg16(ks, KS_CCR);
 
        ks8851_read_selftest(ks);
-       ks8851_init_mac(ks);
+       ks8851_init_mac(ks, dev->of_node);
 
        ret = register_netdev(netdev);
        if (ret) {
@@ -1563,15 +1681,12 @@ err_id:
 err_reg:
        regulator_disable(ks->vdd_io);
 err_reg_io:
-err_gpio:
-       free_netdev(netdev);
        return ret;
 }
 
-static int ks8851_remove(struct spi_device *spi)
+static int ks8851_remove_common(struct device *dev)
 {
-       struct ks8851_net *priv = spi_get_drvdata(spi);
-       struct device *dev = &spi->dev;
+       struct ks8851_net *priv = dev_get_drvdata(dev);
 
        if (netif_msg_drv(priv))
                dev_info(dev, "remove\n");
@@ -1581,11 +1696,67 @@ static int ks8851_remove(struct spi_device *spi)
                gpio_set_value(priv->gpio, 0);
        regulator_disable(priv->vdd_reg);
        regulator_disable(priv->vdd_io);
-       free_netdev(priv->netdev);
 
        return 0;
 }
 
+static int ks8851_probe(struct spi_device *spi)
+{
+       struct device *dev = &spi->dev;
+       struct ks8851_net_spi *kss;
+       struct net_device *netdev;
+       struct ks8851_net *ks;
+
+       netdev = devm_alloc_etherdev(dev, sizeof(struct ks8851_net_spi));
+       if (!netdev)
+               return -ENOMEM;
+
+       spi->bits_per_word = 8;
+
+       ks = netdev_priv(netdev);
+
+       ks->lock = ks8851_lock_spi;
+       ks->unlock = ks8851_unlock_spi;
+       ks->rdreg16 = ks8851_rdreg16_spi;
+       ks->wrreg16 = ks8851_wrreg16_spi;
+       ks->rdfifo = ks8851_rdfifo_spi;
+       ks->wrfifo = ks8851_wrpkt_spi;
+       ks->start_xmit = ks8851_start_xmit_spi;
+       ks->rx_skb = ks8851_rx_skb_spi;
+       ks->flush_tx_work = ks8851_flush_tx_work_spi;
+
+#define STD_IRQ (IRQ_LCI |     /* Link Change */       \
+                IRQ_TXI |      /* TX done */           \
+                IRQ_RXI |      /* RX done */           \
+                IRQ_SPIBEI |   /* SPI bus error */     \
+                IRQ_TXPSI |    /* TX process stop */   \
+                IRQ_RXPSI)     /* RX process stop */
+       ks->rc_ier = STD_IRQ;
+
+       kss = to_ks8851_spi(ks);
+
+       kss->spidev = spi;
+       mutex_init(&kss->lock);
+       INIT_WORK(&kss->tx_work, ks8851_tx_work);
+
+       /* initialise pre-made spi transfer messages */
+       spi_message_init(&kss->spi_msg1);
+       spi_message_add_tail(&kss->spi_xfer1, &kss->spi_msg1);
+
+       spi_message_init(&kss->spi_msg2);
+       spi_message_add_tail(&kss->spi_xfer2[0], &kss->spi_msg2);
+       spi_message_add_tail(&kss->spi_xfer2[1], &kss->spi_msg2);
+
+       netdev->irq = spi->irq;
+
+       return ks8851_probe_common(netdev, dev, msg_enable);
+}
+
+static int ks8851_remove(struct spi_device *spi)
+{
+       return ks8851_remove_common(&spi->dev);
+}
+
 static const struct of_device_id ks8851_match_table[] = {
        { .compatible = "micrel,ks8851" },
        { }