nfp: introduce driver initialization

Signed-off-by: Alejandro Lucero <alejandro.lucero@netronome.com>
Signed-off-by: Rolf Neugebauer <rolf.neugebauer@netronome.com>
This commit is contained in:
Alejandro Lucero 2015-11-30 10:25:35 +00:00 committed by Thomas Monjalon
parent deb714fbb4
commit defb9a5dd1
12 changed files with 1627 additions and 0 deletions

View file

@ -303,6 +303,10 @@ M: Adrien Mazarguil <adrien.mazarguil@6wind.com>
F: drivers/net/mlx5/
F: doc/guides/nics/mlx5.rst
Netronome nfp
M: Alejandro Lucero <alejandro.lucero@netronome.com>
F: drivers/net/nfp/
RedHat virtio
M: Huawei Xie <huawei.xie@intel.com>
M: Yuanhan Liu <yuanhan.liu@linux.intel.com>

View file

@ -253,6 +253,12 @@ CONFIG_RTE_LIBRTE_CXGBE_DEBUG_RX=n
CONFIG_RTE_LIBRTE_ENIC_PMD=y
CONFIG_RTE_LIBRTE_ENIC_DEBUG=n
#
# Compile burst-oriented Netronome NFP PMD driver
#
CONFIG_RTE_LIBRTE_NFP_PMD=n
CONFIG_RTE_LIBRTE_NFP_DEBUG=n
#
# Compile software PMD backed by SZEDATA2 device
#

View file

@ -108,6 +108,10 @@ New Features
Like mlx4, this PMD is only available for Linux and is disabled by default
due to external dependencies (libibverbs and libmlx5).
* **Added driver for Netronome nfp-6xxx card.**
Support for using Netronome nfp-6xxx with PCI VFs.
* **Added virtual szedata2 driver for COMBO cards.**
Added virtual PMD for COMBO-100G and COMBO-80G cards.

View file

@ -43,6 +43,7 @@ DIRS-$(CONFIG_RTE_LIBRTE_IXGBE_PMD) += ixgbe
DIRS-$(CONFIG_RTE_LIBRTE_MLX4_PMD) += mlx4
DIRS-$(CONFIG_RTE_LIBRTE_MLX5_PMD) += mlx5
DIRS-$(CONFIG_RTE_LIBRTE_MPIPE_PMD) += mpipe
DIRS-$(CONFIG_RTE_LIBRTE_NFP_PMD) += nfp
DIRS-$(CONFIG_RTE_LIBRTE_PMD_NULL) += null
DIRS-$(CONFIG_RTE_LIBRTE_PMD_PCAP) += pcap
DIRS-$(CONFIG_RTE_LIBRTE_PMD_RING) += ring

56
drivers/net/nfp/Makefile Normal file
View file

@ -0,0 +1,56 @@
# BSD LICENSE
#
# Copyright(c) 2010-2014 Intel Corporation. All rights reserved.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Intel Corporation nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT
# OWNER 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.
include $(RTE_SDK)/mk/rte.vars.mk
#
# library name
#
LIB = librte_pmd_nfp.a
CFLAGS += -O3
CFLAGS += $(WERROR_FLAGS)
EXPORT_MAP := rte_pmd_nfp_version.map
LIBABIVER := 1
#
# all source are stored in SRCS-y
#
SRCS-$(CONFIG_RTE_LIBRTE_NFP_PMD) += nfp_net.c
# this lib depends upon:
DEPDIRS-$(CONFIG_RTE_LIBRTE_NFP_PMD) += lib/librte_eal lib/librte_ether
DEPDIRS-$(CONFIG_RTE_LIBRTE_NFP_PMD) += lib/librte_mempool lib/librte_mbuf
DEPDIRS-$(CONFIG_RTE_LIBRTE_NFP_PMD) += lib/librte_net lib/librte_malloc
include $(RTE_SDK)/mk/rte.lib.mk

699
drivers/net/nfp/nfp_net.c Normal file
View file

@ -0,0 +1,699 @@
/*
* Copyright (c) 2014, 2015 Netronome Systems, Inc.
* All rights reserved.
*
* Small portions derived from code Copyright(c) 2010-2015 Intel Corporation.
*
* 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
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT HOLDER 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.
*/
/*
* vim:shiftwidth=8:noexpandtab
*
* @file dpdk/pmd/nfp_net.c
*
* Netronome vNIC DPDK Poll-Mode Driver: Main entry point
*/
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <unistd.h>
#include <string.h>
#include <sys/mman.h>
#include <sys/socket.h>
#include <sys/io.h>
#include <assert.h>
#include <time.h>
#include <math.h>
#include <inttypes.h>
#include <rte_byteorder.h>
#include <rte_common.h>
#include <rte_log.h>
#include <rte_debug.h>
#include <rte_ethdev.h>
#include <rte_dev.h>
#include <rte_ether.h>
#include <rte_malloc.h>
#include <rte_memzone.h>
#include <rte_mempool.h>
#include <rte_version.h>
#include <rte_string_fns.h>
#include <rte_alarm.h>
#include "nfp_net_pmd.h"
#include "nfp_net_logs.h"
#include "nfp_net_ctrl.h"
/* Prototypes */
static void nfp_net_close(struct rte_eth_dev *dev);
static int nfp_net_configure(struct rte_eth_dev *dev);
static int nfp_net_init(struct rte_eth_dev *eth_dev);
static int nfp_net_start(struct rte_eth_dev *dev);
static void nfp_net_stop(struct rte_eth_dev *dev);
/*
* The offset of the queue controller queues in the PCIe Target. These
* happen to be at the same offset on the NFP6000 and the NFP3200 so
* we use a single macro here.
*/
#define NFP_PCIE_QUEUE(_q) (0x80000 + (0x800 * ((_q) & 0xff)))
/* Maximum value which can be added to a queue with one transaction */
#define NFP_QCP_MAX_ADD 0x7f
#define RTE_MBUF_DMA_ADDR_DEFAULT(mb) \
(uint64_t)((mb)->buf_physaddr + RTE_PKTMBUF_HEADROOM)
/* nfp_qcp_ptr - Read or Write Pointer of a queue */
enum nfp_qcp_ptr {
NFP_QCP_READ_PTR = 0,
NFP_QCP_WRITE_PTR
};
/*
* nfp_qcp_ptr_add - Add the value to the selected pointer of a queue
* @q: Base address for queue structure
* @ptr: Add to the Read or Write pointer
* @val: Value to add to the queue pointer
*
* If @val is greater than @NFP_QCP_MAX_ADD multiple writes are performed.
*/
static inline void
nfp_qcp_ptr_add(uint8_t *q, enum nfp_qcp_ptr ptr, uint32_t val)
{
uint32_t off;
if (ptr == NFP_QCP_READ_PTR)
off = NFP_QCP_QUEUE_ADD_RPTR;
else
off = NFP_QCP_QUEUE_ADD_WPTR;
while (val > NFP_QCP_MAX_ADD) {
nn_writel(rte_cpu_to_le_32(NFP_QCP_MAX_ADD), q + off);
val -= NFP_QCP_MAX_ADD;
}
nn_writel(rte_cpu_to_le_32(val), q + off);
}
/*
* nfp_qcp_read - Read the current Read/Write pointer value for a queue
* @q: Base address for queue structure
* @ptr: Read or Write pointer
*/
static inline uint32_t
nfp_qcp_read(uint8_t *q, enum nfp_qcp_ptr ptr)
{
uint32_t off;
uint32_t val;
if (ptr == NFP_QCP_READ_PTR)
off = NFP_QCP_QUEUE_STS_LO;
else
off = NFP_QCP_QUEUE_STS_HI;
val = rte_cpu_to_le_32(nn_readl(q + off));
if (ptr == NFP_QCP_READ_PTR)
return val & NFP_QCP_QUEUE_STS_LO_READPTR_mask;
else
return val & NFP_QCP_QUEUE_STS_HI_WRITEPTR_mask;
}
/*
* Functions to read/write from/to Config BAR
* Performs any endian conversion necessary.
*/
static inline uint8_t
nn_cfg_readb(struct nfp_net_hw *hw, int off)
{
return nn_readb(hw->ctrl_bar + off);
}
static inline void
nn_cfg_writeb(struct nfp_net_hw *hw, int off, uint8_t val)
{
nn_writeb(val, hw->ctrl_bar + off);
}
static inline uint32_t
nn_cfg_readl(struct nfp_net_hw *hw, int off)
{
return rte_le_to_cpu_32(nn_readl(hw->ctrl_bar + off));
}
static inline void
nn_cfg_writel(struct nfp_net_hw *hw, int off, uint32_t val)
{
nn_writel(rte_cpu_to_le_32(val), hw->ctrl_bar + off);
}
static inline uint64_t
nn_cfg_readq(struct nfp_net_hw *hw, int off)
{
return rte_le_to_cpu_64(nn_readq(hw->ctrl_bar + off));
}
static inline void
nn_cfg_writeq(struct nfp_net_hw *hw, int off, uint64_t val)
{
nn_writeq(rte_cpu_to_le_64(val), hw->ctrl_bar + off);
}
static int
__nfp_net_reconfig(struct nfp_net_hw *hw, uint32_t update)
{
int cnt;
uint32_t new;
struct timespec wait;
PMD_DRV_LOG(DEBUG, "Writing to the configuration queue (%p)...\n",
hw->qcp_cfg);
if (hw->qcp_cfg == NULL)
rte_panic("Bad configuration queue pointer\n");
nfp_qcp_ptr_add(hw->qcp_cfg, NFP_QCP_WRITE_PTR, 1);
wait.tv_sec = 0;
wait.tv_nsec = 1000000;
PMD_DRV_LOG(DEBUG, "Polling for update ack...\n");
/* Poll update field, waiting for NFP to ack the config */
for (cnt = 0; ; cnt++) {
new = nn_cfg_readl(hw, NFP_NET_CFG_UPDATE);
if (new == 0)
break;
if (new & NFP_NET_CFG_UPDATE_ERR) {
PMD_INIT_LOG(ERR, "Reconfig error: 0x%08x\n", new);
return -1;
}
if (cnt >= NFP_NET_POLL_TIMEOUT) {
PMD_INIT_LOG(ERR, "Reconfig timeout for 0x%08x after"
" %dms\n", update, cnt);
rte_panic("Exiting\n");
}
nanosleep(&wait, 0); /* waiting for a 1ms */
}
PMD_DRV_LOG(DEBUG, "Ack DONE\n");
return 0;
}
/*
* Reconfigure the NIC
* @nn: device to reconfigure
* @ctrl: The value for the ctrl field in the BAR config
* @update: The value for the update field in the BAR config
*
* Write the update word to the BAR and ping the reconfig queue. Then poll
* until the firmware has acknowledged the update by zeroing the update word.
*/
static int
nfp_net_reconfig(struct nfp_net_hw *hw, uint32_t ctrl, uint32_t update)
{
uint32_t err;
PMD_DRV_LOG(DEBUG, "nfp_net_reconfig: ctrl=%08x update=%08x\n",
ctrl, update);
nn_cfg_writel(hw, NFP_NET_CFG_CTRL, ctrl);
nn_cfg_writel(hw, NFP_NET_CFG_UPDATE, update);
rte_wmb();
err = __nfp_net_reconfig(hw, update);
if (!err)
return 0;
/*
* Reconfig errors imply situations where they can be handled.
* Otherwise, rte_panic is called inside __nfp_net_reconfig
*/
PMD_INIT_LOG(ERR, "Error nfp_net reconfig for ctrl: %x update: %x\n",
ctrl, update);
return -EIO;
}
/*
* Configure an Ethernet device. This function must be invoked first
* before any other function in the Ethernet API. This function can
* also be re-invoked when a device is in the stopped state.
*/
static int
nfp_net_configure(struct rte_eth_dev *dev)
{
struct rte_eth_conf *dev_conf;
struct rte_eth_rxmode *rxmode;
struct rte_eth_txmode *txmode;
uint32_t new_ctrl = 0;
uint32_t update = 0;
struct nfp_net_hw *hw;
hw = NFP_NET_DEV_PRIVATE_TO_HW(dev->data->dev_private);
/*
* A DPDK app sends info about how many queues to use and how
* those queues need to be configured. This is used by the
* DPDK core and it makes sure no more queues than those
* advertised by the driver are requested. This function is
* called after that internal process
*/
PMD_INIT_LOG(DEBUG, "Configure\n");
dev_conf = &dev->data->dev_conf;
rxmode = &dev_conf->rxmode;
txmode = &dev_conf->txmode;
/* Checking TX mode */
if (txmode->mq_mode) {
PMD_INIT_LOG(INFO, "TX mq_mode DCB and VMDq not supported\n");
return -EINVAL;
}
/* Checking RX mode */
if (rxmode->mq_mode & ETH_MQ_RX_RSS) {
if (hw->cap & NFP_NET_CFG_CTRL_RSS) {
update = NFP_NET_CFG_UPDATE_RSS;
new_ctrl = NFP_NET_CFG_CTRL_RSS;
} else {
PMD_INIT_LOG(INFO, "RSS not supported\n");
return -EINVAL;
}
}
if (rxmode->split_hdr_size) {
PMD_INIT_LOG(INFO, "rxmode does not support split header\n");
return -EINVAL;
}
if (rxmode->hw_ip_checksum) {
if (hw->cap & NFP_NET_CFG_CTRL_RXCSUM) {
new_ctrl |= NFP_NET_CFG_CTRL_RXCSUM;
} else {
PMD_INIT_LOG(INFO, "RXCSUM not supported\n");
return -EINVAL;
}
}
if (rxmode->hw_vlan_filter) {
PMD_INIT_LOG(INFO, "VLAN filter not supported\n");
return -EINVAL;
}
if (rxmode->hw_vlan_strip) {
if (hw->cap & NFP_NET_CFG_CTRL_RXVLAN) {
new_ctrl |= NFP_NET_CFG_CTRL_RXVLAN;
} else {
PMD_INIT_LOG(INFO, "hw vlan strip not supported\n");
return -EINVAL;
}
}
if (rxmode->hw_vlan_extend) {
PMD_INIT_LOG(INFO, "VLAN extended not supported\n");
return -EINVAL;
}
/* Supporting VLAN insertion by default */
if (hw->cap & NFP_NET_CFG_CTRL_TXVLAN)
new_ctrl |= NFP_NET_CFG_CTRL_TXVLAN;
if (rxmode->jumbo_frame)
/* this is handled in rte_eth_dev_configure */
if (rxmode->hw_strip_crc) {
PMD_INIT_LOG(INFO, "strip CRC not supported\n");
return -EINVAL;
}
if (rxmode->enable_scatter) {
PMD_INIT_LOG(INFO, "Scatter not supported\n");
return -EINVAL;
}
if (!new_ctrl)
return 0;
update |= NFP_NET_CFG_UPDATE_GEN;
nn_cfg_writel(hw, NFP_NET_CFG_CTRL, new_ctrl);
if (nfp_net_reconfig(hw, new_ctrl, update) < 0)
return -EIO;
hw->ctrl = new_ctrl;
return 0;
}
static void
nfp_net_enable_queues(struct rte_eth_dev *dev)
{
struct nfp_net_hw *hw;
uint64_t enabled_queues = 0;
int i;
hw = NFP_NET_DEV_PRIVATE_TO_HW(dev->data->dev_private);
/* Enabling the required TX queues in the device */
for (i = 0; i < dev->data->nb_tx_queues; i++)
enabled_queues |= (1 << i);
nn_cfg_writeq(hw, NFP_NET_CFG_TXRS_ENABLE, enabled_queues);
enabled_queues = 0;
/* Enabling the required RX queues in the device */
for (i = 0; i < dev->data->nb_rx_queues; i++)
enabled_queues |= (1 << i);
nn_cfg_writeq(hw, NFP_NET_CFG_RXRS_ENABLE, enabled_queues);
}
static void
nfp_net_disable_queues(struct rte_eth_dev *dev)
{
struct nfp_net_hw *hw;
uint32_t new_ctrl, update = 0;
hw = NFP_NET_DEV_PRIVATE_TO_HW(dev->data->dev_private);
nn_cfg_writeq(hw, NFP_NET_CFG_TXRS_ENABLE, 0);
nn_cfg_writeq(hw, NFP_NET_CFG_RXRS_ENABLE, 0);
new_ctrl = hw->ctrl & ~NFP_NET_CFG_CTRL_ENABLE;
update = NFP_NET_CFG_UPDATE_GEN | NFP_NET_CFG_UPDATE_RING |
NFP_NET_CFG_UPDATE_MSIX;
if (hw->cap & NFP_NET_CFG_CTRL_RINGCFG)
new_ctrl &= ~NFP_NET_CFG_CTRL_RINGCFG;
/* If an error when reconfig we avoid to change hw state */
if (nfp_net_reconfig(hw, new_ctrl, update) < 0)
return;
hw->ctrl = new_ctrl;
}
static void
nfp_net_params_setup(struct nfp_net_hw *hw)
{
uint32_t *mac_address;
nn_cfg_writel(hw, NFP_NET_CFG_MTU, hw->mtu);
nn_cfg_writel(hw, NFP_NET_CFG_FLBUFSZ, hw->flbufsz);
/* A MAC address is 8 bytes long */
mac_address = (uint32_t *)(hw->mac_addr);
nn_cfg_writel(hw, NFP_NET_CFG_MACADDR,
rte_cpu_to_be_32(*mac_address));
nn_cfg_writel(hw, NFP_NET_CFG_MACADDR + 4,
rte_cpu_to_be_32(*(mac_address + 4)));
}
static void
nfp_net_cfg_queue_setup(struct nfp_net_hw *hw)
{
hw->qcp_cfg = hw->tx_bar + NFP_QCP_QUEUE_ADDR_SZ;
}
static int
nfp_net_start(struct rte_eth_dev *dev)
{
uint32_t new_ctrl, update = 0;
struct nfp_net_hw *hw;
hw = NFP_NET_DEV_PRIVATE_TO_HW(dev->data->dev_private);
PMD_INIT_LOG(DEBUG, "Start\n");
/* Disabling queues just in case... */
nfp_net_disable_queues(dev);
/* Writing configuration parameters in the device */
nfp_net_params_setup(hw);
/* Enabling the required queues in the device */
nfp_net_enable_queues(dev);
/* Enable device */
new_ctrl = hw->ctrl | NFP_NET_CFG_CTRL_ENABLE | NFP_NET_CFG_UPDATE_MSIX;
update = NFP_NET_CFG_UPDATE_GEN | NFP_NET_CFG_UPDATE_RING;
if (hw->cap & NFP_NET_CFG_CTRL_RINGCFG)
new_ctrl |= NFP_NET_CFG_CTRL_RINGCFG;
nn_cfg_writel(hw, NFP_NET_CFG_CTRL, new_ctrl);
if (nfp_net_reconfig(hw, new_ctrl, update) < 0)
return -EIO;
hw->ctrl = new_ctrl;
return 0;
}
/* Stop device: disable rx and tx functions to allow for reconfiguring. */
static void
nfp_net_stop(struct rte_eth_dev *dev)
{
PMD_INIT_LOG(DEBUG, "Stop\n");
nfp_net_disable_queues(dev);
}
/* Reset and stop device. The device can not be restarted. */
static void
nfp_net_close(struct rte_eth_dev *dev)
{
struct nfp_net_hw *hw;
PMD_INIT_LOG(DEBUG, "Close\n");
hw = NFP_NET_DEV_PRIVATE_TO_HW(dev->data->dev_private);
/*
* We assume that the DPDK application is stopping all the
* threads/queues before calling the device close function.
*/
nfp_net_stop(dev);
nn_cfg_writeb(hw, NFP_NET_CFG_LSC, 0xff);
/*
* The ixgbe PMD driver disables the pcie master on the
* device. The i40e does not...
*/
}
/* Initialise and register driver with DPDK Application */
static struct eth_dev_ops nfp_net_eth_dev_ops = {
.dev_configure = nfp_net_configure,
.dev_start = nfp_net_start,
.dev_stop = nfp_net_stop,
.dev_close = nfp_net_close,
};
static int
nfp_net_init(struct rte_eth_dev *eth_dev)
{
struct rte_pci_device *pci_dev;
struct nfp_net_hw *hw;
uint32_t tx_bar_off, rx_bar_off;
uint32_t start_q;
int stride = 4;
PMD_INIT_FUNC_TRACE();
hw = NFP_NET_DEV_PRIVATE_TO_HW(eth_dev->data->dev_private);
eth_dev->dev_ops = &nfp_net_eth_dev_ops;
/* For secondary processes, the primary has done all the work */
if (rte_eal_process_type() != RTE_PROC_PRIMARY)
return 0;
pci_dev = eth_dev->pci_dev;
hw->device_id = pci_dev->id.device_id;
hw->vendor_id = pci_dev->id.vendor_id;
hw->subsystem_device_id = pci_dev->id.subsystem_device_id;
hw->subsystem_vendor_id = pci_dev->id.subsystem_vendor_id;
PMD_INIT_LOG(DEBUG, "nfp_net: device (%u:%u) %u:%u:%u:%u\n",
pci_dev->id.vendor_id, pci_dev->id.device_id,
pci_dev->addr.domain, pci_dev->addr.bus,
pci_dev->addr.devid, pci_dev->addr.function);
hw->ctrl_bar = (uint8_t *)pci_dev->mem_resource[0].addr;
if (hw->ctrl_bar == NULL) {
RTE_LOG(ERR, PMD,
"hw->ctrl_bar is NULL. BAR0 not configured\n");
return -ENODEV;
}
hw->max_rx_queues = nn_cfg_readl(hw, NFP_NET_CFG_MAX_RXRINGS);
hw->max_tx_queues = nn_cfg_readl(hw, NFP_NET_CFG_MAX_TXRINGS);
/* Work out where in the BAR the queues start. */
switch (pci_dev->id.device_id) {
case PCI_DEVICE_ID_NFP6000_VF_NIC:
start_q = nn_cfg_readl(hw, NFP_NET_CFG_START_TXQ);
tx_bar_off = NFP_PCIE_QUEUE(start_q);
start_q = nn_cfg_readl(hw, NFP_NET_CFG_START_RXQ);
rx_bar_off = NFP_PCIE_QUEUE(start_q);
break;
default:
RTE_LOG(ERR, PMD, "nfp_net: no device ID matching\n");
return -ENODEV;
}
PMD_INIT_LOG(DEBUG, "tx_bar_off: 0x%08x\n", tx_bar_off);
PMD_INIT_LOG(DEBUG, "rx_bar_off: 0x%08x\n", rx_bar_off);
hw->tx_bar = (uint8_t *)pci_dev->mem_resource[2].addr + tx_bar_off;
hw->rx_bar = (uint8_t *)pci_dev->mem_resource[2].addr + rx_bar_off;
PMD_INIT_LOG(DEBUG, "ctrl_bar: %p, tx_bar: %p, rx_bar: %p\n",
hw->ctrl_bar, hw->tx_bar, hw->rx_bar);
nfp_net_cfg_queue_setup(hw);
/* Get some of the read-only fields from the config BAR */
hw->ver = nn_cfg_readl(hw, NFP_NET_CFG_VERSION);
hw->cap = nn_cfg_readl(hw, NFP_NET_CFG_CAP);
hw->max_mtu = nn_cfg_readl(hw, NFP_NET_CFG_MAX_MTU);
hw->mtu = hw->max_mtu;
if (NFD_CFG_MAJOR_VERSION_of(hw->ver) < 2)
hw->rx_offset = NFP_NET_RX_OFFSET;
else
hw->rx_offset = nn_cfg_readl(hw, NFP_NET_CFG_RX_OFFSET_ADDR);
PMD_INIT_LOG(INFO, "VER: %#x, Maximum supported MTU: %d\n",
hw->ver, hw->max_mtu);
PMD_INIT_LOG(INFO, "CAP: %#x, %s%s%s%s%s%s%s%s%s\n", hw->cap,
hw->cap & NFP_NET_CFG_CTRL_PROMISC ? "PROMISC " : "",
hw->cap & NFP_NET_CFG_CTRL_RXCSUM ? "RXCSUM " : "",
hw->cap & NFP_NET_CFG_CTRL_TXCSUM ? "TXCSUM " : "",
hw->cap & NFP_NET_CFG_CTRL_RXVLAN ? "RXVLAN " : "",
hw->cap & NFP_NET_CFG_CTRL_TXVLAN ? "TXVLAN " : "",
hw->cap & NFP_NET_CFG_CTRL_SCATTER ? "SCATTER " : "",
hw->cap & NFP_NET_CFG_CTRL_GATHER ? "GATHER " : "",
hw->cap & NFP_NET_CFG_CTRL_LSO ? "TSO " : "",
hw->cap & NFP_NET_CFG_CTRL_RSS ? "RSS " : "");
pci_dev = eth_dev->pci_dev;
hw->ctrl = 0;
hw->stride_rx = stride;
hw->stride_tx = stride;
PMD_INIT_LOG(INFO, "max_rx_queues: %u, max_tx_queues: %u\n",
hw->max_rx_queues, hw->max_tx_queues);
/* Allocating memory for mac addr */
eth_dev->data->mac_addrs = rte_zmalloc("mac_addr", ETHER_ADDR_LEN, 0);
if (eth_dev->data->mac_addrs == NULL) {
PMD_INIT_LOG(ERR, "Failed to space for MAC address");
return -ENOMEM;
}
/* Using random mac addresses for VFs */
eth_random_addr(&hw->mac_addr[0]);
/* Copying mac address to DPDK eth_dev struct */
ether_addr_copy(&eth_dev->data->mac_addrs[0],
(struct ether_addr *)hw->mac_addr);
PMD_INIT_LOG(INFO, "port %d VendorID=0x%x DeviceID=0x%x "
"mac=%02x:%02x:%02x:%02x:%02x:%02x",
eth_dev->data->port_id, pci_dev->id.vendor_id,
pci_dev->id.device_id,
hw->mac_addr[0], hw->mac_addr[1], hw->mac_addr[2],
hw->mac_addr[3], hw->mac_addr[4], hw->mac_addr[5]);
return 0;
}
static struct rte_pci_id pci_id_nfp_net_map[] = {
{
.vendor_id = PCI_VENDOR_ID_NETRONOME,
.device_id = PCI_DEVICE_ID_NFP6000_PF_NIC,
.subsystem_vendor_id = PCI_ANY_ID,
.subsystem_device_id = PCI_ANY_ID,
},
{
.vendor_id = PCI_VENDOR_ID_NETRONOME,
.device_id = PCI_DEVICE_ID_NFP6000_VF_NIC,
.subsystem_vendor_id = PCI_ANY_ID,
.subsystem_device_id = PCI_ANY_ID,
},
{
.vendor_id = 0,
},
};
static struct eth_driver rte_nfp_net_pmd = {
{
.name = "rte_nfp_net_pmd",
.id_table = pci_id_nfp_net_map,
.drv_flags = RTE_PCI_DRV_NEED_MAPPING | RTE_PCI_DRV_INTR_LSC,
},
.eth_dev_init = nfp_net_init,
.dev_private_size = sizeof(struct nfp_net_adapter),
};
static int
nfp_net_pmd_init(const char *name __rte_unused,
const char *params __rte_unused)
{
PMD_INIT_FUNC_TRACE();
PMD_INIT_LOG(INFO, "librte_pmd_nfp_net version %s\n",
NFP_NET_PMD_VERSION);
rte_eth_driver_register(&rte_nfp_net_pmd);
return 0;
}
static struct rte_driver rte_nfp_net_driver = {
.type = PMD_PDEV,
.init = nfp_net_pmd_init,
};
PMD_REGISTER_DRIVER(rte_nfp_net_driver);
/*
* Local variables:
* c-file-style: "Linux"
* indent-tabs-mode: t
* End:
*/

View file

@ -0,0 +1,324 @@
/*
* Copyright (c) 2014, 2015 Netronome Systems, Inc.
* 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
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT HOLDER 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.
*/
/*
* vim:shiftwidth=8:noexpandtab
*
* Netronome network device driver: Control BAR layout
*/
#ifndef _NFP_NET_CTRL_H_
#define _NFP_NET_CTRL_H_
/*
* Configuration BAR size.
*
* The configuration BAR is 8K in size, but on the NFP6000, due to
* THB-350, 32k needs to be reserved.
*/
#ifdef __NFP_IS_6000
#define NFP_NET_CFG_BAR_SZ (32 * 1024)
#else
#define NFP_NET_CFG_BAR_SZ (8 * 1024)
#endif
/* Offset in Freelist buffer where packet starts on RX */
#define NFP_NET_RX_OFFSET 32
/* Hash type pre-pended when a RSS hash was computed */
#define NFP_NET_RSS_NONE 0
#define NFP_NET_RSS_IPV4 1
#define NFP_NET_RSS_IPV6 2
#define NFP_NET_RSS_IPV6_EX 3
#define NFP_NET_RSS_IPV4_TCP 4
#define NFP_NET_RSS_IPV6_TCP 5
#define NFP_NET_RSS_IPV6_EX_TCP 6
#define NFP_NET_RSS_IPV4_UDP 7
#define NFP_NET_RSS_IPV6_UDP 8
#define NFP_NET_RSS_IPV6_EX_UDP 9
/*
* @NFP_NET_TXR_MAX: Maximum number of TX rings
* @NFP_NET_TXR_MASK: Mask for TX rings
* @NFP_NET_RXR_MAX: Maximum number of RX rings
* @NFP_NET_RXR_MASK: Mask for RX rings
*/
#define NFP_NET_TXR_MAX 64
#define NFP_NET_TXR_MASK (NFP_NET_TXR_MAX - 1)
#define NFP_NET_RXR_MAX 64
#define NFP_NET_RXR_MASK (NFP_NET_RXR_MAX - 1)
/*
* Read/Write config words (0x0000 - 0x002c)
* @NFP_NET_CFG_CTRL: Global control
* @NFP_NET_CFG_UPDATE: Indicate which fields are updated
* @NFP_NET_CFG_TXRS_ENABLE: Bitmask of enabled TX rings
* @NFP_NET_CFG_RXRS_ENABLE: Bitmask of enabled RX rings
* @NFP_NET_CFG_MTU: Set MTU size
* @NFP_NET_CFG_FLBUFSZ: Set freelist buffer size (must be larger than MTU)
* @NFP_NET_CFG_EXN: MSI-X table entry for exceptions
* @NFP_NET_CFG_LSC: MSI-X table entry for link state changes
* @NFP_NET_CFG_MACADDR: MAC address
*
* TODO:
* - define Error details in UPDATE
*/
#define NFP_NET_CFG_CTRL 0x0000
#define NFP_NET_CFG_CTRL_ENABLE (0x1 << 0) /* Global enable */
#define NFP_NET_CFG_CTRL_PROMISC (0x1 << 1) /* Enable Promisc mode */
#define NFP_NET_CFG_CTRL_L2BC (0x1 << 2) /* Allow L2 Broadcast */
#define NFP_NET_CFG_CTRL_L2MC (0x1 << 3) /* Allow L2 Multicast */
#define NFP_NET_CFG_CTRL_RXCSUM (0x1 << 4) /* Enable RX Checksum */
#define NFP_NET_CFG_CTRL_TXCSUM (0x1 << 5) /* Enable TX Checksum */
#define NFP_NET_CFG_CTRL_RXVLAN (0x1 << 6) /* Enable VLAN strip */
#define NFP_NET_CFG_CTRL_TXVLAN (0x1 << 7) /* Enable VLAN insert */
#define NFP_NET_CFG_CTRL_SCATTER (0x1 << 8) /* Scatter DMA */
#define NFP_NET_CFG_CTRL_GATHER (0x1 << 9) /* Gather DMA */
#define NFP_NET_CFG_CTRL_LSO (0x1 << 10) /* LSO/TSO */
#define NFP_NET_CFG_CTRL_RINGCFG (0x1 << 16) /* Ring runtime changes */
#define NFP_NET_CFG_CTRL_RSS (0x1 << 17) /* RSS */
#define NFP_NET_CFG_CTRL_IRQMOD (0x1 << 18) /* Interrupt moderation */
#define NFP_NET_CFG_CTRL_RINGPRIO (0x1 << 19) /* Ring priorities */
#define NFP_NET_CFG_CTRL_MSIXAUTO (0x1 << 20) /* MSI-X auto-masking */
#define NFP_NET_CFG_CTRL_TXRWB (0x1 << 21) /* Write-back of TX ring*/
#define NFP_NET_CFG_CTRL_L2SWITCH (0x1 << 22) /* L2 Switch */
#define NFP_NET_CFG_CTRL_L2SWITCH_LOCAL (0x1 << 23) /* Switch to local */
#define NFP_NET_CFG_CTRL_VXLAN (0x1 << 24) /* Enable VXLAN */
#define NFP_NET_CFG_CTRL_NVGRE (0x1 << 25) /* Enable NVGRE */
#define NFP_NET_CFG_UPDATE 0x0004
#define NFP_NET_CFG_UPDATE_GEN (0x1 << 0) /* General update */
#define NFP_NET_CFG_UPDATE_RING (0x1 << 1) /* Ring config change */
#define NFP_NET_CFG_UPDATE_RSS (0x1 << 2) /* RSS config change */
#define NFP_NET_CFG_UPDATE_TXRPRIO (0x1 << 3) /* TX Ring prio change */
#define NFP_NET_CFG_UPDATE_RXRPRIO (0x1 << 4) /* RX Ring prio change */
#define NFP_NET_CFG_UPDATE_MSIX (0x1 << 5) /* MSI-X change */
#define NFP_NET_CFG_UPDATE_L2SWITCH (0x1 << 6) /* Switch changes */
#define NFP_NET_CFG_UPDATE_RESET (0x1 << 7) /* Update due to FLR */
#define NFP_NET_CFG_UPDATE_IRQMOD (0x1 << 8) /* IRQ mod change */
#define NFP_NET_CFG_UPDATE_VXLAN (0x1 << 9) /* VXLAN port change */
#define NFP_NET_CFG_UPDATE_ERR (0x1 << 31) /* A error occurred */
#define NFP_NET_CFG_TXRS_ENABLE 0x0008
#define NFP_NET_CFG_RXRS_ENABLE 0x0010
#define NFP_NET_CFG_MTU 0x0018
#define NFP_NET_CFG_FLBUFSZ 0x001c
#define NFP_NET_CFG_EXN 0x001f
#define NFP_NET_CFG_LSC 0x0020
#define NFP_NET_CFG_MACADDR 0x0024
/*
* Read-only words (0x0030 - 0x0050):
* @NFP_NET_CFG_VERSION: Firmware version number
* @NFP_NET_CFG_STS: Status
* @NFP_NET_CFG_CAP: Capabilities (same bits as @NFP_NET_CFG_CTRL)
* @NFP_NET_MAX_TXRINGS: Maximum number of TX rings
* @NFP_NET_MAX_RXRINGS: Maximum number of RX rings
* @NFP_NET_MAX_MTU: Maximum support MTU
* @NFP_NET_CFG_START_TXQ: Start Queue Control Queue to use for TX (PF only)
* @NFP_NET_CFG_START_RXQ: Start Queue Control Queue to use for RX (PF only)
*
* TODO:
* - define more STS bits
*/
#define NFP_NET_CFG_VERSION 0x0030
#define NFP_NET_CFG_VERSION_RESERVED_MASK (0xff << 24)
#define NFP_NET_CFG_VERSION_CLASS_MASK (0xff << 16)
#define NFP_NET_CFG_VERSION_CLASS(x) (((x) & 0xff) << 16)
#define NFP_NET_CFG_VERSION_CLASS_GENERIC 0
#define NFP_NET_CFG_VERSION_MAJOR_MASK (0xff << 8)
#define NFP_NET_CFG_VERSION_MAJOR(x) (((x) & 0xff) << 8)
#define NFP_NET_CFG_VERSION_MINOR_MASK (0xff << 0)
#define NFP_NET_CFG_VERSION_MINOR(x) (((x) & 0xff) << 0)
#define NFP_NET_CFG_STS 0x0034
#define NFP_NET_CFG_STS_LINK (0x1 << 0) /* Link up or down */
#define NFP_NET_CFG_CAP 0x0038
#define NFP_NET_CFG_MAX_TXRINGS 0x003c
#define NFP_NET_CFG_MAX_RXRINGS 0x0040
#define NFP_NET_CFG_MAX_MTU 0x0044
/* Next two words are being used by VFs for solving THB350 issue */
#define NFP_NET_CFG_START_TXQ 0x0048
#define NFP_NET_CFG_START_RXQ 0x004c
/*
* NFP-3200 workaround (0x0050 - 0x0058)
* @NFP_NET_CFG_SPARE_ADDR: DMA address for ME code to use (e.g. YDS-155 fix)
*/
#define NFP_NET_CFG_SPARE_ADDR 0x0050
/**
* NFP6000/NFP4000 - Prepend configuration
*/
#define NFP_NET_CFG_RX_OFFSET 0x0050
#define NFP_NET_CFG_RX_OFFSET_DYNAMIC 0 /* Prepend mode */
/**
* Reuse spare address to contain the offset from the start of
* the host buffer where the first byte of the received frame
* will land. Any metadata will come prior to that offset. If the
* value in this field is 0, it means that that the metadata will
* always land starting at the first byte of the host buffer and
* packet data will immediately follow the metadata. As always,
* the RX descriptor indicates the presence or absence of metadata
* along with the length thereof.
*/
#define NFP_NET_CFG_RX_OFFSET_ADDR 0x0050
#define NFP_NET_CFG_VXLAN_PORT 0x0060
#define NFP_NET_CFG_VXLAN_SZ 0x0008
/* Offload definitions */
#define NFP_NET_N_VXLAN_PORTS (NFP_NET_CFG_VXLAN_SZ / sizeof(uint16_t))
/**
* 64B reserved for future use (0x0080 - 0x00c0)
*/
#define NFP_NET_CFG_RESERVED 0x0080
#define NFP_NET_CFG_RESERVED_SZ 0x0040
/*
* RSS configuration (0x0100 - 0x01ac):
* Used only when NFP_NET_CFG_CTRL_RSS is enabled
* @NFP_NET_CFG_RSS_CFG: RSS configuration word
* @NFP_NET_CFG_RSS_KEY: RSS "secret" key
* @NFP_NET_CFG_RSS_ITBL: RSS indirection table
*/
#define NFP_NET_CFG_RSS_BASE 0x0100
#define NFP_NET_CFG_RSS_CTRL NFP_NET_CFG_RSS_BASE
#define NFP_NET_CFG_RSS_MASK (0x7f)
#define NFP_NET_CFG_RSS_MASK_of(_x) ((_x) & 0x7f)
#define NFP_NET_CFG_RSS_IPV4 (1 << 8) /* RSS for IPv4 */
#define NFP_NET_CFG_RSS_IPV6 (1 << 9) /* RSS for IPv6 */
#define NFP_NET_CFG_RSS_IPV4_TCP (1 << 10) /* RSS for IPv4/TCP */
#define NFP_NET_CFG_RSS_IPV4_UDP (1 << 11) /* RSS for IPv4/UDP */
#define NFP_NET_CFG_RSS_IPV6_TCP (1 << 12) /* RSS for IPv6/TCP */
#define NFP_NET_CFG_RSS_IPV6_UDP (1 << 13) /* RSS for IPv6/UDP */
#define NFP_NET_CFG_RSS_TOEPLITZ (1 << 24) /* Use Toeplitz hash */
#define NFP_NET_CFG_RSS_KEY (NFP_NET_CFG_RSS_BASE + 0x4)
#define NFP_NET_CFG_RSS_KEY_SZ 0x28
#define NFP_NET_CFG_RSS_ITBL (NFP_NET_CFG_RSS_BASE + 0x4 + \
NFP_NET_CFG_RSS_KEY_SZ)
#define NFP_NET_CFG_RSS_ITBL_SZ 0x80
/*
* TX ring configuration (0x200 - 0x800)
* @NFP_NET_CFG_TXR_BASE: Base offset for TX ring configuration
* @NFP_NET_CFG_TXR_ADDR: Per TX ring DMA address (8B entries)
* @NFP_NET_CFG_TXR_WB_ADDR: Per TX ring write back DMA address (8B entries)
* @NFP_NET_CFG_TXR_SZ: Per TX ring ring size (1B entries)
* @NFP_NET_CFG_TXR_VEC: Per TX ring MSI-X table entry (1B entries)
* @NFP_NET_CFG_TXR_PRIO: Per TX ring priority (1B entries)
* @NFP_NET_CFG_TXR_IRQ_MOD: Per TX ring interrupt moderation (4B entries)
*/
#define NFP_NET_CFG_TXR_BASE 0x0200
#define NFP_NET_CFG_TXR_ADDR(_x) (NFP_NET_CFG_TXR_BASE + ((_x) * 0x8))
#define NFP_NET_CFG_TXR_WB_ADDR(_x) (NFP_NET_CFG_TXR_BASE + 0x200 + \
((_x) * 0x8))
#define NFP_NET_CFG_TXR_SZ(_x) (NFP_NET_CFG_TXR_BASE + 0x400 + (_x))
#define NFP_NET_CFG_TXR_VEC(_x) (NFP_NET_CFG_TXR_BASE + 0x440 + (_x))
#define NFP_NET_CFG_TXR_PRIO(_x) (NFP_NET_CFG_TXR_BASE + 0x480 + (_x))
#define NFP_NET_CFG_TXR_IRQ_MOD(_x) (NFP_NET_CFG_TXR_BASE + 0x500 + \
((_x) * 0x4))
/*
* RX ring configuration (0x0800 - 0x0c00)
* @NFP_NET_CFG_RXR_BASE: Base offset for RX ring configuration
* @NFP_NET_CFG_RXR_ADDR: Per TX ring DMA address (8B entries)
* @NFP_NET_CFG_RXR_SZ: Per TX ring ring size (1B entries)
* @NFP_NET_CFG_RXR_VEC: Per TX ring MSI-X table entry (1B entries)
* @NFP_NET_CFG_RXR_PRIO: Per TX ring priority (1B entries)
* @NFP_NET_CFG_RXR_IRQ_MOD: Per TX ring interrupt moderation (4B entries)
*/
#define NFP_NET_CFG_RXR_BASE 0x0800
#define NFP_NET_CFG_RXR_ADDR(_x) (NFP_NET_CFG_RXR_BASE + ((_x) * 0x8))
#define NFP_NET_CFG_RXR_SZ(_x) (NFP_NET_CFG_RXR_BASE + 0x200 + (_x))
#define NFP_NET_CFG_RXR_VEC(_x) (NFP_NET_CFG_RXR_BASE + 0x240 + (_x))
#define NFP_NET_CFG_RXR_PRIO(_x) (NFP_NET_CFG_RXR_BASE + 0x280 + (_x))
#define NFP_NET_CFG_RXR_IRQ_MOD(_x) (NFP_NET_CFG_RXR_BASE + 0x300 + \
((_x) * 0x4))
/*
* Interrupt Control/Cause registers (0x0c00 - 0x0d00)
* These registers are only used when MSI-X auto-masking is not
* enabled (@NFP_NET_CFG_CTRL_MSIXAUTO not set). The array is index
* by MSI-X entry and are 1B in size. If an entry is zero, the
* corresponding entry is enabled. If the FW generates an interrupt,
* it writes a cause into the corresponding field. This also masks
* the MSI-X entry and the host driver must clear the register to
* re-enable the interrupt.
*/
#define NFP_NET_CFG_ICR_BASE 0x0c00
#define NFP_NET_CFG_ICR(_x) (NFP_NET_CFG_ICR_BASE + (_x))
#define NFP_NET_CFG_ICR_UNMASKED 0x0
#define NFP_NET_CFG_ICR_RXTX 0x1
#define NFP_NET_CFG_ICR_LSC 0x2
/*
* General device stats (0x0d00 - 0x0d90)
* all counters are 64bit.
*/
#define NFP_NET_CFG_STATS_BASE 0x0d00
#define NFP_NET_CFG_STATS_RX_DISCARDS (NFP_NET_CFG_STATS_BASE + 0x00)
#define NFP_NET_CFG_STATS_RX_ERRORS (NFP_NET_CFG_STATS_BASE + 0x08)
#define NFP_NET_CFG_STATS_RX_OCTETS (NFP_NET_CFG_STATS_BASE + 0x10)
#define NFP_NET_CFG_STATS_RX_UC_OCTETS (NFP_NET_CFG_STATS_BASE + 0x18)
#define NFP_NET_CFG_STATS_RX_MC_OCTETS (NFP_NET_CFG_STATS_BASE + 0x20)
#define NFP_NET_CFG_STATS_RX_BC_OCTETS (NFP_NET_CFG_STATS_BASE + 0x28)
#define NFP_NET_CFG_STATS_RX_FRAMES (NFP_NET_CFG_STATS_BASE + 0x30)
#define NFP_NET_CFG_STATS_RX_MC_FRAMES (NFP_NET_CFG_STATS_BASE + 0x38)
#define NFP_NET_CFG_STATS_RX_BC_FRAMES (NFP_NET_CFG_STATS_BASE + 0x40)
#define NFP_NET_CFG_STATS_TX_DISCARDS (NFP_NET_CFG_STATS_BASE + 0x48)
#define NFP_NET_CFG_STATS_TX_ERRORS (NFP_NET_CFG_STATS_BASE + 0x50)
#define NFP_NET_CFG_STATS_TX_OCTETS (NFP_NET_CFG_STATS_BASE + 0x58)
#define NFP_NET_CFG_STATS_TX_UC_OCTETS (NFP_NET_CFG_STATS_BASE + 0x60)
#define NFP_NET_CFG_STATS_TX_MC_OCTETS (NFP_NET_CFG_STATS_BASE + 0x68)
#define NFP_NET_CFG_STATS_TX_BC_OCTETS (NFP_NET_CFG_STATS_BASE + 0x70)
#define NFP_NET_CFG_STATS_TX_FRAMES (NFP_NET_CFG_STATS_BASE + 0x78)
#define NFP_NET_CFG_STATS_TX_MC_FRAMES (NFP_NET_CFG_STATS_BASE + 0x80)
#define NFP_NET_CFG_STATS_TX_BC_FRAMES (NFP_NET_CFG_STATS_BASE + 0x88)
/*
* Per ring stats (0x1000 - 0x1800)
* options, 64bit per entry
* @NFP_NET_CFG_TXR_STATS: TX ring statistics (Packet and Byte count)
* @NFP_NET_CFG_RXR_STATS: RX ring statistics (Packet and Byte count)
*/
#define NFP_NET_CFG_TXR_STATS_BASE 0x1000
#define NFP_NET_CFG_TXR_STATS(_x) (NFP_NET_CFG_TXR_STATS_BASE + \
((_x) * 0x10))
#define NFP_NET_CFG_RXR_STATS_BASE 0x1400
#define NFP_NET_CFG_RXR_STATS(_x) (NFP_NET_CFG_RXR_STATS_BASE + \
((_x) * 0x10))
#endif /* _NFP_NET_CTRL_H_ */
/*
* Local variables:
* c-file-style: "Linux"
* indent-tabs-mode: t
* End:
*/

View file

@ -0,0 +1,75 @@
/*
* Copyright (c) 2014, 2015 Netronome Systems, Inc.
* 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
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT HOLDER 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.
*/
#ifndef _NFP_NET_LOGS_H_
#define _NFP_NET_LOGS_H_
#include <rte_log.h>
#define RTE_LIBRTE_NFP_NET_DEBUG_INIT 1
#ifdef RTE_LIBRTE_NFP_NET_DEBUG_INIT
#define PMD_INIT_LOG(level, fmt, args...) \
RTE_LOG(level, PMD, "%s(): " fmt "\n", __func__, ## args)
#define PMD_INIT_FUNC_TRACE() PMD_INIT_LOG(DEBUG, " >>")
#else
#define PMD_INIT_LOG(level, fmt, args...) do { } while (0)
#define PMD_INIT_FUNC_TRACE() do { } while (0)
#endif
#ifdef RTE_LIBRTE_NFP_NET_DEBUG_RX
#define PMD_RX_LOG(level, fmt, args...) \
RTE_LOG(level, PMD, "%s() rx: " fmt, __func__, ## args)
#else
#define PMD_RX_LOG(level, fmt, args...) do { } while (0)
#endif
#ifdef RTE_LIBRTE_NFP_NET_DEBUG_TX
#define PMD_TX_LOG(level, fmt, args...) \
RTE_LOG(level, PMD, "%s() tx: " fmt, __func__, ## args)
#else
#define PMD_TX_LOG(level, fmt, args...) do { } while (0)
#endif
#ifdef RTE_LIBRTE_NFP_NET_DEBUG_DRIVER
#define PMD_DRV_LOG(level, fmt, args...) \
RTE_LOG(level, PMD, "%s(): " fmt, __func__, ## args)
#else
#define PMD_DRV_LOG(level, fmt, args...) do { } while (0)
#endif
#ifdef RTE_LIBRTE_NFP_NET_DEBUG_INIT
#define ASSERT(x) if (!(x)) rte_panic("NFP_NET: x")
#else
#define ASSERT(x) do { } while (0)
#endif
#endif /* _NFP_NET_LOGS_H_ */

View file

@ -0,0 +1,453 @@
/*
* Copyright (c) 2014, 2015 Netronome Systems, Inc.
* 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
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT HOLDER 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.
*/
/*
* vim:shiftwidth=8:noexpandtab
*
* @file dpdk/pmd/nfp_net_pmd.h
*
* Netronome NFP_NET PDM driver
*/
#ifndef _NFP_NET_PMD_H_
#define _NFP_NET_PMD_H_
#define NFP_NET_PMD_VERSION "0.1"
#define PCI_VENDOR_ID_NETRONOME 0x19ee
#define PCI_DEVICE_ID_NFP6000_PF_NIC 0x6000
#define PCI_DEVICE_ID_NFP6000_VF_NIC 0x6003
/* Forward declaration */
struct nfp_net_adapter;
/*
* The maximum number of descriptors is limited by design as
* DPDK uses uint16_t variables for these values
*/
#define NFP_NET_MAX_TX_DESC (32 * 1024)
#define NFP_NET_MIN_TX_DESC 64
#define NFP_NET_MAX_RX_DESC (32 * 1024)
#define NFP_NET_MIN_RX_DESC 64
/* Bar allocation */
#define NFP_NET_CRTL_BAR 0
#define NFP_NET_TX_BAR 2
#define NFP_NET_RX_BAR 2
/* Macros for accessing the Queue Controller Peripheral 'CSRs' */
#define NFP_QCP_QUEUE_OFF(_x) ((_x) * 0x800)
#define NFP_QCP_QUEUE_ADD_RPTR 0x0000
#define NFP_QCP_QUEUE_ADD_WPTR 0x0004
#define NFP_QCP_QUEUE_STS_LO 0x0008
#define NFP_QCP_QUEUE_STS_LO_READPTR_mask (0x3ffff)
#define NFP_QCP_QUEUE_STS_HI 0x000c
#define NFP_QCP_QUEUE_STS_HI_WRITEPTR_mask (0x3ffff)
/* Interrupt definitions */
#define NFP_NET_IRQ_LSC_IDX 0
#define RTE_MBUF_DATA_DMA_ADDR(mb) \
((uint64_t)((mb)->buf_physaddr + (mb)->data_off))
/* Default values for RX/TX configuration */
#define DEFAULT_RX_FREE_THRESH 32
#define DEFAULT_RX_PTHRESH 8
#define DEFAULT_RX_HTHRESH 8
#define DEFAULT_RX_WTHRESH 0
#define DEFAULT_TX_RS_THRESH 32
#define DEFAULT_TX_FREE_THRESH 32
#define DEFAULT_TX_PTHRESH 32
#define DEFAULT_TX_HTHRESH 0
#define DEFAULT_TX_WTHRESH 0
#define DEFAULT_TX_RSBIT_THRESH 32
/* Alignment for dma zones */
#define NFP_MEMZONE_ALIGN 128
/*
* This is used by the reconfig protocol. It sets the maximum time waiting in
* milliseconds before a reconfig timeout happens.
*/
#define NFP_NET_POLL_TIMEOUT 5000
#define NFP_QCP_QUEUE_ADDR_SZ (0x800)
#define NFP_NET_LINK_DOWN_CHECK_TIMEOUT 4000 /* ms */
#define NFP_NET_LINK_UP_CHECK_TIMEOUT 1000 /* ms */
/* Version number helper defines */
#define NFD_CFG_CLASS_VER_msk 0xff
#define NFD_CFG_CLASS_VER_shf 24
#define NFD_CFG_CLASS_VER(x) (((x) & 0xff) << 24)
#define NFD_CFG_CLASS_VER_of(x) (((x) >> 24) & 0xff)
#define NFD_CFG_CLASS_TYPE_msk 0xff
#define NFD_CFG_CLASS_TYPE_shf 16
#define NFD_CFG_CLASS_TYPE(x) (((x) & 0xff) << 16)
#define NFD_CFG_CLASS_TYPE_of(x) (((x) >> 16) & 0xff)
#define NFD_CFG_MAJOR_VERSION_msk 0xff
#define NFD_CFG_MAJOR_VERSION_shf 8
#define NFD_CFG_MAJOR_VERSION(x) (((x) & 0xff) << 8)
#define NFD_CFG_MAJOR_VERSION_of(x) (((x) >> 8) & 0xff)
#define NFD_CFG_MINOR_VERSION_msk 0xff
#define NFD_CFG_MINOR_VERSION_shf 0
#define NFD_CFG_MINOR_VERSION(x) (((x) & 0xff) << 0)
#define NFD_CFG_MINOR_VERSION_of(x) (((x) >> 0) & 0xff)
#include <linux/types.h>
static inline uint8_t nn_readb(volatile const void *addr)
{
return *((volatile const uint8_t *)(addr));
}
static inline void nn_writeb(uint8_t val, volatile void *addr)
{
*((volatile uint8_t *)(addr)) = val;
}
static inline uint32_t nn_readl(volatile const void *addr)
{
return *((volatile const uint32_t *)(addr));
}
static inline void nn_writel(uint32_t val, volatile void *addr)
{
*((volatile uint32_t *)(addr)) = val;
}
static inline uint64_t nn_readq(volatile void *addr)
{
const volatile uint32_t *p = addr;
uint32_t low, high;
high = nn_readl((volatile const void *)(p + 1));
low = nn_readl((volatile const void *)p);
return low + ((uint64_t)high << 32);
}
static inline void nn_writeq(uint64_t val, volatile void *addr)
{
nn_writel(val >> 32, (volatile char *)addr + 4);
nn_writel(val, addr);
}
/* TX descriptor format */
#define PCIE_DESC_TX_EOP (1 << 7)
#define PCIE_DESC_TX_OFFSET_MASK (0x7f)
/* Flags in the host TX descriptor */
#define PCIE_DESC_TX_CSUM (1 << 7)
#define PCIE_DESC_TX_IP4_CSUM (1 << 6)
#define PCIE_DESC_TX_TCP_CSUM (1 << 5)
#define PCIE_DESC_TX_UDP_CSUM (1 << 4)
#define PCIE_DESC_TX_VLAN (1 << 3)
#define PCIE_DESC_TX_LSO (1 << 2)
#define PCIE_DESC_TX_ENCAP_NONE (0)
#define PCIE_DESC_TX_ENCAP_VXLAN (1 << 1)
#define PCIE_DESC_TX_ENCAP_GRE (1 << 0)
struct nfp_net_tx_desc {
union {
struct {
uint8_t dma_addr_hi; /* High bits of host buf address */
__le16 dma_len; /* Length to DMA for this desc */
uint8_t offset_eop; /* Offset in buf where pkt starts +
* highest bit is eop flag.
*/
__le32 dma_addr_lo; /* Low 32bit of host buf addr */
__le16 lso; /* MSS to be used for LSO */
uint8_t l4_offset; /* LSO, where the L4 data starts */
uint8_t flags; /* TX Flags, see @PCIE_DESC_TX_* */
__le16 vlan; /* VLAN tag to add if indicated */
__le16 data_len; /* Length of frame + meta data */
} __attribute__((__packed__));
__le32 vals[4];
};
};
struct nfp_net_txq {
struct nfp_net_hw *hw; /* Backpointer to nfp_net structure */
/*
* Queue information: @qidx is the queue index from Linux's
* perspective. @tx_qcidx is the index of the Queue
* Controller Peripheral queue relative to the TX queue BAR.
* @cnt is the size of the queue in number of
* descriptors. @qcp_q is a pointer to the base of the queue
* structure on the NFP
*/
uint8_t *qcp_q;
/*
* Read and Write pointers. @wr_p and @rd_p are host side pointer,
* they are free running and have little relation to the QCP pointers *
* @qcp_rd_p is a local copy queue controller peripheral read pointer
*/
uint32_t wr_p;
uint32_t rd_p;
uint32_t qcp_rd_p;
uint32_t tx_count;
uint32_t tx_free_thresh;
uint32_t tail;
/*
* For each descriptor keep a reference to the mbuff and
* DMA address used until completion is signalled.
*/
struct {
struct rte_mbuf *mbuf;
} *txbufs;
/*
* Information about the host side queue location. @txds is
* the virtual address for the queue, @dma is the DMA address
* of the queue and @size is the size in bytes for the queue
* (needed for free)
*/
struct nfp_net_tx_desc *txds;
/*
* At this point 56 bytes have been used for all the fields in the
* TX critical path. We have room for 8 bytes and still all placed
* in a cache line. We are not using the threshold values below nor
* the txq_flags but if we need to, we can add the most used in the
* remaining bytes.
*/
uint32_t tx_rs_thresh; /* not used by now. Future? */
uint32_t tx_pthresh; /* not used by now. Future? */
uint32_t tx_hthresh; /* not used by now. Future? */
uint32_t tx_wthresh; /* not used by now. Future? */
uint32_t txq_flags; /* not used by now. Future? */
uint8_t port_id;
int qidx;
int tx_qcidx;
__le64 dma;
} __attribute__ ((__aligned__(64)));
/* RX and freelist descriptor format */
#define PCIE_DESC_RX_DD (1 << 7)
#define PCIE_DESC_RX_META_LEN_MASK (0x7f)
/* Flags in the RX descriptor */
#define PCIE_DESC_RX_RSS (1 << 15)
#define PCIE_DESC_RX_I_IP4_CSUM (1 << 14)
#define PCIE_DESC_RX_I_IP4_CSUM_OK (1 << 13)
#define PCIE_DESC_RX_I_TCP_CSUM (1 << 12)
#define PCIE_DESC_RX_I_TCP_CSUM_OK (1 << 11)
#define PCIE_DESC_RX_I_UDP_CSUM (1 << 10)
#define PCIE_DESC_RX_I_UDP_CSUM_OK (1 << 9)
#define PCIE_DESC_RX_INGRESS_PORT (1 << 8)
#define PCIE_DESC_RX_EOP (1 << 7)
#define PCIE_DESC_RX_IP4_CSUM (1 << 6)
#define PCIE_DESC_RX_IP4_CSUM_OK (1 << 5)
#define PCIE_DESC_RX_TCP_CSUM (1 << 4)
#define PCIE_DESC_RX_TCP_CSUM_OK (1 << 3)
#define PCIE_DESC_RX_UDP_CSUM (1 << 2)
#define PCIE_DESC_RX_UDP_CSUM_OK (1 << 1)
#define PCIE_DESC_RX_VLAN (1 << 0)
struct nfp_net_rx_desc {
union {
/* Freelist descriptor */
struct {
uint8_t dma_addr_hi;
__le16 spare;
uint8_t dd;
__le32 dma_addr_lo;
} __attribute__((__packed__)) fld;
/* RX descriptor */
struct {
__le16 data_len;
uint8_t reserved;
uint8_t meta_len_dd;
__le16 flags;
__le16 vlan;
} __attribute__((__packed__)) rxd;
__le32 vals[2];
};
};
struct nfp_net_rx_buff {
struct rte_mbuf *mbuf;
};
struct nfp_net_rxq {
struct nfp_net_hw *hw; /* Backpointer to nfp_net structure */
/*
* @qcp_fl and @qcp_rx are pointers to the base addresses of the
* freelist and RX queue controller peripheral queue structures on the
* NFP
*/
uint8_t *qcp_fl;
uint8_t *qcp_rx;
/*
* Read and Write pointers. @wr_p and @rd_p are host side
* pointer, they are free running and have little relation to
* the QCP pointers. @wr_p is where the driver adds new
* freelist descriptors and @rd_p is where the driver start
* reading descriptors for newly arrive packets from.
*/
uint32_t wr_p;
uint32_t rd_p;
/*
* For each buffer placed on the freelist, record the
* associated SKB
*/
struct nfp_net_rx_buff *rxbufs;
/*
* Information about the host side queue location. @rxds is
* the virtual address for the queue
*/
struct nfp_net_rx_desc *rxds;
/*
* The mempool is created by the user specifying a mbuf size.
* We save here the reference of the mempool needed in the RX
* path and the mbuf size for checking received packets can be
* safely copied to the mbuf using the NFP_NET_RX_OFFSET
*/
struct rte_mempool *mem_pool;
uint16_t mbuf_size;
/*
* Next two fields are used for giving more free descriptors
* to the NFP
*/
uint16_t rx_free_thresh;
uint16_t nb_rx_hold;
/* the size of the queue in number of descriptors */
uint16_t rx_count;
/*
* Fields above this point fit in a single cache line and are all used
* in the RX critical path. Fields below this point are just used
* during queue configuration or not used at all (yet)
*/
/* referencing dev->data->port_id */
uint16_t port_id;
uint8_t crc_len; /* Not used by now */
uint8_t drop_en; /* Not used by now */
/* DMA address of the queue */
__le64 dma;
/*
* Queue information: @qidx is the queue index from Linux's
* perspective. @fl_qcidx is the index of the Queue
* Controller peripheral queue relative to the RX queue BAR
* used for the freelist and @rx_qcidx is the Queue Controller
* Peripheral index for the RX queue.
*/
int qidx;
int fl_qcidx;
int rx_qcidx;
} __attribute__ ((__aligned__(64)));
struct nfp_net_hw {
/* Info from the firmware */
uint32_t ver;
uint32_t cap;
uint32_t max_mtu;
uint32_t mtu;
uint32_t rx_offset;
/* Current values for control */
uint32_t ctrl;
uint8_t *ctrl_bar;
uint8_t *tx_bar;
uint8_t *rx_bar;
int stride_rx;
int stride_tx;
uint8_t *qcp_cfg;
uint32_t max_tx_queues;
uint32_t max_rx_queues;
uint16_t flbufsz;
uint16_t device_id;
uint16_t vendor_id;
uint16_t subsystem_device_id;
uint16_t subsystem_vendor_id;
#if defined(DSTQ_SELECTION)
#if DSTQ_SELECTION
uint16_t device_function;
#endif
#endif
uint8_t mac_addr[ETHER_ADDR_LEN];
/* Records starting point for counters */
struct rte_eth_stats eth_stats_base;
#ifdef NFP_NET_LIBNFP
struct nfp_cpp *cpp;
struct nfp_cpp_area *ctrl_area;
struct nfp_cpp_area *tx_area;
struct nfp_cpp_area *rx_area;
struct nfp_cpp_area *msix_area;
#endif
};
struct nfp_net_adapter {
struct nfp_net_hw hw;
};
#define NFP_NET_DEV_PRIVATE_TO_HW(adapter)\
(&((struct nfp_net_adapter *)adapter)->hw)
#endif /* _NFP_NET_PMD_H_ */
/*
* Local variables:
* c-file-style: "Linux"
* indent-tabs-mode: t
* End:
*/

View file

@ -0,0 +1,3 @@
DPDK_2.2 {
local: *;
};

View file

@ -146,6 +146,7 @@ _LDLIBS-$(CONFIG_RTE_LIBRTE_IXGBE_PMD) += -lrte_pmd_ixgbe
_LDLIBS-$(CONFIG_RTE_LIBRTE_E1000_PMD) += -lrte_pmd_e1000
_LDLIBS-$(CONFIG_RTE_LIBRTE_MLX4_PMD) += -lrte_pmd_mlx4
_LDLIBS-$(CONFIG_RTE_LIBRTE_MLX5_PMD) += -lrte_pmd_mlx5
_LDLIBS-$(CONFIG_RTE_LIBRTE_NFP_PMD) += -lrte_pmd_nfp
_LDLIBS-$(CONFIG_RTE_LIBRTE_PMD_SZEDATA2) += -lrte_pmd_szedata2
_LDLIBS-$(CONFIG_RTE_LIBRTE_MPIPE_PMD) += -lrte_pmd_mpipe
_LDLIBS-$(CONFIG_RTE_LIBRTE_PMD_RING) += -lrte_pmd_ring

View file

@ -100,6 +100,7 @@ config () # <directory> <target> <options>
test "$DPDK_DEP_ZLIB" != y || \
echo $2 | grep -q '^i686' || \
sed -ri 's,(BNX2X_PMD=)n,\1y,' $1/.config
sed -ri 's,(NFP_PMD=)n,\1y,' $1/.config
test "$DPDK_DEP_PCAP" != y || \
sed -ri 's,(PCAP=)n,\1y,' $1/.config
test -z "$AESNI_MULTI_BUFFER_LIB_PATH" || \