Skip site navigation (1)Skip section navigation (2)
Date:      Mon, 10 Jan 2011 03:48:42 +0000 (UTC)
From:      Juli Mallett <jmallett@FreeBSD.org>
To:        src-committers@freebsd.org, svn-src-all@freebsd.org, svn-src-head@freebsd.org
Subject:   svn commit: r217214 - in head/sys: contrib/octeon-sdk mips/cavium mips/conf
Message-ID:  <201101100348.p0A3mgGo066037@svn.freebsd.org>

next in thread | raw e-mail | index | archive | help
Author: jmallett
Date: Mon Jan 10 03:48:41 2011
New Revision: 217214
URL: http://svn.freebsd.org/changeset/base/217214

Log:
  o) Expand the CIU driver to be aware of newly-allocated parts of the IRQ range.
  o) Add 'octm', a trivial driver for the 10/100 management ports found on some
     Octeon systems.
  o) Make the Simple Executive's management port helper routines compile on
     FreeBSD (namely by not doing math on void pointers.)
  o) Add a cvmx_mgmt_port_sendm routine to the Simple Executive to send an mbuf
     so there is only one copy in the transmit path, rather than having to first
     copy the mbuf to an intermediate buffer and then copy that to the Simple
     Executive's transmit ring.
  o) Properly work out MII addresses of management ports on the Lanner MR-730.
     XXX The MR-730 also needs some patches to the MII read/write routines, but
         this is sufficient for now.  Media detection will be fixed in the future
         when I can spend more time reading the vendor-supplied patches.

Added:
  head/sys/mips/cavium/if_octm.c   (contents, props changed)
Modified:
  head/sys/contrib/octeon-sdk/cvmx-helper-board.c
  head/sys/contrib/octeon-sdk/cvmx-mgmt-port.c
  head/sys/contrib/octeon-sdk/cvmx-mgmt-port.h
  head/sys/mips/cavium/ciu.c
  head/sys/mips/cavium/cvmx_config.h
  head/sys/mips/cavium/files.octeon1
  head/sys/mips/conf/OCTEON1

Modified: head/sys/contrib/octeon-sdk/cvmx-helper-board.c
==============================================================================
--- head/sys/contrib/octeon-sdk/cvmx-helper-board.c	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/contrib/octeon-sdk/cvmx-helper-board.c	Mon Jan 10 03:48:41 2011	(r217214)
@@ -272,6 +272,8 @@ int cvmx_helper_board_get_mii_address(in
                 return ipd_port - 16;
 	    return -1;
 	case CVMX_BOARD_TYPE_CUST_LANNER_MR730:
+            if ((ipd_port >= CVMX_HELPER_BOARD_MGMT_IPD_PORT) && (ipd_port < (CVMX_HELPER_BOARD_MGMT_IPD_PORT + 2)))
+		return (ipd_port - CVMX_HELPER_BOARD_MGMT_IPD_PORT) + 0x81;
             if ((ipd_port >= 0) && (ipd_port < 4))
                 return ipd_port;
 	    return -1;

Modified: head/sys/contrib/octeon-sdk/cvmx-mgmt-port.c
==============================================================================
--- head/sys/contrib/octeon-sdk/cvmx-mgmt-port.c	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/contrib/octeon-sdk/cvmx-mgmt-port.c	Mon Jan 10 03:48:41 2011	(r217214)
@@ -112,7 +112,7 @@ CVMX_SHARED cvmx_mgmt_port_state_t *cvmx
  *
  * @return Number of ports
  */
-int __cvmx_mgmt_port_num_ports(void)
+static int __cvmx_mgmt_port_num_ports(void)
 {
     if (OCTEON_IS_MODEL(OCTEON_CN56XX))
         return 1;
@@ -554,6 +554,62 @@ cvmx_mgmt_port_result_t cvmx_mgmt_port_s
 }
 
 
+#if defined(__FreeBSD__)
+/**
+ * Send a packet out the management port. The packet is copied so
+ * the input mbuf isn't used after this call.
+ *
+ * @param port       Management port
+ * @param m          Packet mbuf (with pkthdr)
+ *
+ * @return CVMX_MGMT_PORT_SUCCESS or an error code
+ */
+cvmx_mgmt_port_result_t cvmx_mgmt_port_sendm(int port, const struct mbuf *m)
+{
+    cvmx_mgmt_port_state_t *state;
+    cvmx_mixx_oring2_t mix_oring2;
+
+    if ((port < 0) || (port >= __cvmx_mgmt_port_num_ports()))
+        return CVMX_MGMT_PORT_INVALID_PARAM;
+
+    /* Max sure the packet size is valid */
+    if ((m->m_pkthdr.len < 1) || (m->m_pkthdr.len > CVMX_MGMT_PORT_TX_BUFFER_SIZE))
+        return CVMX_MGMT_PORT_INVALID_PARAM;
+
+    state = cvmx_mgmt_port_state_ptr + port;
+
+    cvmx_spinlock_lock(&state->lock);
+
+    mix_oring2.u64 = cvmx_read_csr(CVMX_MIXX_ORING2(port));
+    if (mix_oring2.s.odbell >= CVMX_MGMT_PORT_NUM_TX_BUFFERS - 1)
+    {
+        /* No room for another packet */
+        cvmx_spinlock_unlock(&state->lock);
+        return CVMX_MGMT_PORT_NO_MEMORY;
+    }
+    else
+    {
+        /* Copy the packet into the output buffer */
+	m_copydata(m, 0, m->m_pkthdr.len, state->tx_buffers[state->tx_write_index]);
+        /* Update the TX ring buffer entry size */
+        state->tx_ring[state->tx_write_index].s.len = m->m_pkthdr.len;
+        /* This code doesn't support TX timestamps */
+        state->tx_ring[state->tx_write_index].s.tstamp = 0;
+        /* Increment our TX index */
+        state->tx_write_index = (state->tx_write_index + 1) % CVMX_MGMT_PORT_NUM_TX_BUFFERS;
+        /* Ring the doorbell, sending the packet */
+        CVMX_SYNCWS;
+        cvmx_write_csr(CVMX_MIXX_ORING2(port), 1);
+        if (cvmx_read_csr(CVMX_MIXX_ORCNT(port)))
+            cvmx_write_csr(CVMX_MIXX_ORCNT(port), cvmx_read_csr(CVMX_MIXX_ORCNT(port)));
+
+        cvmx_spinlock_unlock(&state->lock);
+        return CVMX_MGMT_PORT_SUCCESS;
+    }
+}
+#endif
+
+
 /**
  * Receive a packet from the management port.
  *
@@ -564,7 +620,7 @@ cvmx_mgmt_port_result_t cvmx_mgmt_port_s
  * @return The size of the packet, or a negative erorr code on failure. Zero
  *         means that no packets were available.
  */
-int cvmx_mgmt_port_receive(int port, int buffer_len, void *buffer)
+int cvmx_mgmt_port_receive(int port, int buffer_len, uint8_t *buffer)
 {
     cvmx_mixx_ircnt_t mix_ircnt;
     cvmx_mgmt_port_state_t *state;
@@ -588,13 +644,13 @@ int cvmx_mgmt_port_receive(int port, int
     mix_ircnt.u64 = cvmx_read_csr(CVMX_MIXX_IRCNT(port));
     if (mix_ircnt.s.ircnt)
     {
-        void *source = state->rx_buffers[state->rx_read_index];
-        uint64_t *zero_check = source;
+        uint64_t *source = (void *)state->rx_buffers[state->rx_read_index];
+	uint64_t *zero_check = source;
         /* CN56XX pass 1 has an errata where packets might start 8 bytes
             into the buffer instead of at their correct lcoation. If the
             first 8 bytes is zero we assume this has happened */
         if (OCTEON_IS_MODEL(OCTEON_CN56XX_PASS1_X) && (*zero_check == 0))
-            source += 8;
+            source++;
         /* Start off with zero bytes received */
         result = 0;
         /* While the completion code signals more data, copy the buffers
@@ -621,7 +677,7 @@ int cvmx_mgmt_port_receive(int port, int
             CVMX_SYNCWS;
             /* Increment the number of RX buffers */
             cvmx_write_csr(CVMX_MIXX_IRING2(port), 1);
-            source = state->rx_buffers[state->rx_read_index];
+            source = (void *)state->rx_buffers[state->rx_read_index];
             zero_check = source;
         }
 

Modified: head/sys/contrib/octeon-sdk/cvmx-mgmt-port.h
==============================================================================
--- head/sys/contrib/octeon-sdk/cvmx-mgmt-port.h	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/contrib/octeon-sdk/cvmx-mgmt-port.h	Mon Jan 10 03:48:41 2011	(r217214)
@@ -134,6 +134,19 @@ extern cvmx_mgmt_port_result_t cvmx_mgmt
  */
 extern cvmx_mgmt_port_result_t cvmx_mgmt_port_send(int port, int packet_len, void *buffer);
 
+#if defined(__FreeBSD__)
+/**
+ * Send a packet out the management port. The packet is copied so
+ * the input mbuf isn't used after this call.
+ *
+ * @param port       Management port
+ * @param m          Packet mbuf (with pkthdr)
+ *
+ * @return CVMX_MGMT_PORT_SUCCESS or an error code
+ */
+extern cvmx_mgmt_port_result_t cvmx_mgmt_port_sendm(int port, const struct mbuf *m);
+#endif
+
 /**
  * Receive a packet from the management port.
  *
@@ -144,7 +157,7 @@ extern cvmx_mgmt_port_result_t cvmx_mgmt
  * @return The size of the packet, or a negative erorr code on failure. Zero
  *         means that no packets were available.
  */
-extern int cvmx_mgmt_port_receive(int port, int buffer_len, void *buffer);
+extern int cvmx_mgmt_port_receive(int port, int buffer_len, uint8_t *buffer);
 
 /**
  * Set the MAC address for a management port

Modified: head/sys/mips/cavium/ciu.c
==============================================================================
--- head/sys/mips/cavium/ciu.c	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/mips/cavium/ciu.c	Mon Jan 10 03:48:41 2011	(r217214)
@@ -58,7 +58,7 @@ __FBSDID("$FreeBSD$");
 #define	CIU_IRQ_EN0_COUNT	((CIU_IRQ_EN0_END - CIU_IRQ_EN0_BEGIN) + 1)
 
 #define	CIU_IRQ_EN1_BEGIN	CVMX_IRQ_WDOG0
-#define	CIU_IRQ_EN1_END		CVMX_IRQ_WDOG15
+#define	CIU_IRQ_EN1_END		CVMX_IRQ_DFM
 #define	CIU_IRQ_EN1_COUNT	((CIU_IRQ_EN1_END - CIU_IRQ_EN1_BEGIN) + 1)
 
 struct ciu_softc {

Modified: head/sys/mips/cavium/cvmx_config.h
==============================================================================
--- head/sys/mips/cavium/cvmx_config.h	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/mips/cavium/cvmx_config.h	Mon Jan 10 03:48:41 2011	(r217214)
@@ -45,6 +45,7 @@
 #include <sys/types.h>
 #include <sys/param.h>
 #include <sys/systm.h>
+#include <sys/mbuf.h>
 
 #include <vm/vm.h>
 #include <vm/pmap.h>

Modified: head/sys/mips/cavium/files.octeon1
==============================================================================
--- head/sys/mips/cavium/files.octeon1	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/mips/cavium/files.octeon1	Mon Jan 10 03:48:41 2011	(r217214)
@@ -37,6 +37,10 @@ mips/cavium/octe/mv88e61xxphy.c			option
 mips/cavium/octe/octe.c				optional octe
 mips/cavium/octe/octebus.c			optional octe
 
+mips/cavium/if_octm.c				optional octm
+
+contrib/octeon-sdk/cvmx-mgmt-port.c		optional octm
+
 mips/cavium/octopci.c				optional pci
 mips/cavium/octopci_bus_space.c			optional pci
 

Added: head/sys/mips/cavium/if_octm.c
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ head/sys/mips/cavium/if_octm.c	Mon Jan 10 03:48:41 2011	(r217214)
@@ -0,0 +1,519 @@
+/*-
+ * Copyright (c) 2010-2011 Juli Mallett <jmallett@FreeBSD.org>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED.  IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ *
+ * $FreeBSD$
+ */
+
+/*
+ * Cavium Octeon management port Ethernet devices.
+ */
+
+#include "opt_inet.h"
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/bus.h>
+#include <sys/endian.h>
+#include <sys/kernel.h>
+#include <sys/mbuf.h>
+#include <sys/lock.h>
+#include <sys/module.h>
+#include <sys/mutex.h>
+#include <sys/rman.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <sys/sysctl.h>
+
+#include <net/bpf.h>
+#include <net/ethernet.h>
+#include <net/if.h>
+#include <net/if_dl.h>
+#include <net/if_media.h>
+#include <net/if_types.h>
+#include <net/if_var.h>
+#include <net/if_vlan_var.h>
+
+#ifdef INET
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#endif
+
+#include <contrib/octeon-sdk/cvmx.h>
+#include <contrib/octeon-sdk/cvmx-interrupt.h>
+#include <contrib/octeon-sdk/cvmx-mgmt-port.h>
+
+struct octm_softc {
+	struct ifnet *sc_ifp;
+	device_t sc_dev;
+	unsigned sc_port;
+	int sc_flags;
+	struct ifmedia sc_ifmedia;
+	struct resource *sc_intr;
+	void *sc_intr_cookie;
+};
+
+static void	octm_identify(driver_t *, device_t);
+static int	octm_probe(device_t);
+static int	octm_attach(device_t);
+static int	octm_detach(device_t);
+static int	octm_shutdown(device_t);
+
+static void	octm_init(void *);
+static int	octm_transmit(struct ifnet *, struct mbuf *);
+
+static int	octm_medchange(struct ifnet *);
+static void	octm_medstat(struct ifnet *, struct ifmediareq *);
+
+static int	octm_ioctl(struct ifnet *, u_long, caddr_t);
+
+static void	octm_rx_intr(void *);
+
+static device_method_t octm_methods[] = {
+	/* Device interface */
+	DEVMETHOD(device_identify,	octm_identify),
+	DEVMETHOD(device_probe,		octm_probe),
+	DEVMETHOD(device_attach,	octm_attach),
+	DEVMETHOD(device_detach,	octm_detach),
+	DEVMETHOD(device_shutdown,	octm_shutdown),
+
+	{ 0, 0 }
+};
+
+static driver_t octm_driver = {
+	"octm",
+	octm_methods,
+	sizeof (struct octm_softc),
+};
+
+static devclass_t octm_devclass;
+
+DRIVER_MODULE(octm, ciu, octm_driver, octm_devclass, 0, 0);
+
+static void
+octm_identify(driver_t *drv, device_t parent)
+{
+	unsigned i;
+
+	if (!octeon_has_feature(OCTEON_FEATURE_MGMT_PORT))
+		return;
+
+	for (i = 0; i < CVMX_MGMT_PORT_NUM_PORTS; i++)
+		BUS_ADD_CHILD(parent, 0, "octm", i);
+}
+
+static int
+octm_probe(device_t dev)
+{
+	cvmx_mgmt_port_result_t result;
+
+	result = cvmx_mgmt_port_initialize(device_get_unit(dev));
+	switch (result) {
+	case CVMX_MGMT_PORT_SUCCESS:
+		break;
+	case CVMX_MGMT_PORT_NO_MEMORY:
+		return (ENOBUFS);
+	case CVMX_MGMT_PORT_INVALID_PARAM:
+		return (ENXIO);
+	case CVMX_MGMT_PORT_INIT_ERROR:
+		return (EIO);
+	}
+
+	device_set_desc(dev, "Cavium Octeon Management Ethernet");
+
+	return (0);
+}
+
+static int
+octm_attach(device_t dev)
+{
+	struct ifnet *ifp;
+	struct octm_softc *sc;
+	cvmx_mixx_irhwm_t mixx_irhwm;
+	cvmx_mixx_intena_t mixx_intena;
+	uint64_t mac;
+	int error;
+	int irq;
+	int rid;
+
+	sc = device_get_softc(dev);
+	sc->sc_dev = dev;
+	sc->sc_port = device_get_unit(dev);
+
+	switch (sc->sc_port) {
+	case 0:
+		irq = CVMX_IRQ_MII;
+		break;
+	case 1:
+		irq = CVMX_IRQ_MII1;
+		break;
+	default:
+		device_printf(dev, "unsupported management port %u.\n", sc->sc_port);
+		return (ENXIO);
+	}
+
+	mac = cvmx_mgmt_port_get_mac(sc->sc_port);
+	if (mac == CVMX_MGMT_PORT_GET_MAC_ERROR) {
+		device_printf(dev, "unable to read MAC.\n");
+		return (ENXIO);
+	}
+
+	/* No watermark for input ring.  */
+	mixx_irhwm.u64 = 0;
+	cvmx_write_csr(CVMX_MIXX_IRHWM(sc->sc_port), mixx_irhwm.u64);
+
+	/* Enable input ring interrupts.  */
+	mixx_intena.u64 = 0;
+	mixx_intena.s.ithena = 1;
+	cvmx_write_csr(CVMX_MIXX_INTENA(sc->sc_port), mixx_intena.u64);
+
+	/* Allocate and establish interrupt.  */
+	rid = 0;
+	sc->sc_intr = bus_alloc_resource(sc->sc_dev, SYS_RES_IRQ, &rid,
+	    irq, irq, 1, RF_ACTIVE);
+	if (sc->sc_intr == NULL) {
+		device_printf(dev, "unable to allocate IRQ.\n");
+		return (ENXIO);
+	}
+
+	error = bus_setup_intr(sc->sc_dev, sc->sc_intr, INTR_TYPE_NET, NULL,
+	    octm_rx_intr, sc, &sc->sc_intr_cookie);
+	if (error != 0) {
+		device_printf(dev, "unable to setup interrupt.\n");
+		bus_release_resource(dev, SYS_RES_IRQ, 0, sc->sc_intr);
+		return (ENXIO);
+	}
+
+	bus_describe_intr(sc->sc_dev, sc->sc_intr, sc->sc_intr_cookie, "rx");
+
+	/* XXX Possibly should enable TX interrupts.  */
+
+	ifp = if_alloc(IFT_ETHER);
+	if (ifp == NULL) {
+		device_printf(dev, "cannot allocate ifnet.\n");
+		bus_release_resource(dev, SYS_RES_IRQ, 0, sc->sc_intr);
+		return (ENOMEM);
+	}
+
+	if_initname(ifp, device_get_name(dev), device_get_unit(dev));
+	ifp->if_mtu = ETHERMTU;
+	ifp->if_init = octm_init;
+	ifp->if_softc = sc;
+	ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST | IFF_ALLMULTI;
+	ifp->if_ioctl = octm_ioctl;
+
+	sc->sc_ifp = ifp;
+	sc->sc_flags = ifp->if_flags;
+
+	ifmedia_init(&sc->sc_ifmedia, 0, octm_medchange, octm_medstat);
+
+	ifmedia_add(&sc->sc_ifmedia, IFM_ETHER | IFM_AUTO, 0, NULL);
+	ifmedia_set(&sc->sc_ifmedia, IFM_ETHER | IFM_AUTO);
+
+	ether_ifattach(ifp, (const u_int8_t *)&mac + 2);
+
+	ifp->if_transmit = octm_transmit;
+
+	ifp->if_data.ifi_hdrlen = sizeof(struct ether_vlan_header);
+	ifp->if_capabilities = IFCAP_VLAN_MTU;
+	ifp->if_capenable = ifp->if_capabilities;
+
+	IFQ_SET_MAXLEN(&ifp->if_snd, CVMX_MGMT_PORT_NUM_TX_BUFFERS);
+	ifp->if_snd.ifq_drv_maxlen = CVMX_MGMT_PORT_NUM_TX_BUFFERS;
+	IFQ_SET_READY(&ifp->if_snd);
+
+	return (bus_generic_attach(dev));
+}
+
+static int
+octm_detach(device_t dev)
+{
+	struct octm_softc *sc;
+	cvmx_mgmt_port_result_t result;
+
+	sc = device_get_softc(dev);
+
+	result = cvmx_mgmt_port_initialize(sc->sc_port);
+	switch (result) {
+	case CVMX_MGMT_PORT_SUCCESS:
+		break;
+	case CVMX_MGMT_PORT_NO_MEMORY:
+		return (ENOBUFS);
+	case CVMX_MGMT_PORT_INVALID_PARAM:
+		return (ENXIO);
+	case CVMX_MGMT_PORT_INIT_ERROR:
+		return (EIO);
+	}
+
+	bus_release_resource(dev, SYS_RES_IRQ, 0, sc->sc_intr);
+	/* XXX Incomplete.  */
+
+	return (0);
+}
+
+static int
+octm_shutdown(device_t dev)
+{
+	return (octm_detach(dev));
+}
+
+static void
+octm_init(void *arg)
+{
+	struct ifnet *ifp;
+	struct octm_softc *sc;
+	cvmx_mgmt_port_netdevice_flags_t flags;
+	uint64_t mac;
+
+	sc = arg;
+	ifp = sc->sc_ifp;
+
+	if ((ifp->if_drv_flags & IFF_DRV_RUNNING) != 0) {
+		cvmx_mgmt_port_disable(sc->sc_port);
+
+		ifp->if_drv_flags &= ~IFF_DRV_RUNNING;
+	}
+
+	if (((ifp->if_flags ^ sc->sc_flags) & (IFF_ALLMULTI | IFF_MULTICAST | IFF_PROMISC)) != 0) {
+		flags = 0;
+		if ((ifp->if_flags & IFF_ALLMULTI) != 0)
+			flags |= CVMX_IFF_ALLMULTI;
+		if ((ifp->if_flags & IFF_PROMISC) != 0)
+			flags |= CVMX_IFF_PROMISC;
+		cvmx_mgmt_port_set_multicast_list(sc->sc_port, flags);
+	}
+
+	mac = 0;
+	memcpy((u_int8_t *)&mac + 2, IF_LLADDR(ifp), 6);
+	cvmx_mgmt_port_set_mac(sc->sc_port, mac);
+
+	/* XXX link state?  */
+
+	if ((ifp->if_flags & IFF_UP) != 0)
+		cvmx_mgmt_port_enable(sc->sc_port);
+
+	ifp->if_drv_flags |= IFF_DRV_RUNNING;
+	ifp->if_drv_flags &= ~IFF_DRV_OACTIVE;
+}
+
+static int
+octm_transmit(struct ifnet *ifp, struct mbuf *m)
+{
+	struct octm_softc *sc;
+	cvmx_mgmt_port_result_t result;
+
+	sc = ifp->if_softc;
+
+	if ((ifp->if_drv_flags & (IFF_DRV_RUNNING | IFF_DRV_OACTIVE)) !=
+	    IFF_DRV_RUNNING) {
+		m_freem(m);
+		return (0);
+	}
+
+	result = cvmx_mgmt_port_sendm(sc->sc_port, m);
+
+	if (result == CVMX_MGMT_PORT_SUCCESS)
+		ETHER_BPF_MTAP(ifp, m);
+	else
+		ifp->if_oerrors++;
+
+	m_freem(m);
+
+	switch (result) {
+	case CVMX_MGMT_PORT_SUCCESS:
+		return (0);
+	case CVMX_MGMT_PORT_NO_MEMORY:
+		return (ENOBUFS);
+	case CVMX_MGMT_PORT_INVALID_PARAM:
+		return (ENXIO);
+	case CVMX_MGMT_PORT_INIT_ERROR:
+		return (EIO);
+	default:
+		return (EDOOFUS);
+	}
+}
+
+static int
+octm_medchange(struct ifnet *ifp)
+{
+	return (ENOTSUP);
+}
+
+static void
+octm_medstat(struct ifnet *ifp, struct ifmediareq *ifm)
+{
+	struct octm_softc *sc;
+	cvmx_helper_link_info_t link_info;
+
+	sc = ifp->if_softc;
+
+	ifm->ifm_status = IFM_AVALID;
+	ifm->ifm_active = IFT_ETHER;
+
+	link_info = cvmx_mgmt_port_link_get(sc->sc_port);
+	if (!link_info.s.link_up)
+		return;
+
+	ifm->ifm_status |= IFM_ACTIVE;
+
+	switch (link_info.s.speed) {
+	case 10:
+		ifm->ifm_active |= IFM_10_T;
+		break;
+	case 100:
+		ifm->ifm_active |= IFM_100_TX;
+		break;
+	case 1000:
+		ifm->ifm_active |= IFM_1000_T;
+		break;
+	case 10000:
+		ifm->ifm_active |= IFM_10G_T;
+		break;
+	}
+
+	if (link_info.s.full_duplex)
+		ifm->ifm_active |= IFM_FDX;
+	else
+		ifm->ifm_active |= IFM_HDX;
+}
+
+static int
+octm_ioctl(struct ifnet *ifp, u_long cmd, caddr_t data)
+{
+	struct octm_softc *sc;
+	struct ifreq *ifr;
+#ifdef INET
+	struct ifaddr *ifa;
+#endif
+	int error;
+
+	sc = ifp->if_softc;
+	ifr = (struct ifreq *)data;
+#ifdef INET
+	ifa = (struct ifaddr *)data;
+#endif
+
+	switch (cmd) {
+	case SIOCSIFADDR:
+#ifdef INET
+		/*
+		 * Avoid reinitialization unless it's necessary.
+		 */
+		if (ifa->ifa_addr->sa_family == AF_INET) {
+			ifp->if_flags |= IFF_UP;
+			if ((ifp->if_drv_flags & IFF_DRV_RUNNING) == 0)
+				octm_init(sc);
+			arp_ifinit(ifp, ifa);
+
+			return (0);
+		}
+#endif
+		error = ether_ioctl(ifp, cmd, data);
+		if (error != 0)
+			return (error);
+		return (0);
+
+	case SIOCSIFFLAGS:
+		if (ifp->if_flags == sc->sc_flags)
+			return (0);
+		if ((ifp->if_flags & IFF_UP) != 0) {
+			if ((ifp->if_drv_flags & IFF_DRV_RUNNING) == 0)
+				octm_init(sc);
+		} else {
+			if ((ifp->if_drv_flags & IFF_DRV_RUNNING) != 0) {
+				cvmx_mgmt_port_disable(sc->sc_port);
+
+				ifp->if_drv_flags &= ~IFF_DRV_RUNNING;
+			}
+		}
+		sc->sc_flags = ifp->if_flags;
+		return (0);
+	
+	case SIOCSIFCAP:
+		/*
+		 * Just change the capabilities in software, currently none
+		 * require reprogramming hardware, they just toggle whether we
+		 * make use of already-present facilities in software.
+		 */
+		ifp->if_capenable = ifr->ifr_reqcap;
+		return (0);
+
+	case SIOCSIFMTU:
+		cvmx_mgmt_port_set_max_packet_size(sc->sc_port, ifr->ifr_mtu + ifp->if_data.ifi_hdrlen);
+		return (0);
+
+	case SIOCSIFMEDIA:
+	case SIOCGIFMEDIA:
+		error = ifmedia_ioctl(ifp, ifr, &sc->sc_ifmedia, cmd);
+		if (error != 0)
+			return (error);
+		return (0);
+	
+	default:
+		error = ether_ioctl(ifp, cmd, data);
+		if (error != 0)
+			return (error);
+		return (0);
+	}
+}
+
+static void
+octm_rx_intr(void *arg)
+{
+	struct octm_softc *sc = arg;
+	cvmx_mixx_isr_t mixx_isr;
+	int len;
+
+	mixx_isr.u64 = cvmx_read_csr(CVMX_MIXX_ISR(sc->sc_port));
+	if (!mixx_isr.s.irthresh) {
+		device_printf(sc->sc_dev, "stray interrupt.\n");
+		return;
+	}
+
+	for (;;) {
+		struct mbuf *m = m_getcl(M_DONTWAIT, MT_DATA, M_PKTHDR);
+		if (m == NULL) {
+			device_printf(sc->sc_dev, "no memory for receive mbuf.\n");
+			return;
+		}
+
+
+		len = cvmx_mgmt_port_receive(sc->sc_port, MCLBYTES, m->m_data);
+		if (len > 0) {
+			m->m_pkthdr.rcvif = sc->sc_ifp;
+			m->m_pkthdr.len = m->m_len = len;
+
+			sc->sc_ifp->if_ipackets++;
+
+			(*sc->sc_ifp->if_input)(sc->sc_ifp, m);
+
+			continue;
+		}
+
+		if (len == 0)
+			break;
+
+		sc->sc_ifp->if_ierrors++;
+	}
+}

Modified: head/sys/mips/conf/OCTEON1
==============================================================================
--- head/sys/mips/conf/OCTEON1	Sun Jan  9 23:47:11 2011	(r217213)
+++ head/sys/mips/conf/OCTEON1	Mon Jan 10 03:48:41 2011	(r217214)
@@ -178,6 +178,9 @@ device		uart		# Generic UART driver
 # NOTE: Be sure to keep the 'device miibus' line in order to use these NICs!
 device		octe
 
+# Cavium Octeon management Ethernet.
+device		octm
+
 # Switch PHY support for the octe driver.  These currently present a VLAN per
 # physical port, but may eventually provide support for DSA or similar instead.
 #device		mv88e61xxphy	# Marvell 88E61XX



Want to link to this message? Use this URL: <https://mail-archive.FreeBSD.org/cgi/mid.cgi?201101100348.p0A3mgGo066037>