[PATCH rtems 02/18] first version with mv643xx eth driver broken into pieces which compiles

Vijay Kumar Banerjee vijay at rtems.org
Tue Mar 30 01:27:34 UTC 2021


From: till straumann <till.straumann at alumni.tu-berlin.de>

Update #4344
---
 .../powerpc/beatnik/include/bsp/mv643xx_eth.h |   85 +-
 bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c |  343 ++-
 .../beatnik/net/if_mve/mv643xx_eth_bsdnet.c   | 2601 ++---------------
 3 files changed, 575 insertions(+), 2454 deletions(-)

diff --git a/bsps/powerpc/beatnik/include/bsp/mv643xx_eth.h b/bsps/powerpc/beatnik/include/bsp/mv643xx_eth.h
index eefca62603..f963b91d3d 100644
--- a/bsps/powerpc/beatnik/include/bsp/mv643xx_eth.h
+++ b/bsps/powerpc/beatnik/include/bsp/mv643xx_eth.h
@@ -3,24 +3,11 @@
 
 struct mveth_private;
 
-/* Clear multicast filters                        */
-void
-BSP_mve_mcast_filter_clear(struct mveth_private *mp);
-void
-BSP_mve_mcast_filter_accept_all(struct mveth_private *mp);
-void
-BSP_mve_mcast_filter_accept_add(struct mveth_private *mp, unsigned char *enaddr);
-void
-BSP_mve_mcast_filter_accept_del(struct mveth_private *mp, unsigned char *enaddr);
-/* Stop hardware and clean out the rings */
-void
-BSP_mve_stop_hw(struct mveth_private *mp);
-
 struct mveth_private *
-BSP_mve_setup_1(
-	struct mveth_private*,
+BSP_mve_create(
 	int		 unit,
-	void     (*isr)(void *isr_arg),
+	rtems_id tid,
+	void     (*isr)(void*isr_arg),
 	void     *isr_arg,
 	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
 	void *cleanup_txbuf_arg,
@@ -32,6 +19,23 @@ BSP_mve_setup_1(
 	int		irq_mask
 );
 
+/* Enable/disable promiscuous mode */
+void
+BSP_mve_promisc_set(struct mveth_private *mp, int promisc);
+
+/* Clear multicast filters                        */
+void
+BSP_mve_mcast_filter_clear(struct mveth_private *mp);
+void
+BSP_mve_mcast_filter_accept_all(struct mveth_private *mp);
+void
+BSP_mve_mcast_filter_accept_add(struct mveth_private *mp, unsigned char *enaddr);
+void
+BSP_mve_mcast_filter_accept_del(struct mveth_private *mp, unsigned char *enaddr);
+/* Stop hardware and clean out the rings */
+void
+BSP_mve_stop_hw(struct mveth_private *mp);
+
 /* MAIN RX-TX ROUTINES
  *
  * BSP_mve_swipe_tx():  descriptor scavenger; releases mbufs
@@ -44,6 +48,33 @@ BSP_mve_setup_1(
 /* clean up the TX ring freeing up buffers */
 int
 BSP_mve_swipe_tx(struct mveth_private *mp);
+
+/* Enqueue a mbuf chain or a raw data buffer for transmission;
+ * RETURN: #bytes sent or -1 if there are not enough descriptors
+ *         -2 is returned if the caller should attempt to
+ *         repackage the chain into a smaller one.
+ *
+ * Comments: software cache-flushing incurs a penalty if the
+ *           packet cannot be queued since it is flushed anyways.
+ *           The algorithm is slightly more efficient in the normal
+ *			 case, though.
+ */
+
+typedef struct MveEthBufIter {
+	void  *hdl;    /* opaque handle for the iterator implementor */
+	void  *data;   /* data to be sent                            */
+	size_t len;    /* data size (in octets)                      */
+	void  *uptr;   /* user-pointer to go into the descriptor;
+                      note: cleanup_txbuf is only called for desriptors
+	                        where this field is non-NULL (for historical
+	                        reasons)                             */
+} MveEthBufIter;
+
+typedef MveEthBufIter *(*MveEthBufIterNext)(const MveEthBufIter*);
+
+int
+BSP_mve_send_buf_chain(struct mveth_private *mp, MveEthBufIterNext next, MveEthBufIter *it);
+
 int
 BSP_mve_send_buf_raw(
 	struct mveth_private *mp,
@@ -51,6 +82,7 @@ BSP_mve_send_buf_raw(
 	int                   h_len,
 	void                 *data_p,
     int                   d_len);
+
 /* send received buffers upwards and replace them
  * with freshly allocated ones;
  * ASSUMPTION:	buffer length NEVER changes and is set
@@ -82,6 +114,14 @@ BSP_mve_detach(struct mveth_private *mp);
 void
 BSP_mve_init_hw(struct mveth_private *mp, int promisc, unsigned char *enaddr);
 
+#define MV643XX_MEDIA_FD   (1<<0)
+#define MV643XX_MEDIA_10   (1<<8)
+#define MV643XX_MEDIA_100  (2<<8)
+#define MV643XX_MEDIA_1000 (3<<8)
+#define MV643XX_MEDIA_SPEED_MSK (0xff00)
+void
+BSP_mve_update_serial_port(struct mveth_private *mp, int media);
+
 /* read ethernet address from hw to buffer */
 void
 BSP_mve_read_eaddr(struct mveth_private *mp, unsigned char *oeaddr);
@@ -90,12 +130,19 @@ void
 BSP_mve_enable_irqs(struct mveth_private *mp);
 void
 BSP_mve_disable_irqs(struct mveth_private *mp);
+
+#define MV643XX_ETH_IRQ_RX_DONE						(1<<2)
+#define MV643XX_ETH_EXT_IRQ_TX_DONE					(1<<0)
+#define MV643XX_ETH_EXT_IRQ_LINK_CHG				(1<<16)
 uint32_t
 BSP_mve_ack_irqs(struct mveth_private *mp);
+
 void
 BSP_mve_enable_irq_mask(struct mveth_private *mp, uint32_t mask);
+
 uint32_t
 BSP_mve_disable_irq_mask(struct mveth_private *mp, uint32_t mask);
+
 uint32_t
 BSP_mve_ack_irq_mask(struct mveth_private *mp, uint32_t mask);
 
@@ -108,4 +155,10 @@ BSP_mve_mii_read(struct mveth_private *mp, unsigned addr);
 unsigned
 BSP_mve_mii_write(struct mveth_private *mp, unsigned addr, unsigned v);
 
+unsigned
+BSP_mve_mii_read_early(int port, unsigned addr);
+
+unsigned
+BSP_mve_mii_write_early(int port, unsigned addr, unsigned v);
+
 #endif
diff --git a/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c b/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c
index d002fd52ce..26fe7db9e6 100644
--- a/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c
+++ b/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c
@@ -94,6 +94,7 @@
 #include <stdio.h>
 #include <errno.h>
 #include <inttypes.h>
+#include <stdlib.h>
 
 #include <bsp/mv643xx_eth.h>
 
@@ -748,17 +749,6 @@ struct mveth_private {
 };
 
 /* GLOBAL VARIABLES */
-#ifdef MVETH_DEBUG_TX_DUMP
-int mveth_tx_dump = 0;
-#endif
-
-/* register access protection mutex */
-STATIC rtems_id mveth_mtx = 0;
-#define REGLOCK()	do { \
-		if ( RTEMS_SUCCESSFUL != rtems_semaphore_obtain(mveth_mtx, RTEMS_WAIT, RTEMS_NO_TIMEOUT) ) \
-			rtems_panic(DRVNAME": unable to lock register protection mutex"); \
-		} while (0)
-#define REGUNLOCK()	rtems_semaphore_release(mveth_mtx)
 
 /* Format strings for statistics messages */
 static const char *mibfmt[] = {
@@ -1059,6 +1049,14 @@ uint32_t	x;
 	MV_WRITE(MV643XX_ETH_MAC_ADDR_LO(mp->port_num), x);
 }
 
+static inline int
+port2phy(int port)
+{
+	port &= 0x1f;
+	/* during early init we may not know the phy and we are given a port number instead! */
+	return  ( (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*port)) & 0x1f );
+}
+
 /* PHY/MII Interface
  *
  * Read/write a PHY register;
@@ -1068,8 +1066,8 @@ uint32_t	x;
  *       If non-bsd drivers are running on a subset of IFs proper
  *       locking of all shared registers must be implemented!
  */
-unsigned
-BSP_mve_mii_read(struct mveth_private *mp, unsigned addr)
+static unsigned
+do_mii_read(int phy, unsigned addr)
 {
 unsigned v;
 unsigned wc = 0;
@@ -1082,7 +1080,7 @@ unsigned wc = 0;
 		wc++;
 	} while ( MV643XX_ETH_SMI_BUSY & v );
 
-	MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (mp->phy<<16) | MV643XX_ETH_SMI_OP_RD );
+	MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (phy<<16) | MV643XX_ETH_SMI_OP_RD );
 
 	do {
 		v = MV_READ(MV643XX_ETH_SMI_R);
@@ -1095,7 +1093,19 @@ unsigned wc = 0;
 }
 
 unsigned
-BSP_mve_mii_write(struct mveth_private *mp, unsigned addr, unsigned v)
+BSP_mve_mii_read(struct mveth_private *mp, unsigned addr)
+{
+	return do_mii_read(mp->phy, addr);
+}
+
+unsigned
+BSP_mve_mii_read_early(int port, unsigned addr)
+{
+	return do_mii_read(port2phy(port), addr);
+}
+
+static unsigned
+do_mii_write(int phy, unsigned addr, unsigned v)
 {
 unsigned wc = 0;
 
@@ -1110,11 +1120,24 @@ unsigned wc = 0;
 	while ( MV643XX_ETH_SMI_BUSY & MV_READ(MV643XX_ETH_SMI_R) )
 		wc++ /* wait */;
 
-	MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (mp->phy<<16) | MV643XX_ETH_SMI_OP_WR | v );
+	MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (phy<<16) | MV643XX_ETH_SMI_OP_WR | v );
 
 	return wc;
 }
 
+unsigned
+BSP_mve_mii_write(struct mveth_private *mp, unsigned addr, unsigned v)
+{
+	return do_mii_write( mp->phy, addr, v );
+}
+
+unsigned
+BSP_mve_mii_write_early(int port, unsigned addr, unsigned v)
+{
+	return do_mii_write(port2phy(port), addr, v);
+}
+
+
 /* MID-LAYER SUPPORT ROUTINES */
 
 /* Start TX if descriptors are exhausted */
@@ -1151,6 +1174,19 @@ uint32_t active_q;
 	return active_q;
 }
 
+void
+BSP_mve_promisc_set(struct mveth_private *mp, int promisc)
+{
+uint32_t              v;
+
+	v = MV_READ(MV643XX_ETH_PORT_CONFIG_R(mp->port_num));
+	if ( (mp->promisc = promisc) )
+		v |= MV643XX_ETH_UNICAST_PROMISC_MODE;
+	else
+		v &= ~MV643XX_ETH_UNICAST_PROMISC_MODE;
+	MV_WRITE(MV643XX_ETH_PORT_CONFIG_R(mp->port_num), v);
+}
+
 /* update serial port settings from current link status */
 
 void
@@ -1367,7 +1403,7 @@ register uint8_t *d = to, *s = fro;
 #endif
 
 static int
-mveth_assign_desc_raw(MvEthTxDesc d, void *buf, int len, unsigned long extra)
+mveth_assign_desc_raw(MvEthTxDesc d, void *buf, int len, void *uptr, unsigned long extra)
 {
 int rval = (d->byte_cnt = len);
 
@@ -1389,6 +1425,7 @@ int rval = (d->byte_cnt = len);
 	{
 		d->buf_ptr  = CPUADDR2ENET( (unsigned long)buf );
 	}
+	d->u_buf    = uptr;
 	d->l4i_chk  = 0;
 	return rval;
 }
@@ -1477,9 +1514,8 @@ MvEthTxDesc d;
 
 /* PUBLIC LOW-LEVEL DRIVER ACCESS */
 
-static struct mveth_private *
-mve_setup_internal(
-	struct mveth_private *mp,
+struct mveth_private *
+BSP_mve_create(
 	int		 unit,
 	rtems_id tid,
 	void     (*isr)(void*isr_arg),
@@ -1493,8 +1529,8 @@ mve_setup_internal(
 	int		tx_ring_size,
 	int		irq_mask
 )
-
 {
+struct mveth_private *mp;
 int                  InstallISRSuccessful;
 
 	if ( unit <= 0 || unit > MV643XXETH_NUM_DRIVER_SLOTS ) {
@@ -1510,25 +1546,20 @@ int                  InstallISRSuccessful;
 		return 0;
 	}
 
-	/* lazy init of mutex (non thread-safe! - we assume 1st initialization is single-threaded) */
-	if ( ! mveth_mtx ) {
-		rtems_status_code sc;
-		sc = rtems_semaphore_create(
-				rtems_build_name('m','v','e','X'),
-				1,
-				RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY | RTEMS_DEFAULT_ATTRIBUTES,
-				0,
-				&mveth_mtx);
-		if ( RTEMS_SUCCESSFUL != sc ) {
-			rtems_error(sc,DRVNAME": creating mutex\n");
-			rtems_panic("unable to proceed\n");
-		}
+	if ( tx_ring_size < 1 ) {
+		printk(DRVNAME": tx ring size must not be zero (networking configuration issue?)\n");
+		return 0;
 	}
 
-	memset(mp, 0, sizeof(*mp));
+	if ( rx_ring_size < 1 ) {
+		printk(DRVNAME": rx ring size must not be zero (networking configuration issue?)\n");
+		return 0;
+	}
+
+	mp = calloc( 1, sizeof *mp );
 
 	mp->port_num          = unit-1;
-	mp->phy               = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*mp->port_num)) & 0x1f;
+	mp->phy               = port2phy(mp->port_num);
 
 	mp->tid               = tid;
 	mp->isr               = isr;
@@ -1540,8 +1571,8 @@ int                  InstallISRSuccessful;
 	mp->consume_rxbuf     = consume_rxbuf;
 	mp->consume_rxbuf_arg = consume_rxbuf_arg;
 
-	mp->rbuf_count = rx_ring_size ? rx_ring_size : MV643XX_RX_RING_SIZE;
-	mp->xbuf_count = tx_ring_size ? tx_ring_size : MV643XX_TX_RING_SIZE;
+	mp->rbuf_count = rx_ring_size;
+	mp->xbuf_count = tx_ring_size;
 
 	if ( mp->xbuf_count > 0 )
 		mp->xbuf_count += TX_NUM_TAG_SLOTS;
@@ -1551,16 +1582,10 @@ int                  InstallISRSuccessful;
 	if ( mp->xbuf_count < 0 )
 		mp->xbuf_count = 0;
 
-#ifdef BSDBSD
 	/* allocate ring area; add 1 entry -- room for alignment */
 	assert( !mp->ring_area );
-	mp->ring_area = malloc(
-							sizeof(*mp->ring_area) *
-								(mp->rbuf_count + mp->xbuf_count + 1),
-							M_DEVBUF,
-							M_WAIT );
+	mp->ring_area = malloc( sizeof(*mp->ring_area) * (mp->rbuf_count + mp->xbuf_count + 1) );
 	assert( mp->ring_area );
-#endif
 
 	BSP_mve_stop_hw(mp);
 
@@ -1587,37 +1612,56 @@ int                  InstallISRSuccessful;
 	return mp;
 }
 
-struct mveth_private *
-BSP_mve_setup_1(
-	struct mveth_private *mp,
-	int		 unit,
-	void     (*isr)(void *isr_arg),
-	void     *isr_arg,
-	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
-	void *cleanup_txbuf_arg,
-	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
-	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
-	void *consume_rxbuf_arg,
-	int		rx_ring_size,
-	int		tx_ring_size,
-	int		irq_mask
-)
+void
+BSP_mve_update_serial_port(struct mveth_private *mp, int media)
 {
-	if ( irq_mask && 0 == isr ) {
-		printk(DRVNAME": must supply an ISR if irq_msk not zero\n");
-		return 0;	
+int port = mp->port_num;
+uint32_t old, new;
+
+	new = old = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(port));
+
+	/* mask speed and duplex settings */
+	new &= ~(  MV643XX_ETH_SET_GMII_SPEED_1000
+			 | MV643XX_ETH_SET_MII_SPEED_100
+			 | MV643XX_ETH_SET_FULL_DUPLEX );
+
+	if ( (MV643XX_MEDIA_FD & media) )
+		new |= MV643XX_ETH_SET_FULL_DUPLEX;
+
+	switch ( (media & MV643XX_MEDIA_SPEED_MSK) ) {
+		default: /* treat as 10 */
+			break;
+		case MV643XX_MEDIA_100:
+			new |= MV643XX_ETH_SET_MII_SPEED_100;
+			break;
+		case MV643XX_MEDIA_1000:
+			new |= MV643XX_ETH_SET_GMII_SPEED_1000;
+			break;
 	}
 
-	return mve_setup_internal(
-				mp,
-				unit,
-				0,
-				isr, isr_arg,
-				cleanup_txbuf, cleanup_txbuf_arg,
-				alloc_rxbuf,
-				consume_rxbuf, consume_rxbuf_arg,
-				rx_ring_size, tx_ring_size,
-				irq_mask);
+
+	if ( new != old ) {
+		if ( ! (MV643XX_ETH_SERIAL_PORT_ENBL & new) ) {
+			/* just write */
+			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
+		} else {
+			uint32_t were_running;
+
+			were_running = mveth_stop_tx(port);
+
+			old &= ~MV643XX_ETH_SERIAL_PORT_ENBL;
+			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), old);
+			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
+			/* linux driver writes twice... */
+			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
+
+			if ( were_running ) {
+				MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
+			}
+		}
+	}
+	/* If TX stalled because there was no buffer then whack it */
+	mveth_start_tx(mp);
 }
 
 rtems_id
@@ -1629,24 +1673,14 @@ BSP_mve_get_tid(struct mveth_private *mp)
 int
 BSP_mve_detach(struct mveth_private *mp)
 {
-#ifdef BSDBSD
-int unit = mp->port_num;
-#endif
 	BSP_mve_stop_hw(mp);
 	if ( mp->irq_mask || mp->xirq_mask ) {
 		if ( !BSP_remove_rtems_irq_handler( &irq_data[mp->port_num] ) )
 			return -1;
 	}
-#ifdef BSDBSD
-#warning FIXME
-	free( (void*)mp->ring_area, M_DEVBUF );
-#endif
+	free( (void*)mp->ring_area );
 	memset(mp, 0, sizeof(*mp));
 	__asm__ __volatile__("":::"memory");
-	/* mark as unused */
-#ifdef BSDBSD
-	theMvEths[unit].arpcom.ac_if.if_init = 0;
-#endif
 	return 0;
 }
 
@@ -1692,6 +1726,133 @@ register MvEthTxDesc	d;
 	return rval;
 }
 
+int
+BSP_mve_send_buf_chain(struct mveth_private *mp, MveEthBufIterNext next, MveEthBufIter *it)
+{
+int						rval;
+register MvEthTxDesc	l,d,h;
+int						nmbs;
+MveEthBufIter           head = *it;
+
+	rval = 0;
+
+	/* if no descriptor is available; try to wipe the queue */
+	if ( (mp->avail < 1) && MVETH_CLEAN_ON_SEND(mp)<=0 ) {
+		/* Maybe TX is stalled and needs to be restarted */
+		mveth_start_tx(mp);
+		return -1;
+	}
+
+	h = mp->d_tx_h;
+
+#ifdef MVETH_TESTING 
+	assert( !h->buf_ptr );
+	assert( !h->mb      );
+#endif
+
+	/* Don't use the first descriptor yet because BSP_mve_swipe_tx()
+	 * needs mp->d_tx_h->buf_ptr == NULL as a marker. Hence, we
+	 * start with the second mbuf and fill the first descriptor
+	 * last.
+	 */
+
+	l = h;
+	d = NEXT_TXD(h);
+
+	mp->avail--;
+
+	nmbs = 1;
+	while ( (it = next(it)) ) {
+		if ( 0 == it->len )
+			continue;	/* skip empty mbufs */
+
+		nmbs++;
+
+		if ( mp->avail < 1 && MVETH_CLEAN_ON_SEND(mp)<=0 ) {
+			/* Maybe TX was stalled - try to restart */
+			mveth_start_tx(mp);
+
+			/* not enough descriptors; cleanup...
+			 * the first slot was never used, so we start
+			 * at mp->d_tx_h->next;
+			 */
+			for ( l = NEXT_TXD(h); l!=d; l=NEXT_TXD(l) ) {
+#ifdef MVETH_TESTING
+				assert( l->mb == 0 );
+#endif
+				l->buf_ptr  = 0;
+				l->cmd_sts  = 0;
+				mp->avail++;
+			}
+			mp->avail++;
+			if ( nmbs > TX_AVAILABLE_RING_SIZE(mp) ) {
+				/* this chain will never fit into the ring */
+				if ( nmbs > mp->stats.maxchain )
+					mp->stats.maxchain = nmbs;
+				mp->stats.repack++;
+				/* caller may reorganize chain */
+				return -2;
+			}
+			return -1;
+		}
+
+		mp->avail--;
+
+#ifdef MVETH_TESTING
+		assert( d != h      );
+		assert( !d->buf_ptr );
+#endif
+
+		/* fill this slot */
+		rval += mveth_assign_desc_raw(d, it->data, it->len, it->uptr, TDESC_DMA_OWNED);
+
+		FLUSH_BUF( (uint32_t)it->data, it->len );
+
+		l = d;
+		d = NEXT_TXD(d);
+
+		FLUSH_DESC(l);
+	}
+
+	/* fill first slot - don't release to DMA yet */
+	rval += mveth_assign_desc_raw(h, head.data, head.len, head.uptr, TDESC_FRST);
+
+
+	FLUSH_BUF((uint32_t)head.data, head.len);
+
+
+	/* tag last slot; this covers the case where 1st==last */
+	l->cmd_sts      |= TDESC_LAST | TDESC_INT_ENA;
+
+	FLUSH_DESC(l);
+
+	/* Tag end; make sure chip doesn't try to read ahead of here! */
+	l->next->cmd_sts = 0;
+	FLUSH_DESC(l->next);
+
+	membarrier();
+
+	/* turn over the whole chain by flipping ownership of the first desc */
+	h->cmd_sts |= TDESC_DMA_OWNED;
+
+	FLUSH_DESC(h);
+
+	membarrier();
+
+	/* notify the device */
+	MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
+
+	/* Update softc */
+	mp->stats.packet++;
+	if ( nmbs > mp->stats.maxchain )
+		mp->stats.maxchain = nmbs;
+
+	/* remember new head */
+	mp->d_tx_h = d;
+
+	return rval; /* #bytes sent */
+}
+
 int
 BSP_mve_send_buf_raw(
 	struct mveth_private *mp,
@@ -1754,7 +1915,7 @@ int                     frst_len;
 		assert( d != h      );
 		assert( !d->buf_ptr );
 #endif
-		rval += mveth_assign_desc_raw(d, data_p, d_len, TDESC_DMA_OWNED);
+		rval += mveth_assign_desc_raw(d, data_p, d_len, 0, TDESC_DMA_OWNED);
 		FLUSH_BUF( (uint32_t)data_p, d_len );
 		d->u_buf = data_p;
 
@@ -1765,7 +1926,7 @@ int                     frst_len;
 	}
 
 	/* fill first slot with raw buffer - don't release to DMA yet */
-	rval       += mveth_assign_desc_raw(h, frst_buf, frst_len, TDESC_FRST);
+	rval       += mveth_assign_desc_raw(h, frst_buf, frst_len, 0, TDESC_FRST);
 
 	FLUSH_BUF( (uint32_t)frst_buf, frst_len);
 
@@ -2158,8 +2319,8 @@ BSP_mve_ack_irq_mask(struct mveth_private *mp, uint32_t mask)
 	return mveth_ack_irqs(mp, mask);
 }
 
-static void
-dump_update_stats(struct mveth_private *mp, FILE *f)
+void
+BSP_mve_dump_stats(struct mveth_private *mp, FILE *f)
 {
 int      p = mp->port_num;
 int      idx;
@@ -2198,9 +2359,3 @@ uint32_t v;
 	}
 	fprintf(f, "\n");
 }
-
-void
-BSP_mve_dump_stats(struct mveth_private *mp, FILE *f)
-{
-	dump_update_stats(mp, f);
-}
diff --git a/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth_bsdnet.c b/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth_bsdnet.c
index a2efdce8e1..2e841c5e8b 100644
--- a/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth_bsdnet.c
+++ b/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth_bsdnet.c
@@ -74,14 +74,12 @@
  *       further down...
  */
 
-/*
 #ifndef KERNEL
 #define KERNEL
 #endif
 #ifndef _KERNEL
 #define _KERNEL
 #endif
-*/
 
 #include <rtems.h>
 #include <rtems/bspIo.h>
@@ -95,14 +93,15 @@
 #include <errno.h>
 #include <inttypes.h>
 
+#include <bsp/mv643xx_eth.h>
 
-#ifdef BSDBSD
 #include <sys/param.h>
 #include <sys/proc.h>
 #include <sys/socket.h>
 #include <sys/sockio.h>
 #include <dev/mii/mii.h>
 #include <net/if_var.h>
+#include <net/if_arp.h>
 #include <net/if_media.h>
 
 /* Not so nice; would be more elegant not to depend on C library but the
@@ -125,14 +124,11 @@
 #include <net/if.h>
 #include <netinet/in.h>
 #include <netinet/if_ether.h>
-#endif /* BSDBSD */
 
-#ifdef BSDBSD
 #include <rtems/rtems_mii_ioctl.h>
 
 #include <bsp/early_enet_link_status.h>
 #include <bsp/if_mve_pub.h>
-#endif /* BSDBSD */
 
 /* CONFIGURABLE PARAMETERS */
 
@@ -149,12 +145,6 @@
 /* Enable debugging messages and some support routines  (dump rings etc.)                    */      
 #undef  MVETH_DEBUG
 
-/* Hack for driver development; rtems bsdnet doesn't implement detaching an interface :-(
- * but this hack allows us to unload/reload the driver module which makes development
- * a lot less painful.
- */
-#undef MVETH_DETACH_HACK
-
 /* Ring sizes */
 
 #ifdef MVETH_TESTING
@@ -201,154 +191,8 @@
 
 #define TX_NUM_TAG_SLOTS			1 /* leave room for tag; must not be 0 */
 
-/* This is REAL; chip reads from 64-bit down-aligned buffer
- * if the buffer size is < 8 !!! for buffer sizes 8 and upwards
- * alignment is not an issue. This was verified using the
- * 'mve_smallbuf_test.c'
- */
-#define ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM
-
-/* Chip register configuration values */
-#define	MVETH_PORT_CONFIG_VAL			(0				\
-			| MV643XX_ETH_DFLT_RX_Q(0)					\
-			| MV643XX_ETH_DFLT_RX_ARP_Q(0)				\
-			| MV643XX_ETH_DFLT_RX_TCP_Q(0)				\
-			| MV643XX_ETH_DFLT_RX_UDP_Q(0)				\
-			| MV643XX_ETH_DFLT_RX_BPDU_Q(0)				\
-			)
-
-
-#define	MVETH_PORT_XTEND_CONFIG_VAL		0
-
-#ifdef OLDCONFIGVAL
-#define	MVETH_SERIAL_CTRL_CONFIG_VAL	(0				\
-			 | MV643XX_ETH_FORCE_LINK_PASS 				\
-			 | MV643XX_ETH_DISABLE_AUTO_NEG_FOR_FLOWCTL	\
-			 | MV643XX_ETH_ADVERTISE_SYMMETRIC_FLOWCTL	\
-			 | MV643XX_ETH_BIT9_UNKNOWN					\
-			 | MV643XX_ETH_FORCE_LINK_FAIL_DISABLE		\
-			 | MV643XX_ETH_SC_MAX_RX_1552				\
-			 | MV643XX_ETH_SET_FULL_DUPLEX				\
-			 | MV643XX_ETH_ENBL_FLOWCTL_TX_RX_IN_FD		\
-			 )
-#endif
-/* If we enable autoneg (duplex, speed, ...) then it seems
- * that the chip automatically updates link settings
- * (correct link settings are reflected in PORT_STATUS_R).
- * However, when we disable aneg in the PHY then things
- * can get messed up and the port doesn't work anymore.
- * => we follow the linux driver in disabling all aneg
- * in the serial config reg. and manually updating the
- * speed & duplex bits when the phy link status changes.
- * FIXME: don't know what to do about pause/flow-ctrl.
- * It is best to just use ANEG anyways!!!
- */
-#define	MVETH_SERIAL_CTRL_CONFIG_VAL	(0				\
-			 | MV643XX_ETH_DISABLE_AUTO_NEG_FOR_DUPLEX	\
-			 | MV643XX_ETH_DISABLE_AUTO_NEG_FOR_FLOWCTL	\
-			 | MV643XX_ETH_ADVERTISE_SYMMETRIC_FLOWCTL	\
-			 | MV643XX_ETH_BIT9_UNKNOWN					\
-			 | MV643XX_ETH_FORCE_LINK_FAIL_DISABLE		\
-			 | MV643XX_ETH_DISABLE_AUTO_NEG_SPEED_GMII	\
-			 | MV643XX_ETH_SC_MAX_RX_1552				\
-			 )
-
-#define	MVETH_SERIAL_CTRL_CONFIG_MSK	(0				\
-			 | MV643XX_ETH_SERIAL_PORT_ENBL				\
-			 | MV643XX_ETH_FORCE_LINK_PASS				\
-			 | MV643XX_ETH_SC_MAX_RX_MASK				\
-			 )
-
-
-#ifdef __PPC__
-#define MVETH_SDMA_CONFIG_VAL			(0				\
-			| MV643XX_ETH_RX_BURST_SZ_4_64BIT			\
-			| MV643XX_ETH_TX_BURST_SZ_4_64BIT			\
-			)
-#else
-#define MVETH_SDMA_CONFIG_VAL			(0				\
-			| MV643XX_ETH_RX_BURST_SZ_16_64BIT			\
-			| MV643XX_ETH_TX_BURST_SZ_16_64BIT			\
-			)
-#endif
-
-/* minimal frame size we accept */
-#define MVETH_MIN_FRAMSZ_CONFIG_VAL	40
-
-/* END OF CONFIGURABLE SECTION */
-
-/*
- * Here's stuff I learned about this chip:
- *
- *
- * RX interrupt flags:
- *
- * broadcast packet RX: 0x00000005
- *           last buf:  0x00000c05
- *           overrun:   0x00000c00           
- * unicast   packet RX: 0x00000005
- * bad CRC received:    0x00000005
- *
- * clearing 0x00000004 -> clears 0x00000001
- * clearing 0x00000400 -> clears 0x00000800
- *
- * --> 0x0801 are probably some sort of summary bits.
- *
- * TX interrupt flags:
- *
- * broadcast packet in 1 buf: xcause: 0x00000001 (cause 0x00080000)
- *        into disconn. link:             "                 "
- *
- * in some cases, I observed  xcause: 0x00000101 (reason for 0x100 unknown
- * but the linux driver accepts it also).
- *
- *
- * Here a few more ugly things about this piece of hardware I learned
- * (painfully, painfully; spending many many hours & nights :-()
- *
- * a) Especially in the case of 'chained' descriptors, the DMA keeps
- *    clobbering 'cmd_sts' long after it cleared the OWNership flag!!!
- *    Only after the whole chain is processed (OWN cleared on the
- *    last descriptor) it is safe to change cmd_sts.
- *    However, in the case of hardware snooping I found that the
- *    last descriptor in chain has its cmd_sts still clobbered *after*
- *    checking ownership!, I.e.,
- *        if ( ! OWN & cmd_sts ) {
- *            cmd_sts = 0;
- *        }
- *    --> sometimes, cmd_sts is STILL != 0 here
- *
- * b) Sometimes, the OWNership flag is *not cleared*.  
- * 
- * c) Weird things happen if the chip finds a descriptor with 'OWN'
- *    still set (i.e., not properly loaded), i.e., corrupted packets
- *    are sent [with OK checksum since the chip calculates it]. 
- *
- * Combine a+b+c and we end up with a real mess.
- *
- * The fact that the chip doesn't reliably reset OWN and that OTOH,
- * it can't be reliably reset by the driver and still, the chip needs
- * it for proper communication doesn't make things easy...
- *
- * Here the basic workarounds:
- *
- *     - In addition to check OWN, the scavenger compares the "currently
- *       served desc" register to the descriptor it tries to recover and
- *       ignores OWN if they do not match. Hope this is OK.
- *       Otherwise, we could scan the list of used descriptors and proceed
- *       recycling descriptors if we find a !OWNed one behind the target...
- *
- *     - Always keep an empty slot around to mark the end of the list of
- *       jobs. The driver clears the descriptor ahead when enqueueing a new
- *       packet.
- */
-
 #define DRVNAME			"mve"
-#define MAX_NUM_SLOTS	3
-
-#if MV643XXETH_NUM_DRIVER_SLOTS > MAX_NUM_SLOTS
-#error "mv643xxeth: only MAX_NUM_SLOTS supported"
-#endif
+#define MAX_NUM_SLOTS   3
 
 #ifdef NDEBUG
 #error "Driver uses assert() statements with side-effects; MUST NOT define NDEBUG"
@@ -360,21 +204,6 @@
 #define STATIC static
 #endif
 
-struct mveth_private;
-
-/* Clear multicast filters                        */
-void
-BSP_mve_mcast_filter_clear(struct mveth_private *mp);
-void
-BSP_mve_mcast_filter_accept_all(struct mveth_private *mp);
-void
-BSP_mve_mcast_filter_accept_add(struct mveth_private *mp, unsigned char *enaddr);
-void
-BSP_mve_mcast_filter_accept_del(struct mveth_private *mp, unsigned char *enaddr);
-/* Stop hardware and clean out the rings */
-void
-BSP_mve_stop_hw(struct mveth_private *mp);
-
 struct mveth_private *
 BSP_mve_setup(
 	int		 unit,
@@ -389,99 +218,6 @@ BSP_mve_setup(
 	int		irq_mask
 );
 
-struct mveth_private *
-BSP_mve_setup_1(
-	int		 unit,
-	void     (*isr)(void *isr_arg),
-	void     *isr_arg,
-	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
-	void *cleanup_txbuf_arg,
-	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
-	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
-	void *consume_rxbuf_arg,
-	int		rx_ring_size,
-	int		tx_ring_size,
-	int		irq_mask
-);
-
-/* MAIN RX-TX ROUTINES
- *
- * BSP_mve_swipe_tx():  descriptor scavenger; releases mbufs
- * BSP_mve_send_buf():  xfer mbufs from IF to chip
- * BSP_mve_swipe_rx():  enqueue received mbufs to interface
- *                    allocate new ones and yield them to the
- *                    chip.
- */
-
-/* clean up the TX ring freeing up buffers */
-int
-BSP_mve_swipe_tx(struct mveth_private *mp);
-int
-BSP_mve_send_buf_raw(
-	struct mveth_private *mp,
-	void                 *head_p,
-	int                   h_len,
-	void                 *data_p,
-    int                   d_len);
-/* send received buffers upwards and replace them
- * with freshly allocated ones;
- * ASSUMPTION:	buffer length NEVER changes and is set
- *				when the ring is initialized.
- * TS 20060727: not sure if this assumption is still necessary - I believe it isn't.
- */
-int
-BSP_mve_swipe_rx(struct mveth_private *mp);
-
-rtems_id
-BSP_mve_get_tid(struct mveth_private *mp);
-int
-BSP_mve_detach(struct mveth_private *mp);
-
-/* Fire up the low-level driver
- *
- * - make sure hardware is halted
- * - enable cache snooping
- * - clear address filters
- * - clear mib counters
- * - reset phy
- * - initialize (or reinitialize) descriptor rings
- * - check that the firmware has set up a reasonable mac address.
- * - generate unicast filter entry for our mac address
- * - write register config values to the chip
- * - start hardware (serial port and SDMA)
- */
-
-void
-BSP_mve_init_hw(struct mveth_private *mp, int promisc, unsigned char *enaddr);
-
-/* read ethernet address from hw to buffer */
-void
-BSP_mve_read_eaddr(struct mveth_private *mp, unsigned char *oeaddr);
-
-void
-BSP_mve_enable_irqs(struct mveth_private *mp);
-void
-BSP_mve_disable_irqs(struct mveth_private *mp);
-uint32_t
-BSP_mve_ack_irqs(struct mveth_private *mp);
-void
-BSP_mve_enable_irq_mask(struct mveth_private *mp, uint32_t mask);
-uint32_t
-BSP_mve_disable_irq_mask(struct mveth_private *mp, uint32_t mask);
-uint32_t
-BSP_mve_ack_irq_mask(struct mveth_private *mp, uint32_t mask);
-
-void
-BSP_mve_dump_stats(struct mveth_private *mp, FILE *f);
-
-unsigned
-mveth_mii_read(struct mveth_private *mp, unsigned addr);
-
-unsigned
-mveth_mii_write(struct mveth_private *mp, unsigned addr, unsigned v);
-
-
-
 #define TX_AVAILABLE_RING_SIZE(mp)		((mp)->xbuf_count - (TX_NUM_TAG_SLOTS))
 
 /* macros for ring alignment; proper alignment is a hardware req; . */
@@ -805,120 +541,15 @@ mveth_mii_write(struct mveth_private *mp, unsigned addr, unsigned v);
  */
 typedef uint32_t Dma_addr_t;
 
-typedef volatile struct mveth_rx_desc {
-#ifndef __BIG_ENDIAN__
-#error	"descriptor declaration not implemented for little endian machines"
-#endif
-	uint16_t	byte_cnt;
-	uint16_t	buf_size;
-	uint32_t	cmd_sts;					/* control and status */
-	Dma_addr_t	next_desc_ptr;				/* next descriptor (as seen from DMA) */
-	Dma_addr_t	buf_ptr;
-	/* fields below here are not used by the chip */
-	void		*u_buf;						/* user buffer */
-	volatile struct mveth_rx_desc *next;	/* next descriptor (CPU address; next_desc_ptr is a DMA address) */
-	uint32_t	pad[2];
-} __attribute__(( aligned(RING_ALIGNMENT) )) MvEthRxDescRec, *MvEthRxDesc;
-
-typedef volatile struct mveth_tx_desc {
-#ifndef __BIG_ENDIAN__
-#error	"descriptor declaration not implemented for little endian machines"
-#endif
-	uint16_t	byte_cnt;
-	uint16_t	l4i_chk;
-	uint32_t	cmd_sts;					/* control and status */
-	Dma_addr_t	next_desc_ptr;				/* next descriptor (as seen from DMA) */
-	Dma_addr_t	buf_ptr;
-	/* fields below here are not used by the chip */
-	uint32_t	workaround[2];				/* use this space to work around the 8byte problem (is this real?) */
-	void		*u_buf;						/* user buffer */
-	volatile struct mveth_tx_desc *next;	/* next descriptor (CPU address; next_desc_ptr is a DMA address)   */
-} __attribute__(( aligned(RING_ALIGNMENT) )) MvEthTxDescRec, *MvEthTxDesc;
-
-/* Assume there are never more then 64k aliasing entries */
-typedef uint16_t Mc_Refcnt[MV643XX_ETH_NUM_MCAST_ENTRIES*4];
-
-/* driver private data and bsdnet interface structure */
-struct mveth_private {
-	MvEthRxDesc		rx_ring;					/* pointers to aligned ring area             */
-	MvEthTxDesc		tx_ring;					/* pointers to aligned ring area             */
-	MvEthRxDesc		ring_area;					/* allocated ring area                       */
-	int				rbuf_count, xbuf_count;		/* saved ring sizes from ifconfig            */
-	int				port_num;
-	int				phy;
-	MvEthRxDesc		d_rx_t;						/* tail of the RX ring; next received packet */
-	MvEthTxDesc		d_tx_t, d_tx_h;				
-	uint32_t		rx_desc_dma, tx_desc_dma; 	/* ring address as seen by DMA;	(1:1 on this BSP) */
-	int				avail;
-	void            (*isr)(void*);
-	void            *isr_arg;
-	/* Callbacks to handle buffers */
-	void			(*cleanup_txbuf)(void*, void*, int);	/* callback to cleanup TX buffer */
-	void			*cleanup_txbuf_arg;
-	void			*(*alloc_rxbuf)(int *psize, uintptr_t *paddr);	/* allocate RX buffer  */
-	void			(*consume_rxbuf)(void*, void*,  int);	/* callback to consume RX buffer */
-	void			*consume_rxbuf_arg;
-	rtems_id        tid;
-	uint32_t		irq_mask;					/* IRQs we use                              */
-	uint32_t		xirq_mask;
-    int             promisc;
-	struct		{
-		unsigned		irqs;
-		unsigned		maxchain;
-		unsigned		repack;
-		unsigned		packet;
-		unsigned		odrops;					/* no counter in core code                   */
-		struct {
-			uint64_t	good_octs_rcvd;         /* 64-bit */
-			uint32_t	bad_octs_rcvd;
-			uint32_t	internal_mac_tx_err;
-			uint32_t	good_frames_rcvd;
-			uint32_t	bad_frames_rcvd;
-			uint32_t	bcast_frames_rcvd;
-			uint32_t	mcast_frames_rcvd;
-			uint32_t	frames_64_octs;
-			uint32_t	frames_65_127_octs;
-			uint32_t	frames_128_255_octs;
-			uint32_t	frames_256_511_octs;
-			uint32_t	frames_512_1023_octs;
-			uint32_t	frames_1024_max_octs;
-			uint64_t	good_octs_sent;         /* 64-bit */
-			uint32_t	good_frames_sent;
-			uint32_t	excessive_coll;
-			uint32_t	mcast_frames_sent;
-			uint32_t	bcast_frames_sent;
-			uint32_t	unrec_mac_ctrl_rcvd;
-			uint32_t	fc_sent;
-			uint32_t	good_fc_rcvd;
-			uint32_t	bad_fc_rcvd;
-			uint32_t	undersize_rcvd;
-			uint32_t	fragments_rcvd;
-			uint32_t	oversize_rcvd;
-			uint32_t	jabber_rcvd;
-			uint32_t	mac_rx_err;
-			uint32_t	bad_crc_event;
-			uint32_t	coll;
-			uint32_t	late_coll;
-		} mib;
-	}			stats;
-	struct {
-		Mc_Refcnt	specl, other;
-	}           mc_refcnt;
-};
-
 /* stuff needed for bsdnet support */
-#ifdef BSDBSD
 struct mveth_bsdsupp {
 	int				oif_flags;					/* old / cached if_flags */
 };
-#endif /*BSDBSD*/
 
 struct mveth_softc {
-#ifdef BSDBSD
 	struct arpcom			arpcom;
 	struct mveth_bsdsupp	bsd;
-#endif /*BSDBSD*/
-	struct mveth_private	pvt;
+	struct mveth_private	*pvt;
 };
 
 /* GLOBAL VARIABLES */
@@ -926,110 +557,26 @@ struct mveth_softc {
 int mveth_tx_dump = 0;
 #endif
 
-/* THE array of driver/bsdnet structs */
-
-/* If detaching/module unloading is enabled, the main driver data
- * structure must remain in memory; hence it must reside in its own
- * 'dummy' module...
- */
-#ifdef  MVETH_DETACH_HACK
-extern
-#else
-STATIC
-#endif
-struct mveth_softc theMvEths[MV643XXETH_NUM_DRIVER_SLOTS]
-#ifndef MVETH_DETACH_HACK
-= {{{{0}},}}
-#endif
-;
-
-#ifdef BSDBSD
-/* daemon task id */
-STATIC rtems_id	mveth_tid = 0;
-#endif /*BSDBSD*/
-
 /* register access protection mutex */
 STATIC rtems_id mveth_mtx = 0;
+
 #define REGLOCK()	do { \
 		if ( RTEMS_SUCCESSFUL != rtems_semaphore_obtain(mveth_mtx, RTEMS_WAIT, RTEMS_NO_TIMEOUT) ) \
 			rtems_panic(DRVNAME": unable to lock register protection mutex"); \
 		} while (0)
 #define REGUNLOCK()	rtems_semaphore_release(mveth_mtx)
 
-/* Format strings for statistics messages */
-static const char *mibfmt[] = {
-	"  GOOD_OCTS_RCVD:      %"PRIu64"\n",
-	0,
-	"  BAD_OCTS_RCVD:       %"PRIu32"\n",
-	"  INTERNAL_MAC_TX_ERR: %"PRIu32"\n",
-	"  GOOD_FRAMES_RCVD:    %"PRIu32"\n",
-	"  BAD_FRAMES_RCVD:     %"PRIu32"\n",
-	"  BCAST_FRAMES_RCVD:   %"PRIu32"\n",
-	"  MCAST_FRAMES_RCVD:   %"PRIu32"\n",
-	"  FRAMES_64_OCTS:      %"PRIu32"\n",
-	"  FRAMES_65_127_OCTS:  %"PRIu32"\n",
-	"  FRAMES_128_255_OCTS: %"PRIu32"\n",
-	"  FRAMES_256_511_OCTS: %"PRIu32"\n",
-	"  FRAMES_512_1023_OCTS:%"PRIu32"\n",
-	"  FRAMES_1024_MAX_OCTS:%"PRIu32"\n",
-	"  GOOD_OCTS_SENT:      %"PRIu64"\n",
-	0,
-	"  GOOD_FRAMES_SENT:    %"PRIu32"\n",
-	"  EXCESSIVE_COLL:      %"PRIu32"\n",
-	"  MCAST_FRAMES_SENT:   %"PRIu32"\n",
-	"  BCAST_FRAMES_SENT:   %"PRIu32"\n",
-	"  UNREC_MAC_CTRL_RCVD: %"PRIu32"\n",
-	"  FC_SENT:             %"PRIu32"\n",
-	"  GOOD_FC_RCVD:        %"PRIu32"\n",
-	"  BAD_FC_RCVD:         %"PRIu32"\n",
-	"  UNDERSIZE_RCVD:      %"PRIu32"\n",
-	"  FRAGMENTS_RCVD:      %"PRIu32"\n",
-	"  OVERSIZE_RCVD:       %"PRIu32"\n",
-	"  JABBER_RCVD:         %"PRIu32"\n",
-	"  MAC_RX_ERR:          %"PRIu32"\n",
-	"  BAD_CRC_EVENT:       %"PRIu32"\n",
-	"  COLL:                %"PRIu32"\n",
-	"  LATE_COLL:           %"PRIu32"\n",
-};
+/* THE array of driver/bsdnet structs */
 
-/* Interrupt Handler Connection */
-
-/* forward decls + implementation for IRQ API funcs */
-
-static void mveth_isr(rtems_irq_hdl_param unit);
-static void mveth_isr_1(rtems_irq_hdl_param unit);
-static void noop(const rtems_irq_connect_data *unused)  {}
-static int  noop1(const rtems_irq_connect_data *unused) { return 0; }
-
-static rtems_irq_connect_data irq_data[MAX_NUM_SLOTS] = {
-	{
-		BSP_IRQ_ETH0,
-		0,
-		(rtems_irq_hdl_param)0,
-		noop,
-		noop,
-		noop1
-	},
-	{
-		BSP_IRQ_ETH1,
-		0,
-		(rtems_irq_hdl_param)1,
-		noop,
-		noop,
-		noop1
-	},
-	{
-		BSP_IRQ_ETH2,
-		0,
-		(rtems_irq_hdl_param)2,
-		noop,
-		noop,
-		noop1
-	},
-};
+STATIC
+struct mveth_softc theMvEths[MV643XXETH_NUM_DRIVER_SLOTS]
+= {{{{0}},}}
+;
+
+/* daemon task id */
+STATIC rtems_id	mveth_tid = 0;
 
 /* MII Ioctl Interface */
-#ifdef BSDMII
 
 /* mdio / mii interface wrappers for rtems_mii_ioctl API */
 
@@ -1038,7 +585,7 @@ static int mveth_mdio_r(int phy, void *uarg, unsigned reg, uint32_t *pval)
 	if ( phy > 1 )
 		return -1;
 
-	*pval = mveth_mii_read(uarg, reg);
+	*pval = BSP_mve_mii_read(uarg, reg);
 	return 0;
 }
 
@@ -1046,7 +593,7 @@ static int mveth_mdio_w(int phy, void *uarg, unsigned reg, uint32_t val)
 {
 	if ( phy > 1 )
 		return -1;
-	mveth_mii_write(uarg, reg, val);
+	BSP_mve_mii_write(uarg, reg, val);
 	return 0;
 }
 
@@ -1056,1701 +603,252 @@ static struct rtems_mdio_info mveth_mdio = {
 	has_gmii: 1,
 };
 
-#endif /* BSDBSD */
-
-/* LOW LEVEL SUPPORT ROUTINES */
-
-/* Software Cache Coherency */
-#ifndef ENABLE_HW_SNOOPING
-#ifndef __PPC__
-#error "Software cache coherency maintenance is not implemented for your CPU architecture"
-#endif
-
-static inline unsigned INVAL_DESC(volatile void *d)
-{
-typedef const char cache_line[PPC_CACHE_ALIGNMENT];
-	asm volatile("dcbi 0, %1":"=m"(*(cache_line*)d):"r"(d));
-	return (unsigned)d;	/* so this can be used in comma expression */
-}
-
-static inline void FLUSH_DESC(volatile void *d)
-{
-typedef const char cache_line[PPC_CACHE_ALIGNMENT];
-	asm volatile("dcbf 0, %0"::"r"(d),"m"(*(cache_line*)d));
-}
-
-static inline void FLUSH_BARRIER(void)
-{
-	asm volatile("eieio");
-}
-
-/* RX buffers are always cache-line aligned
- * ASSUMPTIONS:
- *   - 'addr' is cache aligned
- *   -  len   is a multiple >0 of cache lines
- */
-static inline void INVAL_BUF(register uintptr_t addr, register int len)
-{
-typedef char maxbuf[2048]; /* more than an ethernet packet */
-	do {
-		len -= RX_BUF_ALIGNMENT;
-		asm volatile("dcbi %0, %1"::"b"(addr),"r"(len));
-	} while (len > 0);
-	asm volatile("":"=m"(*(maxbuf*)addr));
-}
-
-/* Flushing TX buffers is a little bit trickier; we don't really know their
- * alignment but *assume* adjacent addresses are covering 'ordinary' memory
- * so that flushing them does no harm!
- */
-static inline void FLUSH_BUF(register uintptr_t addr, register int len)
-{
-	asm volatile("":::"memory");
-	len = MV643XX_ALIGN(len, RX_BUF_ALIGNMENT);
-	do { 
-		asm volatile("dcbf %0, %1"::"b"(addr),"r"(len));
-		len -= RX_BUF_ALIGNMENT;
-	} while ( len >= 0 );
-}
-
-#else /* hardware snooping enabled */
-
-/* inline this to silence compiler warnings */
-static inline int INVAL_DESC(volatile void *d)
-{ return 0; }
-
-#define FLUSH_DESC(d)	NOOP()
-#define INVAL_BUF(b,l)	NOOP()
-#define FLUSH_BUF(b,l)	NOOP()
-#define FLUSH_BARRIER()	NOOP()
-
-#endif	/* cache coherency support */
-
-/* Synchronize memory access */
-#ifdef __PPC__
-static inline void membarrier(void)
-{
-	asm volatile("sync":::"memory");
-}
-#else
-#error "memory barrier instruction not defined (yet) for this CPU"
-#endif
-
-/* Enable and disable interrupts at the device */
-static inline void
-mveth_enable_irqs(struct mveth_private *mp, uint32_t mask)
-{
-rtems_interrupt_level l;
-uint32_t val;
-	rtems_interrupt_disable(l);
-
-	val  = MV_READ(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num));
-	val  = (val | mask | MV643XX_ETH_IRQ_EXT_ENA) & mp->irq_mask;
-
-	MV_WRITE(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num),        val);
-
-	val  = MV_READ(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num));
-	val  = (val | mask) & mp->xirq_mask;
-	MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num), val);
-
-	rtems_interrupt_enable(l);
-}
-
-static inline uint32_t
-mveth_disable_irqs(struct mveth_private *mp, uint32_t mask)
-{
-rtems_interrupt_level l;
-uint32_t val,xval,tmp;
-	rtems_interrupt_disable(l);
-
-	val  = MV_READ(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num));
-	tmp  = ( (val & ~mask) | MV643XX_ETH_IRQ_EXT_ENA ) & mp->irq_mask;
-	MV_WRITE(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num),        tmp);
-
-	xval = MV_READ(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num));
-	tmp  = (xval & ~mask) & mp->xirq_mask;
-	MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num), tmp);
-
-	rtems_interrupt_enable(l);
-
-	return (val | xval);
-}
-
-/* This should be safe even w/o turning off interrupts if multiple
- * threads ack different bits in the cause register (and ignore
- * other ones) since writing 'ones' into the cause register doesn't
- * 'stick'.
- */
-
-static inline uint32_t
-mveth_ack_irqs(struct mveth_private *mp, uint32_t mask)
-{
-register uint32_t x,xe,p;
-
-		p  = mp->port_num;
-		/* Get cause */
-		x  = MV_READ(MV643XX_ETH_INTERRUPT_CAUSE_R(p));
-
-		/* Ack interrupts filtering the ones we're interested in */
-
-		/* Note: EXT_IRQ bit clears by itself if EXT interrupts are cleared */
-		MV_WRITE(MV643XX_ETH_INTERRUPT_CAUSE_R(p), ~ (x & mp->irq_mask & mask));
-
-				/* linux driver tests 1<<1 as a summary bit for extended interrupts;
-				 * the mv64360 seems to use 1<<19 for that purpose; for the moment,
-				 * I just check both.
-				 * Update: link status irq (1<<16 in xe) doesn't set (1<<19) in x!
-				 */
-		if ( 1 /* x & 2 */ )
-		{
-			xe = MV_READ(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(p));
-
-			MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(p), ~ (xe & mp->xirq_mask & mask));
-		} else {
-			xe = 0;
-		}
-#ifdef MVETH_TESTING
-		if (    ((x & MV643XX_ETH_ALL_IRQS) & ~MV643XX_ETH_KNOWN_IRQS)
-			 || ((xe & MV643XX_ETH_ALL_EXT_IRQS) & ~MV643XX_ETH_KNOWN_EXT_IRQS) ) {
-			fprintf(stderr, "Unknown IRQs detected; leaving all disabled for debugging:\n");
-			fprintf(stderr, "Cause reg was 0x%08x, ext cause 0x%08x\n", x, xe);
-			mp->irq_mask  = 0;
-			mp->xirq_mask = 0;
-		}
-#endif
-		/* luckily, the extended and 'normal' interrupts we use don't overlap so
-		 * we can just OR them into a single word
-		 */
-		return  (xe & mp->xirq_mask) | (x & mp->irq_mask);
-}
-
-static void mveth_isr(rtems_irq_hdl_param arg)
-{
-unsigned unit = (unsigned)arg;
-	mveth_disable_irqs(&theMvEths[unit].pvt, -1);
-	theMvEths[unit].pvt.stats.irqs++;
-#ifdef BSDBSD
-#warning FIXME
-	rtems_bsdnet_event_send( theMvEths[unit].pvt.tid, 1<<unit );
-#endif
-}
-
-static void mveth_isr_1(rtems_irq_hdl_param arg)
-{
-unsigned              unit = (unsigned)arg;
-struct mveth_private *mp   = &theMvEths[unit].pvt;
-
-	mp->stats.irqs++;
-	mp->isr(mp->isr_arg);
-}
-
-static void
-mveth_clear_mib_counters(struct mveth_private *mp)
-{
-register int		i;
-register uint32_t	b;
-	/* reading the counters resets them */
-	b = MV643XX_ETH_MIB_COUNTERS(mp->port_num);
-	for (i=0; i< MV643XX_ETH_NUM_MIB_COUNTERS; i++, b+=4)
-		(void)MV_READ(b);
-}
-
-/* Reading a MIB register also clears it. Hence we read the lo
- * register first, then the hi one. Correct reading is guaranteed since
- * the 'lo' register cannot overflow after it is read since it had
- * been reset to 0.
- */
-static unsigned long long
-read_long_mib_counter(int port_num, int idx)
-{
-unsigned long lo;
-unsigned long long hi;
-	lo = MV_READ(MV643XX_ETH_MIB_COUNTERS(port_num)+(idx<<2));
-	idx++;
-	hi = MV_READ(MV643XX_ETH_MIB_COUNTERS(port_num)+(idx<<2));
-	return (hi<<32) | lo;
-}
-
-static inline unsigned long
-read_mib_counter(int port_num, int idx)
-{
-	return MV_READ(MV643XX_ETH_MIB_COUNTERS(port_num)+(idx<<2));
-}
-
-
-/* write ethernet address from buffer to hardware (need to change unicast filter after this) */
-static void
-mveth_write_eaddr(struct mveth_private *mp, unsigned char *eaddr)
-{
-int			i;
-uint32_t	x;
-
-	/* build hi word */
- 	for (i=4,x=0; i; i--, eaddr++) {
-		x = (x<<8) | *eaddr;
-	}
-	MV_WRITE(MV643XX_ETH_MAC_ADDR_HI(mp->port_num), x);
-
-	/* build lo word */
- 	for (i=2,x=0; i; i--, eaddr++) {
-		x = (x<<8) | *eaddr;
-	}
-	MV_WRITE(MV643XX_ETH_MAC_ADDR_LO(mp->port_num), x);
-}
-
-/* PHY/MII Interface
- *
- * Read/write a PHY register;
- * 
- * NOTE: The SMI register is shared among the three devices.
- *       Protection is provided by the global networking semaphore.
- *       If non-bsd drivers are running on a subset of IFs proper
- *       locking of all shared registers must be implemented!
- */
-unsigned
-mveth_mii_read(struct mveth_private *mp, unsigned addr)
-{
-unsigned v;
-unsigned wc = 0;
-
-	addr  &= 0x1f;
-
-	/* wait until not busy */
-	do {
-		v = MV_READ(MV643XX_ETH_SMI_R);
-		wc++;
-	} while ( MV643XX_ETH_SMI_BUSY & v );
-
-	MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (mp->phy<<16) | MV643XX_ETH_SMI_OP_RD );
-
-	do {
-		v = MV_READ(MV643XX_ETH_SMI_R);
-		wc++;
-	} while ( MV643XX_ETH_SMI_BUSY & v );
-
-	if (wc>0xffff)
-		wc = 0xffff;
-	return (wc<<16) | (v & 0xffff);
-}
-
-unsigned
-mveth_mii_write(struct mveth_private *mp, unsigned addr, unsigned v)
-{
-unsigned wc = 0;
-
-	addr  &= 0x1f;
-	v     &= 0xffff;
-
-	/* busywait is ugly but not preventing ISRs or high priority tasks from
-	 * preempting us
-	 */
-
-	/* wait until not busy */
-	while ( MV643XX_ETH_SMI_BUSY & MV_READ(MV643XX_ETH_SMI_R) )
-		wc++ /* wait */;
-
-	MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (mp->phy<<16) | MV643XX_ETH_SMI_OP_WR | v );
-
-	return wc;
-}
-
-/* MID-LAYER SUPPORT ROUTINES */
-
-/* Start TX if descriptors are exhausted */
-static __inline__ void
-mveth_start_tx(struct mveth_private *mp)
-{
-uint32_t running;
-	if ( mp->avail <= 0 ) {
-		running = MV_READ(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num));
-		if ( ! (running & MV643XX_ETH_TX_START(0)) ) {
-			MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
-		}
-	}
-}
-
-/* Stop TX and wait for the command queues to stop and the fifo to drain */
-static uint32_t
-mveth_stop_tx(int port)
-{
-uint32_t active_q;
-
-	active_q = (MV_READ(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port)) & MV643XX_ETH_TX_ANY_RUNNING);
-
-	if ( active_q ) {
-		/* Halt TX and wait for activity to stop */
-		MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port), MV643XX_ETH_TX_STOP_ALL);
-		while ( MV643XX_ETH_TX_ANY_RUNNING & MV_READ(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port)) )
-			/* poll-wait */;
-		/* Wait for Tx FIFO to drain */
-		while ( ! (MV643XX_ETH_PORT_STATUS_R(port) & MV643XX_ETH_PORT_STATUS_TX_FIFO_EMPTY) )
-			/* poll-wait */;
-	}
-
-	return active_q;
-}
-
-/* update serial port settings from current link status */
-#ifdef BSDMII
-static void
-mveth_update_serial_port(struct mveth_private *mp, int media)
+static struct mveth_private *
+mve_setup_bsd(
+	int		 unit,
+	rtems_id tid,
+	void     (*isr)(void *isr_arg),
+	void     *isr_arg,
+	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
+	void *cleanup_txbuf_arg,
+	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
+	void *consume_rxbuf_arg,
+	int		rx_ring_size,
+	int		tx_ring_size,
+	int		irq_mask
+)
 {
-int port = mp->port_num;
-uint32_t old, new;
-
-	new = old = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(port));
-
-	/* mask speed and duplex settings */
-	new &= ~(  MV643XX_ETH_SET_GMII_SPEED_1000
-			 | MV643XX_ETH_SET_MII_SPEED_100
-			 | MV643XX_ETH_SET_FULL_DUPLEX );
-
-	if ( IFM_FDX & media )
-		new |= MV643XX_ETH_SET_FULL_DUPLEX;
-
-	switch ( IFM_SUBTYPE(media) ) {
-		default: /* treat as 10 */
-			break;
-		case IFM_100_TX:
-			new |= MV643XX_ETH_SET_MII_SPEED_100;
-			break;
-		case IFM_1000_T:
-			new |= MV643XX_ETH_SET_GMII_SPEED_1000;
-			break;
-	}
-
-
-	if ( new != old ) {
-		if ( ! (MV643XX_ETH_SERIAL_PORT_ENBL & new) ) {
-			/* just write */
-			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
-		} else {
-			uint32_t were_running;
-
-			were_running = mveth_stop_tx(port);
-
-			old &= ~MV643XX_ETH_SERIAL_PORT_ENBL;
-			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), old);
-			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
-			/* linux driver writes twice... */
-			MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
-
-			if ( were_running ) {
-				MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
-			}
-		}
-	}
-}
-#endif /*BSDMII*/
-
-
-void
-BSP_mve_mcast_filter_clear(struct mveth_private *mp)
-{
-int                 i;
-register uint32_t 	s,o;
-uint32_t            v = mp->promisc ? 0x01010101 : 0x00000000;
-	s = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
-	o = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
-	for (i=0; i<MV643XX_ETH_NUM_MCAST_ENTRIES; i++) {
-		MV_WRITE(s,v);
-		MV_WRITE(o,v);
-		s+=4;
-		o+=4;
-	}
-	for (i=0; i<sizeof(mp->mc_refcnt.specl)/sizeof(mp->mc_refcnt.specl[0]); i++) {
-		mp->mc_refcnt.specl[i] = 0;
-		mp->mc_refcnt.other[i] = 0;
-	}
-}
-
-void
-BSP_mve_mcast_filter_accept_all(struct mveth_private *mp)
-{
-int                 i;
-register uint32_t 	s,o;
-	s = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
-	o = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
-	for (i=0; i<MV643XX_ETH_NUM_MCAST_ENTRIES; i++) {
-		MV_WRITE(s,0x01010101);
-		MV_WRITE(o,0x01010101);
-		s+=4;
-		o+=4;
-		/* Not clear what we should do with the reference count.
-		 * For now just increment it.
-		 */
-		for (i=0; i<sizeof(mp->mc_refcnt.specl)/sizeof(mp->mc_refcnt.specl[0]); i++) {
-			mp->mc_refcnt.specl[i]++;
-			mp->mc_refcnt.other[i]++;
-		}
-	}
-}
-
-static void add_entry(uint32_t off, uint8_t hash, Mc_Refcnt *refcnt)
-{
-uint32_t val;
-uint32_t slot = hash & 0xfc;
-
-	if ( 0 == (*refcnt)[hash]++ ) {
-		val = MV_READ(off+slot) | ( 1 << ((hash&3)<<3) );
-		MV_WRITE(off+slot, val);
-	}
-}
-
-static void del_entry(uint32_t off, uint8_t hash, Mc_Refcnt *refcnt)
-{
-uint32_t val;
-uint32_t slot = hash & 0xfc;
-
-	if ( (*refcnt)[hash] > 0 && 0 == --(*refcnt)[hash] ) {
-		val = MV_READ(off+slot) & ~( 1 << ((hash&3)<<3) );
-		MV_WRITE(off+slot, val);
-	}
-}
-
-void
-BSP_mve_mcast_filter_accept_add(struct mveth_private *mp, unsigned char *enaddr)
-{
-uint32_t   hash;
-static const char spec[]={0x01,0x00,0x5e,0x00,0x00};
-static const char bcst[]={0xff,0xff,0xff,0xff,0xff,0xff};
-uint32_t   tabl;
-Mc_Refcnt  *refcnt;
-
-	if ( ! (0x01 & enaddr[0]) ) {
-		/* not a multicast address; ignore */
-		return;
-	}
-
-	if ( 0 == memcmp(enaddr, bcst, sizeof(bcst)) ) {
-		/* broadcast address; ignore */
-		return;
-	}
-
-	if ( 0 == memcmp(enaddr, spec, sizeof(spec)) ) {
-		hash   = enaddr[5];
-		tabl   = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
-		refcnt = &mp->mc_refcnt.specl;
-	} else {
-		uint32_t test, mask;
-		int      i;
-		/* algorithm used by linux driver */
-		for ( hash=0, i=0; i<6; i++ ) {
-			hash = (hash ^ enaddr[i]) << 8;
-			for ( test=0x8000, mask=0x8380; test>0x0080; test>>=1, mask>>=1 ) {
-				if ( hash & test )
-					hash ^= mask;
-			}
-		}
-		tabl   = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
-		refcnt = &mp->mc_refcnt.other;
-	}
-	add_entry(tabl, hash, refcnt);
-}
-
-void
-BSP_mve_mcast_filter_accept_del(struct mveth_private *mp, unsigned char *enaddr)
-{
-uint32_t   hash;
-static const char spec[]={0x01,0x00,0x5e,0x00,0x00};
-static const char bcst[]={0xff,0xff,0xff,0xff,0xff,0xff};
-uint32_t   tabl;
-Mc_Refcnt  *refcnt;
-
-	if ( ! (0x01 & enaddr[0]) ) {
-		/* not a multicast address; ignore */
-		return;
-	}
-
-	if ( 0 == memcmp(enaddr, bcst, sizeof(bcst)) ) {
-		/* broadcast address; ignore */
-		return;
-	}
-
-	if ( 0 == memcmp(enaddr, spec, sizeof(spec)) ) {
-		hash   = enaddr[5];
-		tabl   = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
-		refcnt = &mp->mc_refcnt.specl;
-	} else {
-		uint32_t test, mask;
-		int      i;
-		/* algorithm used by linux driver */
-		for ( hash=0, i=0; i<6; i++ ) {
-			hash = (hash ^ enaddr[i]) << 8;
-			for ( test=0x8000, mask=0x8380; test>0x0080; test>>=1, mask>>=1 ) {
-				if ( hash & test )
-					hash ^= mask;
-			}
-		}
-		tabl   = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
-		refcnt = &mp->mc_refcnt.other;
-	}
-	del_entry(tabl, hash, refcnt);
-}
-
-/* Clear all address filters (multi- and unicast) */
-static void
-mveth_clear_addr_filters(struct mveth_private *mp)
-{
-register int      i;
-register uint32_t u;
-	u = MV643XX_ETH_DA_FILTER_UNICAST_TBL(mp->port_num);
-	for (i=0; i<MV643XX_ETH_NUM_UNICAST_ENTRIES; i++) {
-		MV_WRITE(u,0);
-		u+=4;
-	}
-	BSP_mve_mcast_filter_clear(mp);
-}
-
-/* Setup unicast filter for a given MAC address (least significant nibble) */
-static void
-mveth_ucfilter(struct mveth_private *mp, unsigned char mac_lsbyte, int accept)
-{
-unsigned nib, slot, bit;
-uint32_t	val;
-	/* compute slot in table */
-	nib  = mac_lsbyte & 0xf;	/* strip nibble     */
-	slot = nib & ~3;			/* (nibble/4)*4     */
-	bit  = (nib &  3)<<3;		/*  8*(nibble % 4)  */
-	val = MV_READ(MV643XX_ETH_DA_FILTER_UNICAST_TBL(mp->port_num) + slot);
-	if ( accept ) {
-		val |= 0x01 << bit;
-	} else {
-		val &= 0x0e << bit;
-	}
-	MV_WRITE(MV643XX_ETH_DA_FILTER_UNICAST_TBL(mp->port_num) + slot, val);
-}
-
-#if defined( ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM ) && 0
-/* Currently unused; small unaligned buffers seem to be rare
- * so we just use memcpy()...
- */
-
-/* memcpy for 0..7 bytes; arranged so that gcc
- * optimizes for powerpc...
- */
-
-static inline void memcpy8(void *to, void *fr, unsigned x)
-{
-register uint8_t *d = to, *s = fro;
-
-	d+=l; s+=l;
-	if ( l & 1 ) {
-		*--d=*--s;
-	}
-	if ( l & 2 ) {
-		/* pre-decrementing causes gcc to use auto-decrementing
-		 * PPC instructions (lhzu rx, -2(ry))
-		 */
-		d-=2; s-=2;
-		/* use memcpy; don't cast to short -- accessing
-		 * misaligned data as short is not portable
-		 * (but it works on PPC).
-		 */
-		__builtin_memcpy(d,s,2);
-	}
-	if ( l & 4 ) {
-		d-=4; s-=4;
-		/* see above */
-		__builtin_memcpy(d,s,4);
-	}
-}
-#endif
-
-#ifdef BSDBSD
-/* Assign values (buffer + user data) to a tx descriptor slot */
-static int
-mveth_assign_desc(MvEthTxDesc d, struct mbuf *m, unsigned long extra)
-{
-int rval = (d->byte_cnt = m->m_len);
-
-#ifdef MVETH_TESTING
-	assert( !d->mb      );
-	assert(  m->m_len   );
-#endif
-
-	/* set CRC on all descriptors; seems to be necessary */
-	d->cmd_sts  = extra | (TDESC_GEN_CRC | TDESC_ZERO_PAD);
-
-#ifdef ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM
-	/* The buffer must be 64bit aligned if the payload is <8 (??) */
-	if ( rval < 8 && ((mtod(m, uintptr_t)) & 7) ) {
-		d->buf_ptr = CPUADDR2ENET( d->workaround );
-		memcpy((void*)d->workaround, mtod(m, void*), rval);
-	} else
-#endif
-	{
-		d->buf_ptr  = CPUADDR2ENET( mtod(m, unsigned long) );
-	}
-	d->l4i_chk  = 0;
-	return rval;
-}
-#endif /*BSDBSD*/
-
-static int
-mveth_assign_desc_raw(MvEthTxDesc d, void *buf, int len, unsigned long extra)
-{
-int rval = (d->byte_cnt = len);
-
-#ifdef MVETH_TESTING
-	assert( !d->u_buf );
-	assert(  len   );
-#endif
-
-	/* set CRC on all descriptors; seems to be necessary */
-	d->cmd_sts  = extra | (TDESC_GEN_CRC | TDESC_ZERO_PAD);
-
-#ifdef ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM
-	/* The buffer must be 64bit aligned if the payload is <8 (??) */
-	if ( rval < 8 && ( ((uintptr_t)buf) & 7) ) {
-		d->buf_ptr = CPUADDR2ENET( d->workaround );
-		memcpy((void*)d->workaround, buf, rval);
-	} else
-#endif
-	{
-		d->buf_ptr  = CPUADDR2ENET( (unsigned long)buf );
-	}
-	d->l4i_chk  = 0;
-	return rval;
-}
-
-/*
- * Ring Initialization
- *
- * ENDIAN ASSUMPTION: DMA engine matches CPU endianness (???)
- *
- * Linux driver discriminates __LITTLE and __BIG endian for re-arranging
- * the u16 fields in the descriptor structs. However, no endian conversion
- * is done on the individual fields (SDMA byte swapping is disabled on LE).
- */
-
-STATIC int
-mveth_init_rx_desc_ring(struct mveth_private *mp)
-{
-int i,sz;
-MvEthRxDesc	d;
-uintptr_t baddr;
-
-	memset((void*)mp->rx_ring, 0, sizeof(*mp->rx_ring)*mp->rbuf_count);
-
-	mp->rx_desc_dma = CPUADDR2ENET(mp->rx_ring);
-
-	for ( i=0, d = mp->rx_ring; i<mp->rbuf_count; i++, d++ ) {
-		d->u_buf = mp->alloc_rxbuf(&sz, &baddr);
-		assert( d->u_buf );
-
-#ifndef ENABLE_HW_SNOOPING
-		/* could reduce the area to max. ethernet packet size */
-		INVAL_BUF(baddr, sz);
-#endif
-
-		d->buf_size = sz;
-		d->byte_cnt = 0;
-		d->cmd_sts  = RDESC_DMA_OWNED | RDESC_INT_ENA;
-		d->next		= mp->rx_ring + (i+1) % mp->rbuf_count;
-
-		d->buf_ptr  = CPUADDR2ENET( baddr );
-		d->next_desc_ptr = CPUADDR2ENET(d->next);
-		FLUSH_DESC(d);
-	}
-	FLUSH_BARRIER();
-
-	mp->d_rx_t = mp->rx_ring;
-
-	/* point the chip to the start of the ring */
-	MV_WRITE(MV643XX_ETH_RX_Q0_CURRENT_DESC_PTR(mp->port_num),mp->rx_desc_dma);
-
-
-	return i;
-}
-
-STATIC int
-mveth_init_tx_desc_ring(struct mveth_private *mp)
-{
-int i;
-MvEthTxDesc d;
-
-	memset((void*)mp->tx_ring, 0, sizeof(*mp->tx_ring)*mp->xbuf_count);
-
-	/* DMA and CPU live in the same address space (rtems) */
-	mp->tx_desc_dma = CPUADDR2ENET(mp->tx_ring);
-	mp->avail       = TX_AVAILABLE_RING_SIZE(mp);
-
-	for ( i=0, d=mp->tx_ring; i<mp->xbuf_count; i++,d++ ) {
-		d->l4i_chk  = 0;
-		d->byte_cnt = 0;
-		d->cmd_sts  = 0;
-		d->buf_ptr  = 0;
-
-		d->next     = mp->tx_ring + (i+1) % mp->xbuf_count;
-		d->next_desc_ptr = CPUADDR2ENET(d->next);
-		FLUSH_DESC(d);
-	}
-	FLUSH_BARRIER();
-
-	mp->d_tx_h = mp->d_tx_t = mp->tx_ring;
-
-	/* point the chip to the start of the ring */
-	MV_WRITE(MV643XX_ETH_TX_Q0_CURRENT_DESC_PTR(mp->port_num),mp->tx_desc_dma);
-
-	return i;
-}
-
-/* PUBLIC LOW-LEVEL DRIVER ACCESS */
-
-static struct mveth_private *
-mve_setup_internal(
-	int		 unit,
-	rtems_id tid,
-	void     (*isr)(void*isr_arg),
-	void     *isr_arg,
-	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
-	void *cleanup_txbuf_arg,
-	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
-	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
-	void *consume_rxbuf_arg,
-	int		rx_ring_size,
-	int		tx_ring_size,
-	int		irq_mask
-)
-
-{
-struct mveth_private *mp;
-#ifdef BSDBSD
-struct ifnet         *ifp;
-#endif
-int                  InstallISRSuccessful;
-
-	if ( unit <= 0 || unit > MV643XXETH_NUM_DRIVER_SLOTS ) {
-		printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, MV643XXETH_NUM_DRIVER_SLOTS);
-		return 0;
-	}
-#ifdef BSDBSD
-#warning FIXME
-	ifp = &theMvEths[unit-1].arpcom.ac_if;
-	if ( ifp->if_init ) {
-		if ( ifp->if_init ) {
-			printk(DRVNAME": instance %i already attached.\n", unit);
-			return 0;
-		}
-	}
-#endif
-
-	if ( rx_ring_size < 0 && tx_ring_size < 0 )
-		return 0;
-
-	if ( MV_64360 != BSP_getDiscoveryVersion(0) ) {
-		printk(DRVNAME": not mv64360 chip\n");
-		return 0;
-	}
-
-	/* lazy init of mutex (non thread-safe! - we assume 1st initialization is single-threaded) */
-	if ( ! mveth_mtx ) {
-		rtems_status_code sc;
-		sc = rtems_semaphore_create(
-				rtems_build_name('m','v','e','X'),
-				1,
-				RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY | RTEMS_DEFAULT_ATTRIBUTES,
-				0,
-				&mveth_mtx);
-		if ( RTEMS_SUCCESSFUL != sc ) {
-			rtems_error(sc,DRVNAME": creating mutex\n");
-			rtems_panic("unable to proceed\n");
-		}
-	}
-
-	mp = &theMvEths[unit-1].pvt;
-
-	memset(mp, 0, sizeof(*mp));
-
-	mp->port_num          = unit-1;
-	mp->phy               = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*mp->port_num)) & 0x1f;
-
-	mp->tid               = tid;
-	mp->isr               = isr;
-	mp->isr_arg           = isr_arg;
-
-	mp->cleanup_txbuf     = cleanup_txbuf;
-	mp->cleanup_txbuf_arg = cleanup_txbuf_arg;
-	mp->alloc_rxbuf       = alloc_rxbuf;
-	mp->consume_rxbuf     = consume_rxbuf;
-	mp->consume_rxbuf_arg = consume_rxbuf_arg;
-
-	mp->rbuf_count = rx_ring_size ? rx_ring_size : MV643XX_RX_RING_SIZE;
-	mp->xbuf_count = tx_ring_size ? tx_ring_size : MV643XX_TX_RING_SIZE;
-
-	if ( mp->xbuf_count > 0 )
-		mp->xbuf_count += TX_NUM_TAG_SLOTS;
-
-	if ( mp->rbuf_count < 0 )
-		mp->rbuf_count = 0;
-	if ( mp->xbuf_count < 0 )
-		mp->xbuf_count = 0;
-
-#ifdef BSDBSD
-	/* allocate ring area; add 1 entry -- room for alignment */
-	assert( !mp->ring_area );
-	mp->ring_area = malloc(
-							sizeof(*mp->ring_area) *
-								(mp->rbuf_count + mp->xbuf_count + 1),
-							M_DEVBUF,
-							M_WAIT );
-	assert( mp->ring_area );
-#endif
-
-	BSP_mve_stop_hw(mp);
-
-	if ( irq_mask ) {
-		irq_data[mp->port_num].hdl = tid ? mveth_isr : mveth_isr_1;	
-		InstallISRSuccessful = BSP_install_rtems_irq_handler( &irq_data[mp->port_num] );
-		assert( InstallISRSuccessful );
-	}
-
-#ifdef BSDBSD
-#warning fixme
-	/* mark as used */
-	ifp->if_init = (void*)(-1);
-#endif
-
-	if ( rx_ring_size < 0 )
-		irq_mask &= ~ MV643XX_ETH_IRQ_RX_DONE;
-	if ( tx_ring_size < 0 )
-		irq_mask &= ~ MV643XX_ETH_EXT_IRQ_TX_DONE;
-
-	mp->irq_mask = (irq_mask & MV643XX_ETH_IRQ_RX_DONE);
-	if ( (irq_mask &= (MV643XX_ETH_EXT_IRQ_TX_DONE | MV643XX_ETH_EXT_IRQ_LINK_CHG)) ) {
-		mp->irq_mask |= MV643XX_ETH_IRQ_EXT_ENA;
-		mp->xirq_mask = irq_mask;
-	} else {
-		mp->xirq_mask = 0;
-	}
-
-	return mp;
-}
-
-struct mveth_private *
-BSP_mve_setup(
-	int		 unit,
-	rtems_id tid,
-	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
-	void *cleanup_txbuf_arg,
-	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
-	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
-	void *consume_rxbuf_arg,
-	int		rx_ring_size,
-	int		tx_ring_size,
-	int		irq_mask
-)
-{
-struct ifnet         *ifp;
-struct mveth_private *mp,
+struct ifnet         *ifp;
+struct mveth_private *mp;
 
 	if ( unit <= 0 || unit > MV643XXETH_NUM_DRIVER_SLOTS ) {
 		printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, MV643XXETH_NUM_DRIVER_SLOTS);
 		return 0;
-	}
-
-	if ( irq_mask && 0 == tid ) {
-		printk(DRVNAME": must supply a TID if irq_msk not zero\n");
-		return 0;	
-	}
-
-	ifp = &theMvEths[unit-1].arpcom.ac_if;
-
-	if ( ifp->if_init ) {
-		if ( ifp->if_init ) {
-			printk(DRVNAME": instance %i already attached.\n", unit);
-			return 0;
-		}
-	}
-
-	mp  = &theMvEths[unit-1].pvt;
-
-	if ( 0 == mve_setup_internal(
-				mp,
-				unit,
-				tid,
-				0, 0,
-				cleanup_txbuf, cleanup_txbuf_arg,
-				alloc_rxbuf,
-				consume_rxbuf, consume_rxbuf_arg,
-				rx_ring_size, tx_ring_size,
-				irq_mask) ) {
-		return 0;
-	}
-
-	/* mark as used */
-	ifp->if_init = (void*)(-1);
-
-	return mp;
-}
-
-struct mveth_private *
-BSP_mve_setup_1(
-	int		 unit,
-	void     (*isr)(void *isr_arg),
-	void     *isr_arg,
-	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
-	void *cleanup_txbuf_arg,
-	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
-	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
-	void *consume_rxbuf_arg,
-	int		rx_ring_size,
-	int		tx_ring_size,
-	int		irq_mask
-)
-{
-	if ( irq_mask && 0 == isr ) {
-		printk(DRVNAME": must supply an ISR if irq_msk not zero\n");
-		return 0;	
-	}
-
-	return mve_setup_internal(
-				unit,
-				0,
-				isr, isr_arg,
-				cleanup_txbuf, cleanup_txbuf_arg,
-				alloc_rxbuf,
-				consume_rxbuf, consume_rxbuf_arg,
-				rx_ring_size, tx_ring_size,
-				irq_mask);
-}
-
-rtems_id
-BSP_mve_get_tid(struct mveth_private *mp)
-{
-    return mp->tid;
-}
-
-int
-BSP_mve_detach(struct mveth_private *mp)
-{
-#ifdef BSDBSD
-int unit = mp->port_num;
-#endif
-	BSP_mve_stop_hw(mp);
-	if ( mp->irq_mask || mp->xirq_mask ) {
-		if ( !BSP_remove_rtems_irq_handler( &irq_data[mp->port_num] ) )
-			return -1;
-	}
-#ifdef BSDBSD
-#warning FIXME
-	free( (void*)mp->ring_area, M_DEVBUF );
-#endif
-	memset(mp, 0, sizeof(*mp));
-	__asm__ __volatile__("":::"memory");
-	/* mark as unused */
-#ifdef BSDBSD
-	theMvEths[unit].arpcom.ac_if.if_init = 0;
-#endif
-	return 0;
-}
-
-/* MAIN RX-TX ROUTINES
- *
- * BSP_mve_swipe_tx():  descriptor scavenger; releases mbufs
- * BSP_mve_send_buf():  xfer mbufs from IF to chip
- * BSP_mve_swipe_rx():  enqueue received mbufs to interface
- *                    allocate new ones and yield them to the
- *                    chip.
- */
-
-/* clean up the TX ring freeing up buffers */
-int
-BSP_mve_swipe_tx(struct mveth_private *mp)
-{
-int						rval = 0;
-register MvEthTxDesc	d;
-
-	for ( d = mp->d_tx_t; d->buf_ptr; d = NEXT_TXD(d) ) {
-
-		INVAL_DESC(d);
-
-		if (	(TDESC_DMA_OWNED & d->cmd_sts)
-			 &&	(uint32_t)d == MV_READ(MV643XX_ETH_CURRENT_SERVED_TX_DESC(mp->port_num)) )
-			break;
-
-		/* d->u_buf is only set on the last descriptor in a chain;
-		 * we only count errors in the last descriptor;
-		 */
-		if ( d->u_buf ) {
-			mp->cleanup_txbuf(d->u_buf, mp->cleanup_txbuf_arg, (d->cmd_sts & TDESC_ERROR) ? 1 : 0);
-			d->u_buf = 0;
-		}
-
-		d->buf_ptr = 0;
-
-		rval++;
-	}
-	mp->d_tx_t = d;
-	mp->avail += rval;
-
-	return rval;
-}
-
-#ifdef BSDBSD
-
-/* allocate a new cluster and copy an existing chain there;
- * old chain is released...
- */
-static struct mbuf *
-repackage_chain(struct mbuf *m_head)
-{
-struct mbuf *m;
-	MGETHDR(m, M_DONTWAIT, MT_DATA);
-
-	if ( !m ) {
-		goto bail;
-	}
-
-	MCLGET(m, M_DONTWAIT);
-
-	if ( !(M_EXT & m->m_flags) ) {
-		m_freem(m);
-		m = 0;
-		goto bail;
-	}
-
-	m_copydata(m_head, 0, MCLBYTES, mtod(m, caddr_t));
-	m->m_pkthdr.len = m->m_len = m_head->m_pkthdr.len;
-
-bail:
-	m_freem(m_head);
-	return m;
-}
-
-/* Enqueue a mbuf chain or a raw data buffer for transmission;
- * RETURN: #bytes sent or -1 if there are not enough descriptors
- *
- * If 'len' is <=0 then 'm_head' is assumed to point to a mbuf chain.
- * OTOH, a raw data packet may be send (non-BSD driver) by pointing
- * m_head to the start of the data and passing 'len' > 0.
- *
- * Comments: software cache-flushing incurs a penalty if the
- *           packet cannot be queued since it is flushed anyways.
- *           The algorithm is slightly more efficient in the normal
- *			 case, though.
- */
-int
-BSP_mve_send_buf(struct mveth_private *mp, void *m_head, void *data_p, int len)
-{
-int						rval;
-register MvEthTxDesc	l,d,h;
-register struct mbuf	*m1;
-int						nmbs;
-int						ismbuf = (len <= 0);
-
-/* Only way to get here is when we discover that the mbuf chain
- * is too long for the tx ring
- */
-startover:
-
-	rval = 0;
-
-#ifdef MVETH_TESTING 
-	assert(m_head);
-#endif
-
-	/* if no descriptor is available; try to wipe the queue */
-	if ( (mp->avail < 1) && MVETH_CLEAN_ON_SEND(mp)<=0 ) {
-		/* Maybe TX is stalled and needs to be restarted */
-		mveth_start_tx(mp);
-		return -1;
-	}
-
-	h = mp->d_tx_h;
-
-#ifdef MVETH_TESTING 
-	assert( !h->buf_ptr );
-	assert( !h->mb      );
-#endif
-
-	if ( ! (m1 = m_head) )
-		return 0;
-
-	if ( ismbuf ) {
-		/* find first mbuf with actual data */
-		while ( 0 == m1->m_len ) {
-			if ( ! (m1 = m1->m_next) ) {
-				/* end reached and still no data to send ?? */
-				m_freem(m_head);
-				return 0;
-			}
-		}
-	}
-
-	/* Don't use the first descriptor yet because BSP_mve_swipe_tx()
-	 * needs mp->d_tx_h->buf_ptr == NULL as a marker. Hence, we
-	 * start with the second mbuf and fill the first descriptor
-	 * last.
-	 */
-
-	l = h;
-	d = NEXT_TXD(h);
-
-	mp->avail--;
-
-	nmbs = 1;
-	if ( ismbuf ) {
-			register struct mbuf *m;
-			for ( m=m1->m_next; m; m=m->m_next ) {
-					if ( 0 == m->m_len )
-							continue;	/* skip empty mbufs */
-
-					nmbs++;
-
-					if ( mp->avail < 1 && MVETH_CLEAN_ON_SEND(mp)<=0 ) {
-							/* Maybe TX was stalled - try to restart */
-							mveth_start_tx(mp);
-
-							/* not enough descriptors; cleanup...
-							 * the first slot was never used, so we start
-							 * at mp->d_tx_h->next;
-							 */
-							for ( l = NEXT_TXD(h); l!=d; l=NEXT_TXD(l) ) {
-#ifdef MVETH_TESTING
-									assert( l->mb == 0 );
-#endif
-									l->buf_ptr  = 0;
-									l->cmd_sts  = 0;
-									mp->avail++;
-							}
-							mp->avail++;
-							if ( nmbs > TX_AVAILABLE_RING_SIZE(mp) ) {
-									/* this chain will never fit into the ring */
-									if ( nmbs > mp->stats.maxchain )
-											mp->stats.maxchain = nmbs;
-									mp->stats.repack++;
-									if ( ! (m_head = repackage_chain(m_head)) ) {
-											/* no cluster available */
-											mp->stats.odrops++;
-											return 0;
-									}
-									goto startover;
-							}
-							return -1;
-					}
-
-					mp->avail--;
-
-#ifdef MVETH_TESTING
-					assert( d != h      );
-					assert( !d->buf_ptr );
-#endif
-
-					/* fill this slot */
-					rval += mveth_assign_desc(d, m, TDESC_DMA_OWNED);
-
-					FLUSH_BUF(mtod(m, uint32_t), m->m_len);
-
-					l = d;
-					d = NEXT_TXD(d);
-
-					FLUSH_DESC(l);
-			}
-
-		/* fill first slot - don't release to DMA yet */
-		rval += mveth_assign_desc(h, m1, TDESC_FRST);
-
-
-		FLUSH_BUF(mtod(m1, uint32_t), m1->m_len);
-
-	} else {
-		/* fill first slot with raw buffer - don't release to DMA yet */
-		rval += mveth_assign_desc_raw(h, data_p, len, TDESC_FRST);
-
-		FLUSH_BUF( (uint32_t)data_p, len);
-	}
-
-	/* tag last slot; this covers the case where 1st==last */
-	l->cmd_sts      |= TDESC_LAST | TDESC_INT_ENA;
-	/* mbuf goes into last desc */
-	l->u_buf         = m_head;
-
-
-	FLUSH_DESC(l);
-
-	/* Tag end; make sure chip doesn't try to read ahead of here! */
-	l->next->cmd_sts = 0;
-	FLUSH_DESC(l->next);
-
-#ifdef MVETH_DEBUG_TX_DUMP
-	if ( (mveth_tx_dump & (1<<mp->port_num)) ) {
-		int ll,kk;
-		if ( ismbuf ) {
-			struct mbuf *m;
-			for ( kk=0, m=m_head; m; m=m->m_next) {
-				for ( ll=0; ll<m->m_len; ll++ ) {
-					printf("%02X ",*(mtod(m,char*) + ll));
-					if ( ((++kk)&0xf) == 0 )
-						printf("\n");
-				}
-			}
-		} else {
-			for ( ll=0; ll<len; ) {
-				printf("%02X ",*((char*)data_p + ll));
-				if ( ((++ll)&0xf) == 0 )
-					printf("\n");
-			}	
-		}
-		printf("\n");
-	}
-#endif
-
-	membarrier();
-
-	/* turn over the whole chain by flipping ownership of the first desc */
-	h->cmd_sts |= TDESC_DMA_OWNED;
-
-	FLUSH_DESC(h);
-
-	membarrier();
-
-	/* notify the device */
-	MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
-
-	/* Update softc */
-	mp->stats.packet++;
-	if ( nmbs > mp->stats.maxchain )
-		mp->stats.maxchain = nmbs;
-
-	/* remember new head */
-	mp->d_tx_h = d;
-
-	return rval; /* #bytes sent */
-}
-#endif /* BSDBSD */
-
-int
-BSP_mve_send_buf_raw(
-	struct mveth_private *mp,
-	void                 *head_p,
-	int                   h_len,
-	void                 *data_p,
-    int                   d_len)
-{
-int						rval;
-register MvEthTxDesc	l,d,h;
-int						needed;
-void                    *frst_buf;
-int                     frst_len;
-
-	rval = 0;
-
-#ifdef MVETH_TESTING 
-	assert(header || data);
-#endif
-
-	needed = head_p && data_p ? 2 : 1;
-
-	/* if no descriptor is available; try to wipe the queue */
-	if (   ( mp->avail < needed )
-        && ( MVETH_CLEAN_ON_SEND(mp) <= 0 || mp->avail < needed ) ) {
-		/* Maybe TX was stalled and needs a restart */
-		mveth_start_tx(mp);
-		return -1;
-	}
-
-	h = mp->d_tx_h;
-
-#ifdef MVETH_TESTING 
-	assert( !h->buf_ptr );
-	assert( !h->mb      );
-#endif
-
-	/* find the 'first' user buffer */
-	if ( (frst_buf = head_p) ) {
-		frst_len = h_len;
-	} else {
-		frst_buf = data_p;
-		frst_len = d_len;
-	}
-
-	/* Don't use the first descriptor yet because BSP_mve_swipe_tx()
-	 * needs mp->d_tx_h->buf_ptr == NULL as a marker. Hence, we
-	 * start with the second (optional) slot and fill the first
-     * descriptor last.
-	 */
-
-	l = h;
-	d = NEXT_TXD(h);
-
-	mp->avail--;
-
-	if ( needed > 1 ) {
-		mp->avail--;
-#ifdef MVETH_TESTING
-		assert( d != h      );
-		assert( !d->buf_ptr );
-#endif
-		rval += mveth_assign_desc_raw(d, data_p, d_len, TDESC_DMA_OWNED);
-		FLUSH_BUF( (uint32_t)data_p, d_len );
-		d->u_buf = data_p;
-
-		l = d;
-		d = NEXT_TXD(d);
-
-		FLUSH_DESC(l);
-	}
-
-	/* fill first slot with raw buffer - don't release to DMA yet */
-	rval       += mveth_assign_desc_raw(h, frst_buf, frst_len, TDESC_FRST);
-
-	FLUSH_BUF( (uint32_t)frst_buf, frst_len);
-
-	/* tag last slot; this covers the case where 1st==last */
-	l->cmd_sts |= TDESC_LAST | TDESC_INT_ENA;
-
-	/* first buffer of 'chain' goes into last desc */
-	l->u_buf    = frst_buf;
-
-	FLUSH_DESC(l);
-
-	/* Tag end; make sure chip doesn't try to read ahead of here! */
-	l->next->cmd_sts = 0;
-	FLUSH_DESC(l->next);
-
-	membarrier();
-
-	/* turn over the whole chain by flipping ownership of the first desc */
-	h->cmd_sts |= TDESC_DMA_OWNED;
-
-	FLUSH_DESC(h);
-
-	membarrier();
-
-	/* notify the device */
-	MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
-
-	/* Update softc */
-	mp->stats.packet++;
-	if ( needed > mp->stats.maxchain )
-		mp->stats.maxchain = needed;
-
-	/* remember new head */
-	mp->d_tx_h = d;
-
-	return rval; /* #bytes sent */
-}
-
-/* send received buffers upwards and replace them
- * with freshly allocated ones;
- * ASSUMPTION:	buffer length NEVER changes and is set
- *				when the ring is initialized.
- * TS 20060727: not sure if this assumption is still necessary - I believe it isn't.
- */
-
-int
-BSP_mve_swipe_rx(struct mveth_private *mp)
-{
-int						rval = 0, err;
-register MvEthRxDesc	d;
-void					*newbuf;
-int						sz;
-uintptr_t 				baddr;
-
-	for ( d = mp->d_rx_t; ! (INVAL_DESC(d), (RDESC_DMA_OWNED & d->cmd_sts)); d=NEXT_RXD(d) ) {
-
-#ifdef MVETH_TESTING 
-		assert(d->u_buf);
-#endif
-
-		err = (RDESC_ERROR & d->cmd_sts);
-
-		if ( err || !(newbuf = mp->alloc_rxbuf(&sz, &baddr)) ) {
-			/* drop packet and recycle buffer */
-			newbuf = d->u_buf;
-			mp->consume_rxbuf(0, mp->consume_rxbuf_arg, err ? -1 : 0);
-		} else {
-#ifdef MVETH_TESTING
-			assert( d->byte_cnt > 0 );
-#endif
-			mp->consume_rxbuf(d->u_buf, mp->consume_rxbuf_arg, d->byte_cnt);
-
-#ifndef ENABLE_HW_SNOOPING
-			/* could reduce the area to max. ethernet packet size */
-			INVAL_BUF(baddr, sz);
-#endif
-			d->u_buf    = newbuf;
-			d->buf_ptr  = CPUADDR2ENET(baddr);
-			d->buf_size = sz;
-			FLUSH_DESC(d);
-		}
-
-		membarrier();
-
-		d->cmd_sts = RDESC_DMA_OWNED | RDESC_INT_ENA;
-
-		FLUSH_DESC(d);
-
-		rval++;
-	}
-	MV_WRITE(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_RX_START(0));
-	mp->d_rx_t = d;
-	return rval;
-}
-
-/* Stop hardware and clean out the rings */
-void
-BSP_mve_stop_hw(struct mveth_private *mp)
-{
-MvEthTxDesc	d;
-MvEthRxDesc	r;
-int			i;
-
-	mveth_disable_irqs(mp, -1);
+	}
 
-	mveth_stop_tx(mp->port_num);
+	ifp = &theMvEths[unit-1].arpcom.ac_if;
 
-	/* cleanup TX rings */
-	if (mp->d_tx_t) { /* maybe ring isn't initialized yet */
-		for ( i=0, d=mp->tx_ring; i<mp->xbuf_count; i++, d++ ) {
-			/* should be safe to clear ownership */
-			d->cmd_sts &= ~TDESC_DMA_OWNED;
-			FLUSH_DESC(d);
+	if ( ifp->if_init ) {
+		if ( ifp->if_init ) {
+			printk(DRVNAME": instance %i already attached.\n", unit);
+			return 0;
 		}
-		FLUSH_BARRIER();
+	}
 
-		BSP_mve_swipe_tx(mp);
+	mp  = theMvEths[unit-1].pvt;
 
-#ifdef MVETH_TESTING 
-		assert( mp->d_tx_h == mp->d_tx_t );
-		for ( i=0, d=mp->tx_ring; i<mp->xbuf_count; i++, d++ ) {
-			assert( !d->buf_ptr );
-		}
-#endif
+	if ( ! (mp = BSP_mve_create(
+				unit,
+				tid,
+				isr, isr_arg,
+				cleanup_txbuf, cleanup_txbuf_arg,
+				alloc_rxbuf,
+				consume_rxbuf, consume_rxbuf_arg,
+				rx_ring_size, tx_ring_size,
+				irq_mask)) ) {
+		return 0;
 	}
+	theMvEths[unit-1].pvt = mp;
 
-	MV_WRITE(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_RX_STOP_ALL);
-	while ( MV643XX_ETH_RX_ANY_RUNNING & MV_READ(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num)) )
-		/* poll-wait */;
-
-	/* stop serial port */
-	MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num),
-		MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num))
-		& ~( MV643XX_ETH_SERIAL_PORT_ENBL | MV643XX_ETH_FORCE_LINK_FAIL_DISABLE | MV643XX_ETH_FORCE_LINK_PASS)
-		);
-
-	/* clear pending interrupts */
-	MV_WRITE(MV643XX_ETH_INTERRUPT_CAUSE_R(mp->port_num), 0);
-	MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(mp->port_num), 0);
-
-	/* cleanup RX rings */
-	if ( mp->rx_ring ) {
-		for ( i=0, r=mp->rx_ring; i<mp->rbuf_count; i++, r++ ) {
-			/* should be OK to clear ownership flag */
-			r->cmd_sts = 0;
-			FLUSH_DESC(r);
-			mp->consume_rxbuf(r->u_buf, mp->consume_rxbuf_arg, 0);
-			r->u_buf = 0;
+	/* lazy init of mutex (non thread-safe! - we assume 1st initialization is single-threaded) */
+	if ( ! mveth_mtx ) {
+		rtems_status_code sc;
+		sc = rtems_semaphore_create(
+				rtems_build_name('m','v','e','X'),
+				1,
+				RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY | RTEMS_DEFAULT_ATTRIBUTES,
+				0,
+				&mveth_mtx);
+		if ( RTEMS_SUCCESSFUL != sc ) {
+			rtems_error(sc,DRVNAME": creating mutex\n");
+			rtems_panic("unable to proceed\n");
 		}
-		FLUSH_BARRIER();
 	}
 
+	/* mark as used */
+	ifp->if_init = (void*)(-1);
 
+	return mp;
 }
 
-uint32_t mveth_serial_ctrl_config_val = MVETH_SERIAL_CTRL_CONFIG_VAL;
-
-/* Fire up the low-level driver
- *
- * - make sure hardware is halted
- * - enable cache snooping
- * - clear address filters
- * - clear mib counters
- * - reset phy
- * - initialize (or reinitialize) descriptor rings
- * - check that the firmware has set up a reasonable mac address.
- * - generate unicast filter entry for our mac address
- * - write register config values to the chip
- * - start hardware (serial port and SDMA)
- */
-
-void
-BSP_mve_init_hw(struct mveth_private *mp, int promisc, unsigned char *enaddr)
+struct mveth_private *
+BSP_mve_setup(
+	int		 unit,
+	rtems_id tid,
+	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
+	void *cleanup_txbuf_arg,
+	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
+	void *consume_rxbuf_arg,
+	int		rx_ring_size,
+	int		tx_ring_size,
+	int		irq_mask
+)
 {
-int					i;
-uint32_t			v;
-static int			inited = 0;
-
-#ifdef MVETH_DEBUG
-	printk(DRVNAME"%i: Entering BSP_mve_init_hw()\n", mp->port_num+1);
-#endif
-
-	/* since enable/disable IRQ routine only operate on select bitsets
-	 * we must make sure everything is masked initially.
-	 */
-	MV_WRITE(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num),        0);
-	MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num), 0);
-
-	BSP_mve_stop_hw(mp);
-
-	memset(&mp->stats, 0, sizeof(mp->stats));
-
-	mp->promisc = promisc;
-
-	/* MotLoad has cache snooping disabled on the ENET2MEM windows.
-	 * Some comments in (linux) indicate that there are errata
-	 * which cause problems which would be a real bummer.
-	 * We try it anyways...
-	 */
-	if ( !inited ) {
-	unsigned long disbl, bar;
-		inited = 1;	/* FIXME: non-thread safe lazy init */
-		disbl = MV_READ(MV643XX_ETH_BAR_ENBL_R);
-			/* disable all 6 windows */
-			MV_WRITE(MV643XX_ETH_BAR_ENBL_R, MV643XX_ETH_BAR_DISBL_ALL);
-			/* set WB snooping on enabled bars */
-			for ( i=0; i<MV643XX_ETH_NUM_BARS*8; i+=8 ) {
-				if ( (bar = MV_READ(MV643XX_ETH_BAR_0 + i)) && MV_READ(MV643XX_ETH_SIZE_R_0 + i) ) {
-#ifdef ENABLE_HW_SNOOPING
-					MV_WRITE(MV643XX_ETH_BAR_0 + i, bar | MV64360_ENET2MEM_SNOOP_WB);
-#else
-					MV_WRITE(MV643XX_ETH_BAR_0 + i, bar & ~MV64360_ENET2MEM_SNOOP_MSK);
-#endif
-					/* read back to flush fifo [linux comment] */
-					(void)MV_READ(MV643XX_ETH_BAR_0 + i);
-				}
-			}
-			/* restore/re-enable */
-		MV_WRITE(MV643XX_ETH_BAR_ENBL_R, disbl);
+	if ( irq_mask && 0 == tid ) {
+		printk(DRVNAME": must supply a TID if irq_msk not zero\n");
+		return 0;	
 	}
 
-	mveth_clear_mib_counters(mp);
-	mveth_clear_addr_filters(mp);
-
-/*	Just leave it alone...
-	reset_phy();
-*/
-
-	if ( mp->rbuf_count > 0 ) {
-		mp->rx_ring = (MvEthRxDesc)MV643XX_ALIGN(mp->ring_area, RING_ALIGNMENT);
-		mveth_init_rx_desc_ring(mp);
-	}
+	return mve_setup_bsd(
+				unit,
+				tid,
+				0, 0,
+				cleanup_txbuf, cleanup_txbuf_arg,
+				alloc_rxbuf,
+				consume_rxbuf, consume_rxbuf_arg,
+				rx_ring_size, tx_ring_size,
+				irq_mask);
+}
 
-	if ( mp->xbuf_count > 0 ) {
-		mp->tx_ring = (MvEthTxDesc)mp->rx_ring + mp->rbuf_count;
-		mveth_init_tx_desc_ring(mp);
+struct mveth_private *
+BSP_mve_setup_1(
+	int		 unit,
+	void     (*isr)(void *isr_arg),
+	void     *isr_arg,
+	void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred), 
+	void *cleanup_txbuf_arg,
+	void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+	void (*consume_rxbuf)(void *user_buf, void *closure, int len),
+	void *consume_rxbuf_arg,
+	int		rx_ring_size,
+	int		tx_ring_size,
+	int		irq_mask
+)
+{
+	if ( irq_mask && 0 == isr ) {
+		printk(DRVNAME": must supply an ISR if irq_msk not zero\n");
+		return 0;	
 	}
 
-	if ( enaddr ) {
-		/* set ethernet address from arpcom struct */
-#ifdef MVETH_DEBUG
-		printk(DRVNAME"%i: Writing MAC addr ", mp->port_num+1);
-		for (i=5; i>=0; i--) {
-			printk("%02X%c", enaddr[i], i?':':'\n');
-		}
-#endif
-		mveth_write_eaddr(mp, enaddr);
-	}
+	return mve_setup_bsd(
+				unit,
+				0,
+				isr, isr_arg,
+				cleanup_txbuf, cleanup_txbuf_arg,
+				alloc_rxbuf,
+				consume_rxbuf, consume_rxbuf_arg,
+				rx_ring_size, tx_ring_size,
+				irq_mask);
+}
 
-	/* set mac address and unicast filter */
+/* allocate a new cluster and copy an existing chain there;
+ * old chain is released...
+ */
+static struct mbuf *
+repackage_chain(struct mbuf *m_head)
+{
+struct mbuf *m;
+	MGETHDR(m, M_DONTWAIT, MT_DATA);
 
-	{
-	uint32_t machi, maclo;
-		maclo = MV_READ(MV643XX_ETH_MAC_ADDR_LO(mp->port_num));
-		machi = MV_READ(MV643XX_ETH_MAC_ADDR_HI(mp->port_num));
-		/* ASSUME: firmware has set the mac address for us
-		 *         - if assertion fails, we have to do more work...
-		 */
-		assert( maclo && machi && maclo != 0xffffffff && machi != 0xffffffff );
-		mveth_ucfilter(mp, maclo&0xff, 1/* accept */);
-	}
-	
-	/* port, serial and sdma configuration */
-	v = MVETH_PORT_CONFIG_VAL;
-	if ( promisc ) {
-		/* multicast filters were already set up to
-		 * accept everything (mveth_clear_addr_filters())
-		 */
-		v |= MV643XX_ETH_UNICAST_PROMISC_MODE;
-	} else {
-		v &= ~MV643XX_ETH_UNICAST_PROMISC_MODE;
+	if ( !m ) {
+		goto bail;
 	}
-	MV_WRITE(MV643XX_ETH_PORT_CONFIG_R(mp->port_num),
-				v);
-	MV_WRITE(MV643XX_ETH_PORT_CONFIG_XTEND_R(mp->port_num),
-				MVETH_PORT_XTEND_CONFIG_VAL);
 
-	v  = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num));
-	v &= ~(MVETH_SERIAL_CTRL_CONFIG_MSK);
-	v |= mveth_serial_ctrl_config_val;
-	MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num), v);
+	MCLGET(m, M_DONTWAIT);
 
-#ifdef BSDMII
-#warning FIXME
-	i = IFM_MAKEWORD(0, 0, 0, 0);
-	if ( 0 == BSP_mve_media_ioctl(mp, SIOCGIFMEDIA, &i) ) {
-	    if ( (IFM_LINK_OK & i) ) {
-			mveth_update_serial_port(mp, i);
-		}
+	if ( !(M_EXT & m->m_flags) ) {
+		m_freem(m);
+		m = 0;
+		goto bail;
 	}
-#endif
-
-	/* enable serial port */
-	v  = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num));
-	MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num),
-				v | MV643XX_ETH_SERIAL_PORT_ENBL);
 
-#ifndef __BIG_ENDIAN__
-#error	"byte swapping needs to be disabled for little endian machines"
-#endif
-	MV_WRITE(MV643XX_ETH_SDMA_CONFIG_R(mp->port_num), MVETH_SDMA_CONFIG_VAL);
+	m_copydata(m_head, 0, MCLBYTES, mtod(m, caddr_t));
+	m->m_pkthdr.len = m->m_len = m_head->m_pkthdr.len;
 
-	/* allow short frames */
-	MV_WRITE(MV643XX_ETH_RX_MIN_FRAME_SIZE_R(mp->port_num), MVETH_MIN_FRAMSZ_CONFIG_VAL);
+bail:
+	m_freem(m_head);
+	return m;
+}
 
-	MV_WRITE(MV643XX_ETH_INTERRUPT_CAUSE_R(mp->port_num), 0);
-	MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(mp->port_num), 0);
-	/* TODO: set irq coalescing */
+typedef struct BsdMveIter {
+	MveEthBufIter it;
+	struct mbuf  *m;
+	struct mbuf  *h;
+} BsdMveIter;
 
-	/* enable Rx */
-	if ( mp->rbuf_count > 0 ) {
-		MV_WRITE(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_RX_START(0));
+static MveEthBufIter *fillIter(struct mbuf *m, BsdMveIter *it)
+{
+	if ( (it->m = (void*)m) ) {
+		it->it.data = mtod(m, void*);
+		it->it.len  = m->m_len;
+		it->it.uptr = m->m_next ? it->h : 0;
+		return (MveEthBufIter*)it;
 	}
+	return 0;
+}
 
-	mveth_enable_irqs(mp, -1);
-
-#ifdef MVETH_DEBUG
-	printk(DRVNAME"%i: Leaving BSP_mve_init_hw()\n", mp->port_num+1);
-#endif
+static MveEthBufIter *nextBuf(const MveEthBufIter *arg)
+{
+BsdMveIter *it = (BsdMveIter*)arg;
+	return fillIter( it->m->m_next, it );
 }
 
-/* read ethernet address from hw to buffer */
-void
-BSP_mve_read_eaddr(struct mveth_private *mp, unsigned char *oeaddr)
+int
+BSP_mve_send_buf(struct mveth_private *mp, void *m_head, void *data_p, int len)
 {
-int				i;
-uint32_t		x;
-unsigned char	buf[6], *eaddr;
+int						rval;
+register struct mbuf	*m1;
+BsdMveIter              iter;
 
-	eaddr = oeaddr ? oeaddr : buf;
+/* Only way to get here is when we discover that the mbuf chain
+ * is too long for the tx ring
+ */
+startover:
 
-	eaddr += 5;
-	x = MV_READ(MV643XX_ETH_MAC_ADDR_LO(mp->port_num));
+	rval = 0;
 
-	/* lo word */
- 	for (i=2; i; i--, eaddr--) {
-		*eaddr = (unsigned char)(x & 0xff);
-		x>>=8;
-	}
+#ifdef MVETH_TESTING 
+	assert(m_head);
+#endif
+
+	if ( ! (m1 = m_head) )
+		return 0;
 
-	x = MV_READ(MV643XX_ETH_MAC_ADDR_HI(mp->port_num));
-	/* hi word */
- 	for (i=4; i; i--, eaddr--) {
-		*eaddr = (unsigned char)(x & 0xff);
-		x>>=8;
+	/* find first mbuf with actual data */
+	while ( 0 == m1->m_len ) {
+		if ( ! (m1 = m1->m_next) ) {
+			/* end reached and still no data to send ?? */
+			m_freem(m_head);
+			return 0;
+		}
 	}
 
-	if ( !oeaddr ) {
-		printf("%02X",buf[0]);
-		for (i=1; i<sizeof(buf); i++)
-			printf(":%02X",buf[i]);
+#ifdef MVETH_DEBUG_TX_DUMP
+	if ( (mveth_tx_dump & (1<<mp->port_num)) ) {
+		int ll,kk;
+		struct mbuf *m;
+		for ( kk=0, m=m_head; m; m=m->m_next) {
+			for ( ll=0; ll<m->m_len; ll++ ) {
+				printf("%02X ",*(mtod(m,char*) + ll));
+				if ( ((++kk)&0xf) == 0 )
+					printf("\n");
+			}
+		}
 		printf("\n");
 	}
+#endif
+
+	fillIter( m_head, &iter );
+	iter.h = m_head;
+
+	rval = BSP_mve_send_buf_chain( mp, nextBuf, &iter.it );
+
+	if ( -2 == rval ) {
+		if ( ! (m_head = repackage_chain( m_head )) ) {
+			/* no cluster available */
+			/* No access to this counter, unfortunately			
+			mp->stats.odrops++;
+			 */
+			return 0;
+		}
+		goto startover;
+	}
+
+	return rval;
 }
 
-#ifdef BSDMII
 int
 BSP_mve_media_ioctl(struct mveth_private *mp, int cmd, int *parg)
 {
@@ -2770,46 +868,7 @@ int rval;
 	REGUNLOCK();
 	return rval;
 }
-#endif
-
-void
-BSP_mve_enable_irqs(struct mveth_private *mp)
-{
-	mveth_enable_irqs(mp, -1);
-}
-
-void
-BSP_mve_disable_irqs(struct mveth_private *mp)
-{
-	mveth_disable_irqs(mp, -1);
-}
-
-uint32_t
-BSP_mve_ack_irqs(struct mveth_private *mp)
-{
-	return mveth_ack_irqs(mp, -1);
-}
-
-
-void
-BSP_mve_enable_irq_mask(struct mveth_private *mp, uint32_t mask)
-{
-	mveth_enable_irqs(mp, mask);
-}
-
-uint32_t
-BSP_mve_disable_irq_mask(struct mveth_private *mp, uint32_t mask)
-{
-	return mveth_disable_irqs(mp, mask);
-}
 
-uint32_t
-BSP_mve_ack_irq_mask(struct mveth_private *mp, uint32_t mask)
-{
-	return mveth_ack_irqs(mp, mask);
-}
-
-#ifdef BSDMII
 int
 BSP_mve_ack_link_chg(struct mveth_private *mp, int *pmedia)
 {
@@ -2817,9 +876,25 @@ int media = IFM_MAKEWORD(0,0,0,0);
 
 	if ( 0 == BSP_mve_media_ioctl(mp, SIOCGIFMEDIA, &media)) {
 		if ( IFM_LINK_OK & media ) {
-			mveth_update_serial_port(mp, media);
-			/* If TX stalled because there was no buffer then whack it */
-			mveth_start_tx(mp);
+			int serport_cfg = 0;
+
+			if ( IFM_FDX & media ) {
+				serport_cfg |= MV643XX_MEDIA_FD;
+			}
+
+			switch ( IFM_SUBTYPE(media) ) {
+				default: /* treat as 10 */
+					serport_cfg |= MV643XX_MEDIA_10;
+					break;
+				case IFM_100_TX:
+					serport_cfg |= MV643XX_MEDIA_100;
+					break;
+				case IFM_1000_T:
+					serport_cfg |= MV643XX_MEDIA_1000;
+					break;
+			}
+
+			BSP_mve_update_serial_port(mp, serport_cfg);
 		}
 		if ( pmedia )
 			*pmedia = media;
@@ -2827,9 +902,6 @@ int media = IFM_MAKEWORD(0,0,0,0);
 	}
 	return -1;
 }
-#endif
-
-#ifdef BSDBSD
 
 /* BSDNET SUPPORT/GLUE ROUTINES */
 
@@ -2839,7 +911,7 @@ mveth_set_filters(struct ifnet *ifp);
 STATIC void
 mveth_stop(struct mveth_softc *sc)
 {
-	BSP_mve_stop_hw(&sc->pvt);
+	BSP_mve_stop_hw(sc->pvt);
 	sc->arpcom.ac_if.if_timer = 0;
 }
 
@@ -2938,56 +1010,6 @@ struct mbuf  *mb  = buf;
 	ifp->if_obytes += mb->m_pkthdr.len;
 	m_freem(mb);
 }
-#endif /*BSDBSD*/
-
-static void
-dump_update_stats(struct mveth_private *mp, FILE *f)
-{
-int      p = mp->port_num;
-int      idx;
-uint32_t v;
-
-	if ( !f )
-		f = stdout;
-
-	fprintf(f, DRVNAME"%i Statistics:\n",        mp->port_num + 1);
-	fprintf(f, "  # IRQS:                 %i\n", mp->stats.irqs);
-	fprintf(f, "  Max. mbuf chain length: %i\n", mp->stats.maxchain);
-	fprintf(f, "  # repacketed:           %i\n", mp->stats.repack);
-	fprintf(f, "  # packets:              %i\n", mp->stats.packet);
-	fprintf(f, "MIB Counters:\n");
-	for ( idx = MV643XX_ETH_MIB_GOOD_OCTS_RCVD_LO>>2;
-			idx < MV643XX_ETH_NUM_MIB_COUNTERS;
-			idx++ ) {
-		switch ( idx ) {
-			case MV643XX_ETH_MIB_GOOD_OCTS_RCVD_LO>>2:
-				mp->stats.mib.good_octs_rcvd += read_long_mib_counter(p, idx);
-				fprintf(f, mibfmt[idx], mp->stats.mib.good_octs_rcvd);
-				idx++;
-				break;
-
-			case MV643XX_ETH_MIB_GOOD_OCTS_SENT_LO>>2:
-				mp->stats.mib.good_octs_sent += read_long_mib_counter(p, idx);
-				fprintf(f, mibfmt[idx], mp->stats.mib.good_octs_sent);
-				idx++;
-				break;
-
-			default:
-				v = ((uint32_t*)&mp->stats.mib)[idx] += read_mib_counter(p, idx);
-				fprintf(f, mibfmt[idx], v);
-				break;
-		}
-	}
-	fprintf(f, "\n");
-}
-
-void
-BSP_mve_dump_stats(struct mveth_private *mp, FILE *f)
-{
-	dump_update_stats(mp, f);
-}
-
-#ifdef BSDBSD
 
 /* BSDNET DRIVER CALLBACKS */
 
@@ -2998,10 +1020,10 @@ struct mveth_softc	*sc  = arg;
 struct ifnet		*ifp = &sc->arpcom.ac_if;
 int                 media;
 
-	BSP_mve_init_hw(&sc->pvt, ifp->if_flags & IFF_PROMISC, sc->arpcom.ac_enaddr);
+	BSP_mve_init_hw(sc->pvt, ifp->if_flags & IFF_PROMISC, sc->arpcom.ac_enaddr);
 
 	media = IFM_MAKEWORD(0, 0, 0, 0);
-	if ( 0 == BSP_mve_media_ioctl(&sc->pvt, SIOCGIFMEDIA, &media) ) {
+	if ( 0 == BSP_mve_media_ioctl(sc->pvt, SIOCGIFMEDIA, &media) ) {
 	    if ( (IFM_LINK_OK & media) ) {
 			ifp->if_flags &= ~IFF_OACTIVE;
 		} else {
@@ -3026,7 +1048,7 @@ struct mbuf			*m  = 0;
 
 	while ( ifp->if_snd.ifq_head ) {
 		IF_DEQUEUE( &ifp->if_snd, m );
-		if ( BSP_mve_send_buf(&sc->pvt, m, 0, 0) < 0 ) {
+		if ( BSP_mve_send_buf(sc->pvt, m, 0, 0) < 0 ) {
 			IF_PREPEND( &ifp->if_snd, m);
 			ifp->if_flags |= IFF_OACTIVE;
 			break;
@@ -3055,22 +1077,16 @@ static void
 mveth_set_filters(struct ifnet *ifp)
 {
 struct mveth_softc  *sc = ifp->if_softc;
-uint32_t              v;
 
-	v = MV_READ(MV643XX_ETH_PORT_CONFIG_R(sc->pvt.port_num));
-	if ( ifp->if_flags & IFF_PROMISC )
-		v |= MV643XX_ETH_UNICAST_PROMISC_MODE;
-	else
-		v &= ~MV643XX_ETH_UNICAST_PROMISC_MODE;
-	MV_WRITE(MV643XX_ETH_PORT_CONFIG_R(sc->pvt.port_num), v);
+	BSP_mve_promisc_set( sc->pvt, !!(ifp->if_flags & IFF_PROMISC));
 
 	if ( ifp->if_flags & (IFF_PROMISC | IFF_ALLMULTI) ) {
-		BSP_mve_mcast_filter_accept_all(&sc->pvt);
+		BSP_mve_mcast_filter_accept_all(sc->pvt);
 	} else {
 		struct ether_multi     *enm;
 		struct ether_multistep step;
 
-		BSP_mve_mcast_filter_clear( &sc->pvt );
+		BSP_mve_mcast_filter_clear( sc->pvt );
 		
 		ETHER_FIRST_MULTI(step, (struct arpcom *)ifp, enm);
 
@@ -3078,7 +1094,7 @@ uint32_t              v;
 			if ( memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN) )
 				assert( !"Should never get here; IFF_ALLMULTI should be set!" );
 
-			BSP_mve_mcast_filter_accept_add(&sc->pvt, enm->enm_addrlo);
+			BSP_mve_mcast_filter_accept_add(sc->pvt, enm->enm_addrlo);
 
 			ETHER_NEXT_MULTI(step, enm);
 		}
@@ -3102,14 +1118,6 @@ int					f;
 					mveth_init(sc);
 				} else {
 					if ( (f & IFF_PROMISC) != (sc->bsd.oif_flags & IFF_PROMISC) ) {
-						/* Note: in all other scenarios the 'promisc' flag
-						 * in the low-level driver [which affects the way
-						 * the multicast filter is setup: accept none vs.
-						 * accept all in promisc mode] is eventually
-						 * set when the IF is brought up...
-						 */
-						sc->pvt.promisc = (f & IFF_PROMISC);
-
 						mveth_set_filters(ifp);
 					}
 					/* FIXME: other flag changes are ignored/unimplemented */
@@ -3125,7 +1133,7 @@ int					f;
 
   		case SIOCGIFMEDIA:
   		case SIOCSIFMEDIA:
-			error = BSP_mve_media_ioctl(&sc->pvt, cmd, &ifr->ifr_media);
+			error = BSP_mve_media_ioctl(sc->pvt, cmd, &ifr->ifr_media);
 		break;
  
 		case SIOCADDMULTI:
@@ -3146,7 +1154,7 @@ int					f;
 		break;
 
  		case SIO_RTEMS_SHOW_STATS:
-			dump_update_stats(&sc->pvt, stdout);
+			BSP_mve_dump_stats(sc->pvt, stdout);
 		break;
 
 		default:
@@ -3187,13 +1195,13 @@ rtems_event_set		evs;
 					continue;
 				}
 
-				x = mveth_ack_irqs(&sc->pvt, -1);
+				x = BSP_mve_ack_irqs(sc->pvt);
 
 				if ( MV643XX_ETH_EXT_IRQ_LINK_CHG & x ) {
 					/* phy status changed */
 					int media;
 
-					if ( 0 == BSP_mve_ack_link_chg(&sc->pvt, &media) ) {
+					if ( 0 == BSP_mve_ack_link_chg(sc->pvt, &media) ) {
 						if ( IFM_LINK_OK & media ) {
 							ifp->if_flags &= ~IFF_OACTIVE;
 							mveth_start(ifp);
@@ -3204,26 +1212,24 @@ rtems_event_set		evs;
 					}
 				}
 				/* free tx chain */
-				if ( (MV643XX_ETH_EXT_IRQ_TX_DONE & x) && BSP_mve_swipe_tx(&sc->pvt) ) {
+				if ( (MV643XX_ETH_EXT_IRQ_TX_DONE & x) && BSP_mve_swipe_tx(sc->pvt) ) {
 					ifp->if_flags &= ~IFF_OACTIVE;
-					if ( TX_AVAILABLE_RING_SIZE(&sc->pvt) == sc->pvt.avail )
+#warning FIXME
+#ifdef BSDBSD
+					if ( TX_AVAILABLE_RING_SIZE(sc->pvt) == sc->pvt->avail )
 						ifp->if_timer = 0;
+#endif
 					mveth_start(ifp);
 				}
 				if ( (MV643XX_ETH_IRQ_RX_DONE & x) )
-					BSP_mve_swipe_rx(&sc->pvt);
+					BSP_mve_swipe_rx(sc->pvt);
 
-				mveth_enable_irqs(&sc->pvt, -1);
+				BSP_mve_enable_irqs(sc->pvt);
 			}
 		}
 	}
 }
 
-#ifdef  MVETH_DETACH_HACK
-static int mveth_detach(struct mveth_softc *sc);
-#endif
-
-
 /* PUBLIC RTEMS BSDNET ATTACH FUNCTION */
 int
 rtems_mve_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
@@ -3241,8 +1247,6 @@ struct	ifnet		*ifp;
 
 	sc  = &theMvEths[unit-1];
 	ifp = &sc->arpcom.ac_if;
-	sc->pvt.port_num = unit-1;
-	sc->pvt.phy      = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*sc->pvt.port_num)) & 0x1f;
 
 	if ( attaching ) {
 		if ( ifp->if_init ) {
@@ -3275,7 +1279,7 @@ struct	ifnet		*ifp;
 			return -1;
 		}
 
-		if ( nmbclusters < sc->pvt.rbuf_count * cfgUnits + 60 /* arbitrary */ )  {
+		if ( nmbclusters < ifcfg->rbuf_count * cfgUnits + 60 /* arbitrary */ )  {
 			printk(DRVNAME"%i: (mv643xx ethernet) Your application has not enough mbuf clusters\n", unit);
 			printk(     "                         configured for this driver.\n");
 			return -1;
@@ -3285,7 +1289,7 @@ struct	ifnet		*ifp;
 			memcpy(sc->arpcom.ac_enaddr, ifcfg->hardware_address, ETHER_ADDR_LEN);
 		} else {
 			/* read back from hardware assuming that MotLoad already had set it up */
-			BSP_mve_read_eaddr(&sc->pvt, sc->arpcom.ac_enaddr);
+			BSP_mve_read_eaddr(sc->pvt, sc->arpcom.ac_enaddr);
 		}
 
 		ifp->if_softc			= sc;
@@ -3318,29 +1322,18 @@ struct	ifnet		*ifp;
 
 		/* NOTE: ether_output drops packets if ifq_len >= ifq_maxlen
 		 *       but this is the packet count, not the fragment count!
-		ifp->if_snd.ifq_maxlen	= sc->pvt.xbuf_count;
+		ifp->if_snd.ifq_maxlen	= sc->pvt->buf_count;
 		*/
 		ifp->if_snd.ifq_maxlen	= ifqmaxlen;
 
-#ifdef  MVETH_DETACH_HACK
-		if ( !ifp->if_addrlist ) /* do only the first time [reattach hack] */
-#endif
 		{
 			if_attach(ifp);
 			ether_ifattach(ifp);
 		}
 
 	} else {
-#ifdef  MVETH_DETACH_HACK
-		if ( !ifp->if_init ) {
-			printk(DRVNAME": instance %i not attached.\n", unit);
-			return -1;
-		}
-		return mveth_detach(sc);
-#else
 		printk(DRVNAME": interface detaching not implemented\n");
 		return -1;
-#endif
 	}
 
 	return 0;
@@ -3353,8 +1346,6 @@ mveth_early_init(int idx)
 	if ( idx < 0 || idx >= MV643XXETH_NUM_DRIVER_SLOTS )
 		return -1;
 
-	/* determine the phy */
-	theMvEths[idx].pvt.phy = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*idx)) & 0x1f;
 	return 0;
 }
 
@@ -3366,7 +1357,7 @@ int rval;
 	if ( idx < 0 || idx >= MV643XXETH_NUM_DRIVER_SLOTS )
 		return -1;
 
-	rval = mveth_mii_read(&theMvEths[idx].pvt, reg);
+	rval = BSP_mve_mii_read_early(idx, reg);
 	return rval < 0 ? rval : rval & 0xffff;
 }
 
@@ -3376,7 +1367,7 @@ mveth_early_write_phy(int idx, unsigned reg, unsigned val)
 	if ( idx < 0 || idx >= MV643XXETH_NUM_DRIVER_SLOTS )
 		return -1;
 
-	mveth_mii_write(&theMvEths[idx].pvt, reg, val);
+	BSP_mve_mii_write_early(idx, reg, val);
 	return 0;
 }
 
@@ -3391,8 +1382,6 @@ rtems_mve_early_link_check_ops = {
 
 /* DEBUGGING */
 
-#endif /*BSDBSD*/
-
 #ifdef MVETH_DEBUG
 /* Display/dump descriptor rings */
 
@@ -3404,7 +1393,7 @@ if (1) {
 MvEthRxDesc pr;
 printf("RX:\n");
 
-	for (i=0, pr=sc->pvt.rx_ring; i<sc->pvt.rbuf_count; i++, pr++) {
+	for (i=0, pr=sc->pvt->rx_ring; i<sc->pvt->rbuf_count; i++, pr++) {
 #ifndef ENABLE_HW_SNOOPING
 		/* can't just invalidate the descriptor - if it contains
 		 * data that hasn't been flushed yet, we create an inconsistency...
@@ -3423,7 +1412,7 @@ printf("RX:\n");
 if (1) {
 MvEthTxDesc pt;
 printf("TX:\n");
-	for (i=0, pt=sc->pvt.tx_ring; i<sc->pvt.xbuf_count; i++, pt++) {
+	for (i=0, pt=sc->pvt->tx_ring; i<sc->pvt->xbuf_count; i++, pt++) {
 #ifndef ENABLE_HW_SNOOPING
 		rtems_bsdnet_semaphore_obtain();
 		INVAL_DESC(pt);
@@ -3441,79 +1430,3 @@ printf("TX:\n");
 }
 
 #endif
-
-/* DETACH HACK DETAILS */
-
-#ifdef  MVETH_DETACH_HACK
-int
-_cexpModuleFinalize(void *mh)
-{
-int i;
-	for ( i=0; i<MV643XXETH_NUM_DRIVER_SLOTS; i++ ) {
-		if ( theMvEths[i].arpcom.ac_if.if_init ) {
-			printf("Interface %i still attached; refuse to unload\n", i+1);
-			return -1;
-		}
-	}
-	/* delete task; since there are no attached interfaces, it should block
-	 * for events and hence not hold the semaphore or other resources...
-	 */
-	rtems_task_delete(mveth_tid);
-	return 0;
-}
-
-/* ugly hack to allow unloading/reloading the driver core.
- * needed because rtems' bsdnet release doesn't implement
- * if_detach(). Therefore, we bring the interface down but
- * keep the device record alive...
- */
-static void
-ether_ifdetach_pvt(struct ifnet *ifp)
-{
-        ifp->if_flags = 0;
-        ifp->if_ioctl = 0;
-        ifp->if_start = 0;
-        ifp->if_watchdog = 0;
-        ifp->if_init  = 0;
-}
-
-static int
-mveth_detach(struct mveth_softc *sc)
-{
-struct ifnet	*ifp = &sc->arpcom.ac_if;
-	if ( ifp->if_init ) {
-		if ( ifp->if_flags & (IFF_UP | IFF_RUNNING) ) {
-			printf(DRVNAME"%i: refuse to detach; interface still up\n",sc->pvt.port_num+1);
-			return -1;
-		}
-		mveth_stop(sc);
-/* not implemented in BSDnet/RTEMS (yet) but declared in header */
-#define ether_ifdetach ether_ifdetach_pvt
-		ether_ifdetach(ifp);
-	}
-	free( (void*)sc->pvt.ring_area, M_DEVBUF );
-	sc->pvt.ring_area = 0;
-	sc->pvt.tx_ring   = 0;
-	sc->pvt.rx_ring   = 0;
-	sc->pvt.d_tx_t    = sc->pvt.d_tx_h   = 0;
-	sc->pvt.d_rx_t    = 0;
-	sc->pvt.avail     = 0;
-	/* may fail if ISR was not installed yet */
-	BSP_remove_rtems_irq_handler( &irq_data[sc->pvt.port_num] );
-	return 0;
-}
-
-#ifdef MVETH_DEBUG
-struct rtems_bsdnet_ifconfig mveth_dbg_config = {
-	name:				DRVNAME"1",
-	attach:				rtems_mve_attach,
-	ip_address:			"192.168.2.10",		/* not used by rtems_bsdnet_attach */
-	ip_netmask:			"255.255.255.0",	/* not used by rtems_bsdnet_attach */
-	hardware_address:	0, /* (void *) */
-	ignore_broadcast:	0,					/* TODO driver should honour this  */
-	mtu:				0,
-	rbuf_count:			0,					/* TODO driver should honour this  */
-	xbuf_count:			0,					/* TODO driver should honour this  */
-};
-#endif
-#endif
-- 
2.26.2



More information about the devel mailing list