DPDK patches and discussions
 help / color / mirror / Atom feed
* [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville
@ 2014-09-26  6:03 Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 01/20] i40e: set up and initialize flow director Jingjing Wu
                   ` (21 more replies)
  0 siblings, 22 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - define new APIs to support multi-kind filters and their operations.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics and FD_ID report .
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison
 
v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 change:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison

Jingjing Wu (20):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  lib/librte_ether: new filter APIs definition
  lib/librte_ether: define structures for adding/deleting flow director
  i40e: implement operations to add/delete flow director
  app/test-pmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  i40e: report flow director match info to mbuf
  lib/librte_ether: define structures for getting flow director information
  i40e: implement operations to get fdir info
  app/test-pmd: display fdir statistics
  i40e: implement operation to flush flow director table
  app/test-pmd: add test command to flush flow director table
  lib/librte_ether: define structures for configuring flexible payload
  i40e: implement operations to configure flexible payload
  app/test-pmd: add test command to configure flexible payload
  lib/librte_ether: define structures for configuring flex masks
  i40e: implement operations to configure flexible masks
  app/test-pmd: add test command to configure flexible masks

 app/test-pmd/cmdline.c            |  813 +++++++++++++++++++++++++
 app/test-pmd/config.c             |   40 +-
 app/test-pmd/testpmd.h            |    3 +
 lib/librte_ether/Makefile         |    1 +
 lib/librte_ether/rte_eth_ctrl.h   |  343 +++++++++++
 lib/librte_ether/rte_ethdev.c     |   32 +
 lib/librte_ether/rte_ethdev.h     |   67 ++-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  148 ++++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   34 +-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1202 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  175 ++++++
 12 files changed, 2815 insertions(+), 45 deletions(-)
 create mode 100644 lib/librte_ether/rte_eth_ctrl.h
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 01/20] i40e: set up and initialize flow director
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 02/20] i40e: tear down " Jingjing Wu
                   ` (20 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

set up fortville resources to support flow director, includes
 - queue 0 pair allocated and set up for flow director
 - create vsi
 - reserve memzone for flow director programming packet

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/Makefile      |   2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  77 +++++++++++--
 lib/librte_pmd_i40e/i40e_ethdev.h |  30 +++++-
 lib/librte_pmd_i40e/i40e_fdir.c   | 220 ++++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   | 127 ++++++++++++++++++++++
 5 files changed, 444 insertions(+), 12 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

diff --git a/lib/librte_pmd_i40e/Makefile b/lib/librte_pmd_i40e/Makefile
index 4b31675..fdb9e26 100644
--- a/lib/librte_pmd_i40e/Makefile
+++ b/lib/librte_pmd_i40e/Makefile
@@ -87,6 +87,8 @@ SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_rxtx.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev_vf.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_pf.c
+SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_fdir.c
+
 # this lib depends upon:
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_eal lib/librte_ether
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_mempool lib/librte_mbuf
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index a00d6ca..d0413cb 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -779,6 +779,12 @@ i40e_dev_start(struct rte_eth_dev *dev)
 	i40e_vsi_queues_bind_intr(vsi);
 	i40e_vsi_enable_queues_intr(vsi);
 
+	/* enable FDIR MSIX interrupt */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
+		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
+	}
+
 	/* Enable all queues which have been configured */
 	ret = i40e_vsi_switch_queues(vsi, TRUE);
 	if (ret != I40E_SUCCESS) {
@@ -2587,16 +2593,30 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	case I40E_VSI_SRIOV :
 		vsi->nb_qps = pf->vf_nb_qps;
 		break;
+	case I40E_VSI_FDIR:
+		vsi->nb_qps = pf->fdir_nb_qps;
+		break;
 	default:
 		goto fail_mem;
 	}
-	ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
-	if (ret < 0) {
-		PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
-				vsi->seid, ret);
-		goto fail_mem;
-	}
-	vsi->base_queue = ret;
+	/*
+	 * The filter status descriptor is reported in rx queue 0,
+	 * while the tx queue for fdir filter programming has no
+	 * such constraints, can be non-zero queues.
+	 * To simplify it, choose FDIR vsi use queue 0 pair.
+	 * To make sure it will use queue 0 pair, queue allocation
+	 * need be done before this function is called
+	 */
+	if (type != I40E_VSI_FDIR) {
+		ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
+			if (ret < 0) {
+				PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
+						vsi->seid, ret);
+				goto fail_mem;
+			}
+			vsi->base_queue = ret;
+	} else
+		vsi->base_queue = I40E_FDIR_QUEUE_ID;
 
 	/* VF has MSIX interrupt in VF range, don't allocate here */
 	if (type != I40E_VSI_SRIOV) {
@@ -2728,8 +2748,24 @@ i40e_vsi_setup(struct i40e_pf *pf,
 		 * Since VSI is not created yet, only configure parameter,
 		 * will add vsi below.
 		 */
-	}
-	else {
+	} else if (type == I40E_VSI_FDIR) {
+		vsi->uplink_seid = uplink_vsi->uplink_seid;
+		ctxt.pf_num = hw->pf_id;
+		ctxt.vf_num = 0;
+		ctxt.uplink_seid = vsi->uplink_seid;
+		ctxt.connection_type = 0x1;     /* regular data port */
+		ctxt.flags = I40E_AQ_VSI_TYPE_PF;
+		ret = i40e_vsi_config_tc_queue_mapping(vsi, &ctxt.info,
+						I40E_DEFAULT_TCMAP);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to configure "
+					"TC queue mapping\n");
+			goto fail_msix_alloc;
+		}
+		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
+		ctxt.info.valid_sections |=
+			rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
+	} else {
 		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet");
 		goto fail_msix_alloc;
 	}
@@ -2915,8 +2951,16 @@ i40e_pf_setup(struct i40e_pf *pf)
 		PMD_DRV_LOG(ERR, "Could not get switch config, err %d", ret);
 		return ret;
 	}
-
-	/* VSI setup */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		/* make queue allocated first, let FDIR use queue pair 0*/
+		ret = i40e_res_pool_alloc(&pf->qp_pool, I40E_DEFAULT_QP_NUM_FDIR);
+		if (ret != I40E_FDIR_QUEUE_ID) {
+			PMD_DRV_LOG(ERR, "queue allocation fails for FDIR :"
+				    " ret =%d", ret);
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+	/*  main VSI setup */
 	vsi = i40e_vsi_setup(pf, I40E_VSI_MAIN, NULL, 0);
 	if (!vsi) {
 		PMD_DRV_LOG(ERR, "Setup of main vsi failed");
@@ -2926,9 +2970,20 @@ i40e_pf_setup(struct i40e_pf *pf)
 	dev_data->nb_rx_queues = vsi->nb_qps;
 	dev_data->nb_tx_queues = vsi->nb_qps;
 
+	/* setup FDIR after main vsi created.*/
+	if (pf->flags & I40E_FLAG_FDIR) {
+		ret = i40e_fdir_setup(pf);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to setup flow director\n");
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+
 	/* Configure filter control */
 	memset(&settings, 0, sizeof(settings));
 	settings.hash_lut_size = I40E_HASH_LUT_SIZE_128;
+	if (pf->flags & I40E_FLAG_FDIR)
+		settings.enable_fdir = TRUE;
 	/* Enable ethtype and macvlan filters */
 	settings.enable_ethtype = TRUE;
 	settings.enable_macvlan = TRUE;
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 64deef2..a2b1578 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -46,11 +46,12 @@
 /* number of VSIs and queue default setting */
 #define I40E_MAX_QP_NUM_PER_VF    16
 #define I40E_DEFAULT_QP_NUM_VMDQ  64
-#define I40E_DEFAULT_QP_NUM_FDIR  64
+#define I40E_DEFAULT_QP_NUM_FDIR  1
 #define I40E_UINT32_BIT_SIZE      (CHAR_BIT * sizeof(uint32_t))
 #define I40E_VFTA_SIZE            (4096 / I40E_UINT32_BIT_SIZE)
 /* Default TC traffic in case DCB is not enabled */
 #define I40E_DEFAULT_TCMAP        0x1
+#define I40E_FDIR_QUEUE_ID        0
 
 /* i40e flags */
 #define I40E_FLAG_RSS                   (1ULL << 0)
@@ -189,6 +190,27 @@ struct i40e_pf_vf {
 };
 
 /*
+ *  A structure used to define fields of a FDIR related info.
+ */
+struct i40e_fdir_info {
+	struct i40e_vsi *fdir_vsi;     /* pointer to fdir VSI structure */
+	uint16_t match_counter_index;  /* Statistic counter index used for fdir*/
+	struct i40e_tx_queue *txq;
+	struct i40e_rx_queue *rxq;
+	void *prg_pkt;                 /* memory for fdir program packet */
+	uint64_t dma_addr;             /* physic address of packet memory*/
+	/*
+	 * the rule how bytes stream is extracted as flexible payload
+	 * for each payload layer, the setting can up to three elements
+	 */
+	struct {
+		uint8_t offset;        /* offset in words from the beginning of payload */
+		uint8_t size;          /* size in words */
+	} flex_set[3][3];
+
+};
+
+/*
  * Structure to store private data specific for PF instance.
  */
 struct i40e_pf {
@@ -216,6 +238,7 @@ struct i40e_pf {
 	uint16_t vmdq_nb_qps; /* The number of queue pairs of VMDq */
 	uint16_t vf_nb_qps; /* The number of queue pairs of VF */
 	uint16_t fdir_nb_qps; /* The number of queue pairs of Flow Director */
+	struct i40e_fdir_info fdir; /* flow director info */
 };
 
 enum pending_msg {
@@ -312,6 +335,11 @@ void i40e_vsi_queues_unbind_intr(struct i40e_vsi *vsi);
 int i40e_vsi_vlan_pvid_set(struct i40e_vsi *vsi,
 				struct i40e_vsi_vlan_pvid_info *info);
 int i40e_vsi_config_vlan_stripping(struct i40e_vsi *vsi, bool on);
+enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+int i40e_fdir_setup(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
new file mode 100644
index 0000000..5872494
--- /dev/null
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -0,0 +1,220 @@
+/*-
+ *   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 <sys/queue.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdint.h>
+#include <string.h>
+#include <unistd.h>
+#include <stdarg.h>
+
+#include <rte_ether.h>
+#include <rte_ethdev.h>
+#include <rte_log.h>
+#include <rte_memzone.h>
+#include <rte_malloc.h>
+
+#include "i40e_logs.h"
+#include "i40e/i40e_type.h"
+#include "i40e_ethdev.h"
+#include "i40e_rxtx.h"
+
+#define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#define I40E_FDIR_PKT_LEN                   512
+#define I40E_COUNTER_PF           2
+/* Statistic counter index for one pf */
+#define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+
+static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+
+static int
+i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
+{
+	struct i40e_hw *hw = I40E_VSI_TO_HW(rxq->vsi);
+	struct i40e_hmc_obj_rxq rx_ctx;
+	int err = I40E_SUCCESS;
+
+	memset(&rx_ctx, 0, sizeof(struct i40e_hmc_obj_rxq));
+	/* Init the RX queue in hardware */
+	rx_ctx.dbuff = I40E_RXBUF_SZ_1024 >> I40E_RXQ_CTX_DBUFF_SHIFT;
+	rx_ctx.hbuff = 0;
+	rx_ctx.base = rxq->rx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
+	rx_ctx.qlen = rxq->nb_rx_desc;
+#ifndef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+	rx_ctx.dsize = 1;
+#endif
+	rx_ctx.dtype = i40e_header_split_none;
+	rx_ctx.hsplit_0 = I40E_HEADER_SPLIT_NONE;
+	rx_ctx.rxmax = ETHER_MAX_LEN;
+	rx_ctx.tphrdesc_ena = 1;
+	rx_ctx.tphwdesc_ena = 1;
+	rx_ctx.tphdata_ena = 1;
+	rx_ctx.tphhead_ena = 1;
+	rx_ctx.lrxqthresh = 2;
+	rx_ctx.crcstrip = 0;
+	rx_ctx.l2tsel = 1;
+	rx_ctx.showiv = 1;
+	rx_ctx.prefena = 1;
+
+	err = i40e_clear_lan_rx_queue_context(hw, rxq->reg_idx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to clear FDIR RX queue context.");
+		return err;
+	}
+	err = i40e_set_lan_rx_queue_context(hw, rxq->reg_idx, &rx_ctx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to set FDIR RX queue context.");
+		return err;
+	}
+	rxq->qrx_tail = hw->hw_addr +
+		I40E_QRX_TAIL(rxq->vsi->base_queue);
+
+	rte_wmb();
+	/* Init the RX tail regieter. */
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, 0);
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, rxq->nb_rx_desc - 1);
+
+	return err;
+}
+
+/*
+ * i40e_fdir_setup - reserve and initialize the Flow Director resources
+ * @pf: board private structure
+ */
+int
+i40e_fdir_setup(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_vsi *vsi;
+	int err = I40E_SUCCESS;
+	char z_name[RTE_MEMZONE_NAMESIZE];
+	const struct rte_memzone *mz = NULL;
+	struct rte_eth_dev *eth_dev = pf->adapter->eth_dev;
+
+	PMD_DRV_LOG(INFO, "FDIR HW Capabilities: num_filters_guaranteed = %u,"
+			" num_filters_best_effort = %u.\n",
+			hw->func_caps.fd_filters_guaranteed,
+			hw->func_caps.fd_filters_best_effort);
+
+	vsi = pf->fdir.fdir_vsi;
+	if (vsi) {
+		PMD_DRV_LOG(ERR, "FDIR vsi pointer needs"
+				 "to be null before creation.");
+		return I40E_ERR_BAD_PTR;
+	}
+	/* make new FDIR VSI */
+	vsi = i40e_vsi_setup(pf, I40E_VSI_FDIR, pf->main_vsi, 0);
+	if (!vsi) {
+		PMD_DRV_LOG(ERR, "Couldn't create FDIR VSI.");
+		return I40E_ERR_NO_AVAILABLE_VSI;
+	}
+	pf->fdir.fdir_vsi = vsi;
+
+	/*Fdir tx queue setup*/
+	err = i40e_fdir_setup_tx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR TX resources.");
+		goto fail_setup_tx;
+	}
+
+	/*Fdir rx queue setup*/
+	err = i40e_fdir_setup_rx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR RX resources.");
+		goto fail_setup_rx;
+	}
+
+	err = i40e_tx_queue_init(pf->fdir.txq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR TX initialization.");
+		goto fail_mem;
+	}
+
+	/* need switch on before dev start*/
+	err = i40e_switch_tx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do fdir TX switch on.");
+		goto fail_mem;
+	}
+
+	/* Init the rx queue in hardware */
+	err = i40e_fdir_rx_queue_init(pf->fdir.rxq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX initialization.");
+		goto fail_mem;
+	}
+
+	/* switch on rx queue */
+	err = i40e_switch_rx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX switch on.");
+		goto fail_mem;
+	}
+
+	/* reserve memory for the fdir programming packet */
+	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
+			eth_dev->driver->pci_drv.name,
+			I40E_FDIR_MZ_NAME,
+			eth_dev->data->port_id);
+	mz = rte_memzone_lookup(z_name);
+	if (!mz) {
+		mz = rte_memzone_reserve(z_name,
+				I40E_FDIR_PKT_LEN,
+				rte_socket_id(),
+				0);
+		if (!mz) {
+			PMD_DRV_LOG(ERR, "Cannot init memzone for"
+				"flow director program packet.");
+			err = I40E_ERR_NO_MEMORY;
+			goto fail_mem;
+		}
+	}
+	pf->fdir.prg_pkt = mz->addr;
+	pf->fdir.dma_addr = (uint64_t)mz->phys_addr;
+	pf->fdir.match_counter_index = I40E_COUNTER_INDEX_FDIR(hw->pf_id);
+	PMD_DRV_LOG(INFO, "FDIR setup successfully, with programming queue %u.\n",
+		    vsi->base_queue);
+	return I40E_SUCCESS;
+
+fail_mem:
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+fail_setup_rx:
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+fail_setup_tx:
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return err;
+}
diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 099699c..4435367 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -2107,6 +2107,8 @@ i40e_tx_queue_init(struct i40e_tx_queue *txq)
 	tx_ctx.base = txq->tx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
 	tx_ctx.qlen = txq->nb_tx_desc;
 	tx_ctx.rdylist = rte_le_to_cpu_16(vsi->info.qs_handle[0]);
+	if (vsi->type == I40E_VSI_FDIR)
+		tx_ctx.fd_ena = TRUE;
 
 	err = i40e_clear_lan_tx_queue_context(hw, pf_q);
 	if (err != I40E_SUCCESS) {
@@ -2323,3 +2325,128 @@ i40e_dev_clear_queues(struct rte_eth_dev *dev)
 		i40e_reset_rx_queue(dev->data->rx_queues[i]);
 	}
 }
+
+enum i40e_status_code
+i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_tx_queue *txq;
+	const struct rte_memzone *tz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_TX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	txq = rte_zmalloc_socket("i40e fdir tx queue",
+				  sizeof(struct i40e_tx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!txq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"tx queue structure\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(struct i40e_tx_desc) * I40E_FDIR_NUM_TX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	tz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_tx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!tz) {
+		i40e_dev_tx_queue_release(txq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for TX\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	txq->nb_tx_desc = I40E_FDIR_NUM_TX_DESC;
+	txq->queue_id = I40E_FDIR_QUEUE_ID;
+	txq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	txq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	txq->tx_ring_phys_addr = rte_mem_phy2mch(tz->memseg_id, tz->phys_addr);
+#else
+	txq->tx_ring_phys_addr = (uint64_t)tz->phys_addr;
+#endif
+	txq->tx_ring = (struct i40e_tx_desc *)tz->addr;
+	/*
+	 * don't need to allocate software ring and reset for the fdir
+	 * program queue just set the queue has been configured.
+	 */
+	txq->q_set = TRUE;
+	pf->fdir.txq = txq;
+
+	return I40E_SUCCESS;
+}
+
+enum i40e_status_code
+i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_rx_queue *rxq;
+	const struct rte_memzone *rz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_RX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	rxq = rte_zmalloc_socket("i40e fdir rx queue",
+				  sizeof(struct i40e_rx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!rxq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"rx queue structure\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(union i40e_rx_desc) * I40E_FDIR_NUM_RX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	rz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_rx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!rz) {
+		i40e_dev_rx_queue_release(rxq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for RX\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	rxq->nb_rx_desc = I40E_FDIR_NUM_RX_DESC;
+	rxq->queue_id = I40E_FDIR_QUEUE_ID;
+	rxq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	rxq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	rxq->rx_ring_phys_addr = rte_mem_phy2mch(rz->memseg_id, rz->phys_addr);
+#else
+	rxq->rx_ring_phys_addr = (uint64_t)rz->phys_addr;
+#endif
+	rxq->rx_ring = (union i40e_rx_desc *)rz->addr;
+
+	/*
+	 * Don't need to allocate software ring and reset for the fdir
+	 * rx queue, just set the queue has been configured.
+	 */
+	rxq->q_set = TRUE;
+	pf->fdir.rxq = rxq;
+
+	return I40E_SUCCESS;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 02/20] i40e: tear down flow director
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 01/20] i40e: set up and initialize flow director Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 03/20] i40e: initialize flexible payload setting Jingjing Wu
                   ` (19 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

release fortville resources on flow director, includes
 - queue 0 pair release
 - release vsi

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  4 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |  1 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 19 +++++++++++++++++++
 3 files changed, 23 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index d0413cb..da131a8 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -522,7 +522,8 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 	return 0;
 
 err_setup_pf_switch:
-	rte_free(pf->main_vsi);
+	i40e_fdir_teardown(pf);
+	i40e_vsi_release(pf->main_vsi);
 err_get_mac_addr:
 err_configure_lan_hmc:
 	(void)i40e_shutdown_lan_hmc(hw);
@@ -850,6 +851,7 @@ i40e_dev_close(struct rte_eth_dev *dev)
 	i40e_shutdown_lan_hmc(hw);
 
 	/* release all the existing VSIs and VEBs */
+	i40e_fdir_teardown(pf);
 	i40e_vsi_release(pf->main_vsi);
 
 	/* shutdown the adminq */
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index a2b1578..2460635 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -340,6 +340,7 @@ enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
 enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
+void i40e_fdir_teardown(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 5872494..3d8faa0 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -218,3 +218,22 @@ fail_setup_tx:
 	pf->fdir.fdir_vsi = NULL;
 	return err;
 }
+
+/*
+ * i40e_fdir_teardown - release the Flow Director resources
+ * @pf: board private structure
+ */
+void
+i40e_fdir_teardown(struct i40e_pf *pf)
+{
+	struct i40e_vsi *vsi;
+
+	vsi = pf->fdir.fdir_vsi;
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return;
+}
\ No newline at end of file
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 03/20] i40e: initialize flexible payload setting
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 01/20] i40e: set up and initialize flow director Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 02/20] i40e: tear down " Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 04/20] lib/librte_ether: new filter APIs definition Jingjing Wu
                   ` (18 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

set flexible payload related registers to default value at initialization time.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 33 ++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_fdir.c   | 49 +++++++++++++++++++++++++++++++++++++++
 2 files changed, 82 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index da131a8..a3f25e6 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -336,6 +336,32 @@ static struct rte_driver rte_i40e_driver = {
 
 PMD_REGISTER_DRIVER(rte_i40e_driver);
 
+/*
+ * Initialize registers for flexible payload, which should be set by NVM.
+ * This should be removed from code once is fixed in NVM.
+ */
+static inline void i40e_flex_payload_reg_init(struct i40e_hw *hw)
+{
+	/* GLQF_ORT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(18), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(19), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(26), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(30), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(33), 0x000000E0);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(34), 0x000000E3);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(35), 0x000000E6);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(20), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(23), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(63), 0x0000002D);
+
+	/* GLQF_PIT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(16), 0x00007480);
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(17), 0x00007440);
+
+	/* GL_PRS_FVBM Registers */
+	I40E_WRITE_REG(hw, I40E_GL_PRS_FVBM(1), 0x8000035B);
+}
+
 static int
 eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
                   struct rte_eth_dev *dev)
@@ -399,6 +425,13 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 		return ret;
 	}
 
+	/*
+	 * To work around the NVM issue,initialize registers
+	 * for flexible payload by software.
+	 * It should be removed once issues are fixed in NVM.
+	 */
+	i40e_flex_payload_reg_init(hw);
+
 	/* Initialize the parameters for adminq */
 	i40e_init_adminq_parameter(hw);
 	ret = i40e_init_adminq(hw);
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 3d8faa0..a3e6bd7 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -109,6 +109,53 @@ i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
 }
 
 /*
+ * Initialize the configuration about bytes stream extracted as flexible payload
+ * and mask setting
+ */
+static inline void
+i40e_init_flx_pld(struct i40e_pf *pf)
+{
+	uint8_t pctype;;
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+
+	/*
+	 * Define the bytes stream extracted as flexible payload in
+	 * field vector. By default, select 8 words from the beginning
+	 * of payload as flexible payload.
+	 */
+	memset(pf->fdir.flex_set, 0, sizeof(pf->fdir.flex_set));
+
+	/* initialize the flexible payload for L2 payload*/
+	pf->fdir.flex_set[0][0].offset = 0;
+	pf->fdir.flex_set[0][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(0), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(1), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(2), 0x0000FC2A);/*non-used*/
+
+	/* initialize the flexible payload for L3 payload*/
+	pf->fdir.flex_set[1][0].offset = 0;
+	pf->fdir.flex_set[1][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(3), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(4), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(5), 0x0000FC2A);/*non-used*/
+
+	/* initialize the flexible payload for L4 payload*/
+	pf->fdir.flex_set[2][0].offset = 0;
+	pf->fdir.flex_set[2][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(6), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(7), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(8), 0x0000FC2A);/*non-used*/
+
+	/* initialize the masks */
+	for (pctype = I40E_FILTER_PCTYPE_NONF_IPV4_UDP;
+	     pctype <= I40E_FILTER_PCTYPE_FRAG_IPV6; pctype++) {
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), 0);
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, 0), 0);
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, 1), 0);
+	}
+}
+
+/*
  * i40e_fdir_setup - reserve and initialize the Flow Director resources
  * @pf: board private structure
  */
@@ -182,6 +229,8 @@ i40e_fdir_setup(struct i40e_pf *pf)
 		goto fail_mem;
 	}
 
+	i40e_init_flx_pld(pf);
+
 	/* reserve memory for the fdir programming packet */
 	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
 			eth_dev->driver->pci_drv.name,
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 04/20] lib/librte_ether: new filter APIs definition
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (2 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 03/20] i40e: initialize flexible payload setting Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 05/20] lib/librte_ether: define structures for adding/deleting flow director Jingjing Wu
                   ` (17 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

Define new APIs to support configure multi-kind filters using same APIs
 - rte_eth_dev_filter_supported
 - rte_eth_dev_filter_ctrl

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_ether/Makefile       |  1 +
 lib/librte_ether/rte_eth_ctrl.h | 78 +++++++++++++++++++++++++++++++++++++++++
 lib/librte_ether/rte_ethdev.c   | 32 +++++++++++++++++
 lib/librte_ether/rte_ethdev.h   | 44 +++++++++++++++++++++++
 4 files changed, 155 insertions(+)
 create mode 100644 lib/librte_ether/rte_eth_ctrl.h

diff --git a/lib/librte_ether/Makefile b/lib/librte_ether/Makefile
index b310f8b..a461c31 100644
--- a/lib/librte_ether/Makefile
+++ b/lib/librte_ether/Makefile
@@ -46,6 +46,7 @@ SRCS-y += rte_ethdev.c
 #
 SYMLINK-y-include += rte_ether.h
 SYMLINK-y-include += rte_ethdev.h
+SYMLINK-y-include += rte_eth_ctrl.h
 
 # this lib depends upon:
 DEPDIRS-y += lib/librte_eal lib/librte_mempool lib/librte_ring lib/librte_mbuf
diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
new file mode 100644
index 0000000..34ab278
--- /dev/null
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -0,0 +1,78 @@
+/*-
+ *   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.
+ */
+
+#ifndef _RTE_ETH_CTRL_H_
+#define _RTE_ETH_CTRL_H_
+
+/**
+ * @file
+ *
+ * Ethernet device features and related data structures used
+ * by control APIs should be defined in this file.
+ *
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Feature filter types
+ */
+enum rte_filter_type {
+	RTE_ETH_FILTER_NONE = 0,
+	RTE_ETH_FILTER_RSS,
+	RTE_ETH_FILTER_FDIR,
+	RTE_ETH_FILTER_MAX,
+};
+
+/**
+ * All generic operations to filters
+ */
+enum rte_filter_op {
+	RTE_ETH_FILTER_OP_NONE = 0, /**< used to check whether the type filter is supported */
+	RTE_ETH_FILTER_OP_ADD,      /**< add filter entry */
+	RTE_ETH_FILTER_OP_UPDATE,   /**< update filter entry */
+	RTE_ETH_FILTER_OP_DELETE,   /**< delete filter entry */
+	RTE_ETH_FILTER_OP_FLUSH,    /**< flush all entries */
+	RTE_ETH_FILTER_OP_GET,      /**< get filter entry */
+	RTE_ETH_FILTER_OP_SET,      /**< configurations */
+	RTE_ETH_FILTER_OP_GET_INFO, /**< get information of filter, such as status or statistics */
+	RTE_ETH_FILTER_OP_MAX,
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _RTE_ETH_CTRL_H_ */
diff --git a/lib/librte_ether/rte_ethdev.c b/lib/librte_ether/rte_ethdev.c
index b71b679..fdafb15 100644
--- a/lib/librte_ether/rte_ethdev.c
+++ b/lib/librte_ether/rte_ethdev.c
@@ -3139,3 +3139,35 @@ rte_eth_dev_get_flex_filter(uint8_t port_id, uint16_t index,
 	return (*dev->dev_ops->get_flex_filter)(dev, index, filter,
 						rx_queue);
 }
+
+int
+rte_eth_dev_filter_supported(uint8_t port_id, enum rte_filter_type filter_type)
+{
+	struct rte_eth_dev *dev;
+
+	if (port_id >= nb_ports) {
+		PMD_DEBUG_TRACE("Invalid port_id=%d\n", port_id);
+		return -ENODEV;
+	}
+
+	dev = &rte_eth_devices[port_id];
+	FUNC_PTR_OR_ERR_RET(*dev->dev_ops->filter_ctrl, -ENOTSUP);
+	return (*dev->dev_ops->filter_ctrl)(dev, filter_type,
+				RTE_ETH_FILTER_OP_NONE, NULL);
+}
+
+int
+rte_eth_dev_filter_ctrl(uint8_t port_id, enum rte_filter_type filter_type,
+		       enum rte_filter_op filter_op, void *arg)
+{
+	struct rte_eth_dev *dev;
+
+	if (port_id >= nb_ports) {
+		PMD_DEBUG_TRACE("Invalid port_id=%d\n", port_id);
+		return -ENODEV;
+	}
+
+	dev = &rte_eth_devices[port_id];
+	FUNC_PTR_OR_ERR_RET(*dev->dev_ops->filter_ctrl, -ENOTSUP);
+	return (*dev->dev_ops->filter_ctrl)(dev, filter_type, filter_op, arg);
+}
diff --git a/lib/librte_ether/rte_ethdev.h b/lib/librte_ether/rte_ethdev.h
index 60b24c5..e2ea84a 100644
--- a/lib/librte_ether/rte_ethdev.h
+++ b/lib/librte_ether/rte_ethdev.h
@@ -177,6 +177,7 @@ extern "C" {
 #include <rte_pci.h>
 #include <rte_mbuf.h>
 #include "rte_ether.h"
+#include "rte_eth_ctrl.h"
 
 /**
  * A structure used to retrieve statistics for an Ethernet port.
@@ -1383,6 +1384,12 @@ typedef int (*eth_get_flex_filter_t)(struct rte_eth_dev *dev,
 			uint16_t *rx_queue);
 /**< @internal Get a flex filter rule on an Ethernet device */
 
+typedef int (*eth_filter_ctrl_t)(struct rte_eth_dev *dev,
+				 enum rte_filter_type filter_type,
+				 enum rte_filter_op filter_op,
+				 void *arg);
+/**< @internal Take operations to assigned filter type on an Ethernet device */
+
 /**
  * @internal A structure containing the functions exported by an Ethernet driver.
  */
@@ -1491,6 +1498,7 @@ struct eth_dev_ops {
 	eth_add_flex_filter_t          add_flex_filter;      /**< add flex filter. */
 	eth_remove_flex_filter_t       remove_flex_filter;   /**< remove flex filter. */
 	eth_get_flex_filter_t          get_flex_filter;      /**< get flex filter. */
+	eth_filter_ctrl_t              filter_ctrl;          /**< common filter control*/
 };
 
 /**
@@ -3613,6 +3621,42 @@ int rte_eth_dev_remove_flex_filter(uint8_t port_id, uint16_t index);
 int rte_eth_dev_get_flex_filter(uint8_t port_id, uint16_t index,
 			struct rte_flex_filter *filter, uint16_t *rx_queue);
 
+/**
+ * Check whether the filter type is supported on an Ethernet device.
+ * All the supported filter types are defined in 'rte_eth_ctrl.h'.
+ *
+ * @param port_id
+ *   The port identifier of the Ethernet device.
+ * @param filter_type
+ *   filter type.
+ * @return
+ *   - (0) if successful.
+ *   - (-ENOTSUP) if hardware doesn't support this filter type.
+ *   - (-ENODEV) if *port_id* invalid.
+ */
+int rte_eth_dev_filter_supported(uint8_t port_id, enum rte_filter_type filter_type);
+
+/**
+ * Take operations to assigned filter type on an Ethernet device.
+ * All the supported operations and filter types are defined in 'rte_eth_ctrl.h'.
+ *
+ * @param port_id
+ *   The port identifier of the Ethernet device.
+ * @param filter_type
+ *   filter type.
+  * @param filter_op
+ *   The operation taken to assigned filter.
+ * @param arg
+ *   A pointer to arguments defined specifically for the operation.
+ * @return
+ *   - (0) if successful.
+ *   - (-ENOTSUP) if hardware doesn't support.
+ *   - (-ENODEV) if *port_id* invalid.
+ *   - others depends on the specific operations implementation.
+ */
+int rte_eth_dev_filter_ctrl(uint8_t port_id, enum rte_filter_type filter_type,
+			enum rte_filter_op filter_op, void *arg);
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 05/20] lib/librte_ether: define structures for adding/deleting flow director
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (3 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 04/20] lib/librte_ether: new filter APIs definition Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 06/20] i40e: implement operations to add/delete " Jingjing Wu
                   ` (16 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

define structures to add or delete flow director filter

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 159 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 159 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 34ab278..df1ce4b 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -71,6 +71,165 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_OP_MAX,
 };
 
+/**
+ * Define all structures for Flow Director Filter type corresponding with specific operations.
+ */
+
+/**
+ * flow type
+ */
+enum rte_eth_flow_type {
+	RTE_ETH_FLOW_TYPE_NONE = 0x0,
+	RTE_ETH_FLOW_TYPE_UDPV4,
+	RTE_ETH_FLOW_TYPE_TCPV4,
+	RTE_ETH_FLOW_TYPE_SCTPV4,
+	RTE_ETH_FLOW_TYPE_IPV4_OTHER,
+	RTE_ETH_FLOW_TYPE_UDPV6,
+	RTE_ETH_FLOW_TYPE_TCPV6,
+	RTE_ETH_FLOW_TYPE_SCTPV6,
+	RTE_ETH_FLOW_TYPE_IPV6_OTHER,
+};
+
+/**
+ * A structure used to define the input for IPV4 UDP flow
+ */
+struct rte_eth_udpv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+	uint16_t src_port;    /**< UDP Source port to match. */
+	uint16_t dst_port;    /**< UDP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 TCP flow
+ */
+struct rte_eth_tcpv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+	uint16_t src_port;    /**< TCP Source port to match. */
+	uint16_t dst_port;    /**< TCP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 SCTP flow
+ */
+struct rte_eth_sctpv4_flow {
+	uint32_t src_ip;          /**< IPv4 source address to match. */
+	uint32_t dst_ip;          /**< IPv4 destination address to match. */
+	uint32_t verify_tag;      /**< verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV4 flow
+ */
+struct rte_eth_ipv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 UDP flow
+ */
+struct rte_eth_udpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint16_t src_port;       /**< UDP Source port to match. */
+	uint16_t dst_port;       /**< UDP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 TCP flow
+ */
+struct rte_eth_tcpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint16_t src_port;       /**< TCP Source port to match. */
+	uint16_t dst_port;       /**< TCP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 SCTP flow
+ */
+struct rte_eth_sctpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint32_t verify_tag;     /**< verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV6 flow
+ */
+struct rte_eth_ipv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+};
+
+/**
+ * A union constains the inputs for all types of flow
+ */
+union rte_eth_fdir_flow {
+	struct rte_eth_udpv4_flow  udp4_flow;
+	struct rte_eth_tcpv4_flow  tcp4_flow;
+	struct rte_eth_sctpv4_flow sctp4_flow;
+	struct rte_eth_ipv4_flow   ip4_flow;
+	struct rte_eth_udpv6_flow  udp6_flow;
+	struct rte_eth_tcpv6_flow  tcp6_flow;
+	struct rte_eth_sctpv6_flow sctp6_flow;
+	struct rte_eth_ipv6_flow   ip6_flow;
+};
+
+#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
+/**
+ * A structure used to contain extend input of flow
+ */
+struct rte_eth_fdir_flow_ext {
+	uint16_t vlan_tci;
+	uint8_t num_flexwords;         /**< number of flexwords */
+	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
+	uint16_t dest_id;              /**< destination vsi or pool id*/
+};
+
+/**
+ * A structure used to define the input for an flow director filter entry
+ */
+struct rte_eth_fdir_input {
+	enum rte_eth_flow_type flow_type;      /**< type of flow */
+	union rte_eth_fdir_flow flow;          /**< specific flow structure */
+	struct rte_eth_fdir_flow_ext flow_ext; /**< specific flow info */
+};
+
+/**
+ * Flow director report status
+ */
+enum rte_eth_fdir_status {
+	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< no report FDIR. */
+	RTE_ETH_FDIR_REPORT_FD_ID,         /**< only report FD ID. */
+	RTE_ETH_FDIR_REPORT_FD_ID_FLEX_4,  /**< report FD ID and 4 flex bytes. */
+	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< report 8 flex bytes. */
+};
+
+/**
+ * A structure used to define an action when match FDIR packet filter.
+ */
+struct rte_eth_fdir_action {
+	uint16_t rx_queue;        /**< queue assigned to if fdir match. */
+	uint16_t cnt_idx;         /**< statistic count index */
+	uint8_t  drop;            /**< accept or reject */
+	uint8_t  flex_off;        /**< offset used define words to report */
+	enum rte_eth_fdir_status report_status;  /**< status report option */
+};
+
+/**
+ * A structure used to define the flow director filter entry by filter_ctl API
+ * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_OP_ADD and
+ * RTE_ETH_FILTER_OP_DELETE operations.
+ */
+struct rte_eth_fdir_filter {
+	uint16_t soft_id;                   /**< id */
+	struct rte_eth_fdir_input input;    /**< input set */
+	struct rte_eth_fdir_action action;  /**< action taken when match */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 06/20] i40e: implement operations to add/delete flow director
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (4 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 05/20] lib/librte_ether: define structures for adding/deleting flow director Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 07/20] app/test-pmd: add test commands to add/delete flow director filter Jingjing Wu
                   ` (15 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

deal with two operations for flow director
 - RTE_ETH_FILTER_OP_ADD
 - RTE_ETH_FILTER_OP_DELETE
encode the flow inputs to programming packet
sent the packet to filter programming queue and check status on the status report queue

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  29 ++
 lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 617 +++++++++++++++++++++++++++++++++++++-
 3 files changed, 648 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index a3f25e6..9791519 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -205,6 +205,9 @@ static int i40e_dev_rss_hash_update(struct rte_eth_dev *dev,
 				    struct rte_eth_rss_conf *rss_conf);
 static int i40e_dev_rss_hash_conf_get(struct rte_eth_dev *dev,
 				      struct rte_eth_rss_conf *rss_conf);
+static int i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
+				enum rte_filter_type filter_type,
+				enum rte_filter_op filter_op, void *arg);
 
 /* Default hash key buffer for RSS */
 static uint32_t rss_key_default[I40E_PFQF_HKEY_MAX_INDEX + 1];
@@ -256,6 +259,7 @@ static struct eth_dev_ops i40e_eth_dev_ops = {
 	.reta_query                   = i40e_dev_rss_reta_query,
 	.rss_hash_update              = i40e_dev_rss_hash_update,
 	.rss_hash_conf_get            = i40e_dev_rss_hash_conf_get,
+	.filter_ctrl                  = i40e_dev_filter_ctrl,
 };
 
 static struct eth_driver rte_i40e_pmd = {
@@ -4221,3 +4225,28 @@ i40e_pf_config_mq_rx(struct i40e_pf *pf)
 
 	return 0;
 }
+
+/*
+ * Take operations to assigned filter type on NIC.
+ */
+static int
+i40e_dev_filter_ctrl(struct rte_eth_dev *dev, enum rte_filter_type filter_type,
+		     enum rte_filter_op filter_op, void *arg)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	int ret = I40E_SUCCESS;
+
+	if (dev == NULL)
+		return -EINVAL;
+
+	switch (filter_type) {
+	case RTE_ETH_FILTER_FDIR:
+		ret = i40e_fdir_ctrl_func(pf, filter_op, arg);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unsupported filter type %u.", filter_type);
+		ret = -EINVAL;
+		break;
+	}
+	return ret;
+}
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 2460635..af149df 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -341,6 +341,9 @@ enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
 void i40e_fdir_teardown(struct i40e_pf *pf);
+int i40e_fdir_ctrl_func(struct i40e_pf *pf,
+			  enum rte_filter_op filter_op,
+			  void *arg);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index a3e6bd7..82645df 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -44,6 +44,10 @@
 #include <rte_log.h>
 #include <rte_memzone.h>
 #include <rte_malloc.h>
+#include <rte_ip.h>
+#include <rte_udp.h>
+#include <rte_tcp.h>
+#include <rte_sctp.h>
 
 #include "i40e_logs.h"
 #include "i40e/i40e_type.h"
@@ -51,12 +55,43 @@
 #include "i40e_rxtx.h"
 
 #define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#ifndef IPV6_ADDR_LEN
+#define IPV6_ADDR_LEN              16
+#endif
+
 #define I40E_FDIR_PKT_LEN                   512
+#define I40E_FDIR_IP_DEFAULT_LEN            420
+#define I40E_FDIR_IP_DEFAULT_TTL            0x40
+#define I40E_FDIR_IP_DEFAULT_VERSION_IHL    0x45
+#define I40E_FDIR_TCP_DEFAULT_DATAOFF       0x50
+#define I40E_FDIR_IPv6_DEFAULT_VTC_FLOW     0x60300000
+#define I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS   0xFF
+#define I40E_FDIR_IPv6_PAYLOAD_LEN          380
+#define I40E_FDIR_UDP_DEFAULT_LEN           400
+
+/* Wait count and inteval for fdir filter programming */
+#define I40E_FDIR_WAIT_COUNT       10
+#define I40E_FDIR_WAIT_INTERVAL_US 1000
+
+/* Wait count and inteval for fdir filter flush */
+#define I40E_FDIR_FLUSH_RETRY       50
+#define I40E_FDIR_FLUSH_INTERVAL_MS 5
+
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
 #define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
+				     struct rte_eth_fdir_input *fdir_input,
+				     unsigned char *raw_pkt);
+static int i40e_add_del_fdir_filter(struct i40e_pf *pf,
+			    struct rte_eth_fdir_filter *filter,
+			    bool add);
+static int i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			struct rte_eth_fdir_filter *filter,
+			bool add);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -285,4 +320,584 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 	i40e_vsi_release(vsi);
 	pf->fdir.fdir_vsi = NULL;
 	return;
-}
\ No newline at end of file
+}
+
+static int
+i40e_fdir_construct_pkt(struct i40e_pf *pf,
+			     struct rte_eth_fdir_input *fdir_input,
+			     unsigned char *raw_pkt)
+{
+	struct ether_hdr *ether;
+	unsigned char *payload;
+	struct ipv4_hdr *ip;
+	struct ipv6_hdr *ip6;
+	struct udp_hdr *udp;
+	struct tcp_hdr *tcp;
+	struct sctp_hdr *sctp;
+	uint8_t size = 0;
+	int i, set_idx = 2; /* set_idx = 2 means using l4 pyload by default*/
+
+	switch (fdir_input->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct udp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		/* set len to by default */
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.udp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.udp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_UDP;
+		udp->src_port = fdir_input->flow.udp4_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp4_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_UDP_DEFAULT_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct tcp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.tcp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.tcp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_TCP;
+		tcp->src_port = fdir_input->flow.tcp4_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.tcp4_flow.src_port;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct sctp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.sctp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.sctp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_SCTP;
+		sctp->tag = fdir_input->flow.sctp4_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+		ip->next_proto_id = IPPROTO_IP;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.ip4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.ip4_flow.src_ip;
+		set_idx = 1; /* l3 pyload */
+		break;
+
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr) + sizeof(struct udp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.udp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.udp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_UDP;
+		udp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv6_hdr) + sizeof(struct tcp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.tcp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.tcp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_TCP;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		tcp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr) + sizeof(struct sctp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.sctp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.sctp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_SCTP;
+		sctp->tag = fdir_input->flow.sctp6_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) + sizeof(struct ipv6_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->proto = IPPROTO_NONE;
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.ip6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.ip6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		set_idx = 1; /* l3 pyload */
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown flow type %u\n", fdir_input->flow_type);
+		return -EINVAL;
+	}
+
+	for (i = 0; i < 3; i++) {
+		if (pf->fdir.flex_set[set_idx][i].size == 0)
+			break;
+		(void)rte_memcpy(payload + 2 * pf->fdir.flex_set[set_idx][i].offset,
+				 fdir_input->flow_ext.flexwords + size,
+				 2 * pf->fdir.flex_set[set_idx][i].size);
+		size = pf->fdir.flex_set[set_idx][i].size;
+	}
+	return 0;
+}
+
+/* Construct the tx flags */
+static inline uint64_t
+i40e_build_ctob(uint32_t td_cmd,
+		uint32_t td_offset,
+		unsigned int size,
+		uint32_t td_tag)
+{
+	return rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DATA |
+			((uint64_t)td_cmd  << I40E_TXD_QW1_CMD_SHIFT) |
+			((uint64_t)td_offset << I40E_TXD_QW1_OFFSET_SHIFT) |
+			((uint64_t)size  << I40E_TXD_QW1_TX_BUF_SZ_SHIFT) |
+			((uint64_t)td_tag  << I40E_TXD_QW1_L2TAG1_SHIFT));
+}
+
+/*
+ * check the programming status descriptor in rx queue.
+ * done after Programming Flow Director is programmed on
+ * tx queue
+ */
+static inline int
+i40e_check_fdir_programming_status(struct i40e_rx_queue *rxq)
+{
+	volatile union i40e_rx_desc *rxdp;
+	uint64_t qword1;
+	uint32_t rx_status;
+	uint32_t len, id;
+	uint32_t error;
+	int ret = 0;
+
+	rxdp = &rxq->rx_ring[rxq->rx_tail];
+	qword1 = rte_le_to_cpu_64(rxdp->wb.qword1.status_error_len);
+	rx_status = (qword1 & I40E_RXD_QW1_STATUS_MASK)
+			>> I40E_RXD_QW1_STATUS_SHIFT;
+
+	if (rx_status & (1 << I40E_RX_DESC_STATUS_DD_SHIFT)) {
+		len = qword1 >> I40E_RX_PROG_STATUS_DESC_LENGTH_SHIFT;
+		id = (qword1 & I40E_RX_PROG_STATUS_DESC_QW1_PROGID_MASK) >>
+			    I40E_RX_PROG_STATUS_DESC_QW1_PROGID_SHIFT;
+
+		if (len  == I40E_RX_PROG_STATUS_DESC_LENGTH &&
+		    id == I40E_RX_PROG_STATUS_DESC_FD_FILTER_STATUS) {
+			error = (qword1 &
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_MASK) >>
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_SHIFT;
+			if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_FD_TBL_FULL_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to add FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_NO_FD_ENTRY_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to delete FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else
+				PMD_DRV_LOG(ERR, "invalid programming status"
+					    " reported, error = %u.", error);
+		} else
+			PMD_DRV_LOG(ERR, "unknown programming status"
+				    " reported,len = %d, id = %u.", len, id);
+		rxdp->wb.qword1.status_error_len = 0;
+		rxq->rx_tail++;
+		if (unlikely(rxq->rx_tail == rxq->nb_rx_desc))
+			rxq->rx_tail = 0;
+	}
+	return ret;
+}
+
+/*
+ * add or remove flow diretor filter.
+ */
+static int
+i40e_add_del_fdir_filter(struct i40e_pf *pf,
+			    struct rte_eth_fdir_filter *filter,
+			    bool add)
+{
+	int ret = I40E_SUCCESS;
+	unsigned char *pkt = (unsigned char *)pf->fdir.prg_pkt;
+
+	if (!(pf->flags & I40E_FLAG_FDIR)) {
+		PMD_DRV_LOG(ERR, "FDIR is not enabled.");
+		return -ENOTSUP;
+	}
+
+	memset(pkt, 0, I40E_FDIR_PKT_LEN);
+
+	ret = i40e_fdir_construct_pkt(pf, &filter->input, pkt);
+	if (ret < 0) {
+		PMD_DRV_LOG(ERR, "construct packet for fdir fails.");
+		return ret;
+	}
+
+	switch (filter->input.flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_UDP fdir program fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_TCP fdir program fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+			filter, add);
+		if (ret < 0) {
+			PMD_DRV_LOG(ERR, "NONF_IPV4_SCTP fdir program fails.");
+		}
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		/* program on both NONF_IPV4 and FRAG_IPV4 PCTYPE*/
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_OTHER fdir program fails.");
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_FRAG_IPV4,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_FRAG_IPV4 fdir program fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_UDP fdir program fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_TCP fdir program fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_SCTP fdir program fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		/* program on both NONF_IPV6 and FRAG_IPV6 PCTYPE*/
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_OTHER fdir program fails.");
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_FRAG_IPV6,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_FRAG_IPV6 fdir program fails.");
+		break;
+	default:
+		PMD_DRV_LOG(ERR, " invalid flow_type input.");
+		ret = -EINVAL;
+	}
+	return ret;
+}
+
+/*
+ * Program a flow diretor filter rule.
+ * Is done by Flow Director Programming Descriptor followed by packet
+ * structure that contains the filter fieldsneed to match.
+ */
+static int
+i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			struct rte_eth_fdir_filter *filter,
+			bool add)
+{
+	struct i40e_tx_queue *txq = pf->fdir.txq;
+	struct i40e_rx_queue *rxq = pf->fdir.rxq;
+	struct rte_eth_fdir_input *fdir_input = &filter->input;
+	struct rte_eth_fdir_action *fdir_action = &filter->action;
+	volatile struct i40e_tx_desc *txdp;
+	volatile struct i40e_filter_program_desc *fdirdp;
+	uint32_t td_cmd;
+	uint16_t i;
+	uint8_t dest;
+
+	PMD_DRV_LOG(INFO, "filling filter prgramming descriptor.");
+	fdirdp = (volatile struct i40e_filter_program_desc *)
+			(&(txq->tx_ring[txq->tx_tail]));
+
+	fdirdp->qindex_flex_ptype_vsi =
+			rte_cpu_to_le_32((fdir_action->rx_queue <<
+					  I40E_TXD_FLTR_QW0_QINDEX_SHIFT) &
+					  I40E_TXD_FLTR_QW0_QINDEX_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_action->flex_off <<
+					  I40E_TXD_FLTR_QW0_FLEXOFF_SHIFT) &
+					  I40E_TXD_FLTR_QW0_FLEXOFF_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pctype <<
+					  I40E_TXD_FLTR_QW0_PCTYPE_SHIFT) &
+					  I40E_TXD_FLTR_QW0_PCTYPE_MASK);
+
+	/* Use LAN VSI Id if not programmed by user */
+	if (fdir_input->flow_ext.dest_id == 0)
+		fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pf->main_vsi->vsi_id <<
+					  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+					  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+	else
+		fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_input->flow_ext.dest_id <<
+					  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+					  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+
+	fdirdp->dtype_cmd_cntindex =
+			rte_cpu_to_le_32(I40E_TX_DESC_DTYPE_FILTER_PROG);
+
+	if (add)
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_ADD_UPDATE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+	else
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_REMOVE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+
+	if (fdir_action->drop)
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DROP_PACKET;
+	else
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DIRECT_PACKET_QINDEX;
+	fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32((dest <<
+				I40E_TXD_FLTR_QW1_DEST_SHIFT) &
+				I40E_TXD_FLTR_QW1_DEST_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+		rte_cpu_to_le_32((fdir_action->report_status<<
+				I40E_TXD_FLTR_QW1_FD_STATUS_SHIFT) &
+				I40E_TXD_FLTR_QW1_FD_STATUS_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+			rte_cpu_to_le_32(I40E_TXD_FLTR_QW1_CNT_ENA_MASK);
+	if (fdir_action->cnt_idx != 0)
+		fdirdp->dtype_cmd_cntindex |=
+				rte_cpu_to_le_32((fdir_action->cnt_idx <<
+				I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+				I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+	else
+		fdirdp->dtype_cmd_cntindex |=
+				rte_cpu_to_le_32((pf->fdir.match_counter_index <<
+				I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+				I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+
+	fdirdp->fd_id = rte_cpu_to_le_32(filter->soft_id);
+	txq->tx_tail++;
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+
+	PMD_DRV_LOG(INFO, "filling transmit descriptor.");
+	txdp = &(txq->tx_ring[txq->tx_tail]);
+	txdp->buffer_addr = rte_cpu_to_le_64(pf->fdir.dma_addr);
+	td_cmd = I40E_TX_DESC_CMD_EOP |
+		 I40E_TX_DESC_CMD_RS  |
+		 I40E_TX_DESC_CMD_DUMMY;
+
+	txdp->cmd_type_offset_bsz =
+		i40e_build_ctob(td_cmd, 0, I40E_FDIR_PKT_LEN, 0);
+
+	txq->tx_tail++;
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+	/* Update the tx tail register */
+	rte_wmb();
+	I40E_PCI_REG_WRITE(txq->qtx_tail, txq->tx_tail);
+
+	for (i = 0; i < I40E_FDIR_WAIT_COUNT; i++) {
+		rte_delay_us(I40E_FDIR_WAIT_INTERVAL_US);
+		if (txdp->cmd_type_offset_bsz &
+				rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DESC_DONE))
+			break;
+	}
+	if (i >= I40E_FDIR_WAIT_COUNT) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " timeout to get DD on tx queue.");
+		return -ETIMEDOUT;
+	}
+	/* totally delay 10 ms to check programming status*/
+	rte_delay_us((I40E_FDIR_WAIT_COUNT - i) * I40E_FDIR_WAIT_INTERVAL_US);
+	if (i40e_check_fdir_programming_status(rxq) < 0) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " programming status reported.");
+		return -ENOSYS;
+	}
+
+	return 0;
+}
+
+/*
+ * i40e_fdir_ctrl_func - deal with all operations on flow director.
+ * @pf: board private structure
+ * @filter_op:operation will be taken.
+ * @arg: a pointer to specific structure corresponding to the filter_op
+ */
+int
+i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
+{
+	int ret = I40E_SUCCESS;
+
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_OP_NONE &&
+	    filter_op != RTE_ETH_FILTER_OP_FLUSH)
+		return -EINVAL;
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_OP_NONE:
+		if (!(pf->flags & I40E_FLAG_FDIR))
+			ret = -ENOTSUP;
+		break;
+	case RTE_ETH_FILTER_OP_ADD:
+		ret = i40e_add_del_fdir_filter(pf,
+			(struct rte_eth_fdir_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_OP_DELETE:
+		ret = i40e_add_del_fdir_filter(pf,
+			(struct rte_eth_fdir_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
+		ret = -EINVAL;
+		break;
+	}
+	return ret;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 07/20] app/test-pmd: add test commands to add/delete flow director filter
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (5 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 06/20] i40e: implement operations to add/delete " Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 08/20] i40e: match counter for flow director Jingjing Wu
                   ` (14 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

add commands which can be used to test adding or deleting 8 flow types of the flow director filters: ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 app/test-pmd/cmdline.c | 447 +++++++++++++++++++++++++++++++++++++++++++++++++
 app/test-pmd/testpmd.h |   3 +
 2 files changed, 450 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 225f669..173e863 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -660,6 +660,28 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"get_flex_filter (port_id) index (idx)\n"
 			"    get info of a flex filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del)"
+			" flow (ip4|ip6) src (src_ip_address) dst (dst_ip_address)"
+			" flexwords (flexwords_value) (drop|fwd)"
+			" queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a IP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del)"
+			" flow (udp4|tcp4|udp6|tcp6)"
+			" src (src_ip_address) (src_port)"
+			" dst (dst_ip_address) (dst_port)"
+			" flexwords (flexwords_value) (drop|fwd)"
+			" queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a UDP/TCP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del)"
+			" flow (sctp4|sctp6)"
+			" src (src_ip_address) dst (dst_ip_address)"
+			" tag (verification_tag)"
+			" flexwords (flexwords_value) (drop|fwd)"
+			" queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a SCTP type flow director filter.\n\n"
 		);
 	}
 }
@@ -7411,6 +7433,428 @@ cmdline_parse_inst_t cmd_get_flex_filter = {
 	},
 };
 
+/* *** Filters Control *** */
+
+/* *** deal with flow director filter *** */
+struct cmd_flow_director_result {
+	cmdline_fixed_string_t flow_director_filter;
+	uint8_t port_id;
+	cmdline_fixed_string_t ops;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t src;
+	cmdline_ipaddr_t ip_src;
+	uint16_t port_src;
+	cmdline_fixed_string_t dst;
+	cmdline_ipaddr_t ip_dst;
+	uint16_t port_dst;
+	cmdline_fixed_string_t verify_tag;
+	uint32_t verify_tag_value;
+	cmdline_fixed_string_t flexwords;
+	cmdline_fixed_string_t flexwords_value;
+	cmdline_fixed_string_t drop;
+	cmdline_fixed_string_t queue;
+	uint16_t  queue_id;
+	cmdline_fixed_string_t fd_id;
+	uint32_t  fd_id_value;
+};
+
+static inline int
+parse_flexwords(const char *q_arg, uint16_t *flexwords)
+{
+#define MAX_NUM_WORD 8
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	unsigned long int_fld[MAX_NUM_WORD];
+	char *str_fld[MAX_NUM_WORD];
+	int i;
+	unsigned size;
+	int num_words = -1;
+
+	p = strchr(p0, '(');
+	if (p == NULL)
+		return -1;
+	++p;
+	p0 = strchr(p, ')');
+	if (p0 == NULL)
+		return -1;
+
+	size = p0 - p;
+	if (size >= sizeof(s))
+		return -1;
+
+	snprintf(s, sizeof(s), "%.*s", size, p);
+	num_words = rte_strsplit(s, sizeof(s), str_fld, MAX_NUM_WORD, ',');
+	if (num_words < 0 || num_words > MAX_NUM_WORD)
+		return -1;
+	for (i = 0; i < num_words; i++) {
+		errno = 0;
+		int_fld[i] = strtoul(str_fld[i], &end, 0);
+		if (errno != 0 || end == str_fld[i] || int_fld[i] > UINT16_MAX)
+			return -1;
+		flexwords[i] = rte_cpu_to_be_16((uint16_t)int_fld[i]);
+	}
+	return num_words;
+}
+
+static void
+cmd_flow_director_filter_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	struct rte_eth_fdir_filter entry;
+	uint16_t flexwords[8];
+	int num_flexwords;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+	memset(flexwords, 0, sizeof(flexwords));
+	memset(&entry, 0, sizeof(struct rte_eth_fdir_filter));
+	num_flexwords = parse_flexwords(res->flexwords_value, flexwords);
+	if (num_flexwords < 0) {
+		printf("error: Cannot pase flexwords input.\n");
+		return;
+	}
+
+	if (!strcmp(res->flow_type, "ip4")) {
+		/* no need to convert, already big endian. */
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.ip4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.ip4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_IPV4_OTHER;
+	} else if (!strcmp(res->flow_type, "udp4")) {
+		/* no need to convert, already big endian. */
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.udp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.udp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.udp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
+	} else if (!strcmp(res->flow_type, "tcp4")) {
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.tcp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.tcp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.tcp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.tcp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
+	} else if (!strcmp(res->flow_type, "sctp4")) {
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.sctp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.sctp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.sctp4_flow.verify_tag =
+				rte_cpu_to_be_32(res->verify_tag_value);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
+	} else if (!strcmp(res->flow_type, "ip6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.ip6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.ip6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_IPV6_OTHER;
+	} else if (!strcmp(res->flow_type, "udp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.udp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.udp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow.udp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
+	} else if (!strcmp(res->flow_type, "tcp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.tcp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.tcp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow.tcp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.tcp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
+	} else if (!strcmp(res->flow_type, "sctp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.sctp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.sctp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow.sctp6_flow.verify_tag =
+			rte_cpu_to_be_32(res->verify_tag_value);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
+	}
+
+	entry.input.flow_ext.num_flexwords = num_flexwords;
+	rte_memcpy(entry.input.flow_ext.flexwords,
+		   flexwords,
+		   BYTES_PER_WORD * num_flexwords);
+
+	entry.input.flow_ext.dest_id = 0; /* if set to 0, will use main vsi by default*/
+	entry.action.flex_off = 0;  /*use 0 by default*/
+	if (!strcmp(res->drop, "drop"))
+		entry.action.drop = 1;
+	else
+		entry.action.drop = 0;
+	/* set to report FD ID by default temporary*/
+	entry.action.report_status = RTE_ETH_FDIR_REPORT_FD_ID;
+	entry.action.rx_queue = res->queue_id;
+	/* use 0 by default, will set it to fdir counter per dev */
+	entry.action.cnt_idx = 0;
+	entry.soft_id = res->fd_id_value;
+	if (!strcmp(res->ops, "add"))
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_OP_ADD, &entry);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_OP_DELETE, &entry);
+	if (ret < 0)
+		printf("flow director programming error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_token_string_t cmd_flow_director_filter =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_director_filter, "flow_director_filter");
+cmdline_parse_token_num_t cmd_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_ops =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 ops, "add#del");
+cmdline_parse_token_string_t cmd_flow_director_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_type,
+				 "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_src =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 src, "src");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_src =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_src);
+cmdline_parse_token_num_t cmd_flow_director_port_src =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_src, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_dst =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 dst, "dst");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_dst =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_dst);
+cmdline_parse_token_num_t cmd_flow_director_port_dst =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_dst, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_verify_tag =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				  verify_tag, "verify_tag");
+cmdline_parse_token_num_t cmd_flow_director_verify_tag_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      verify_tag_value, UINT32);
+cmdline_parse_token_string_t cmd_flow_director_flexwords =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flexwords, "flexwords");
+cmdline_parse_token_string_t cmd_flow_director_flexwords_value =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+			      flexwords_value, NULL);
+cmdline_parse_token_string_t cmd_flow_director_drop =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 drop, "drop#fwd");
+cmdline_parse_token_string_t cmd_flow_director_queue =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 queue, "queue");
+cmdline_parse_token_num_t cmd_flow_director_queue_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      queue_id, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_fd_id =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 fd_id, "fd_id");
+cmdline_parse_token_num_t cmd_flow_director_fd_id_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      fd_id_value, UINT32);
+
+cmdline_parse_inst_t cmd_add_del_ip_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a ip flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_udp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a udp/tcp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_port_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_port_dst,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a sctp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_verify_tag,
+		(void *)&cmd_flow_director_verify_tag_value,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7537,6 +7981,9 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_remove_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_get_flex_filter,
+	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	NULL,
 };
 
diff --git a/app/test-pmd/testpmd.h b/app/test-pmd/testpmd.h
index 9cbfeac..74c0c0c 100644
--- a/app/test-pmd/testpmd.h
+++ b/app/test-pmd/testpmd.h
@@ -73,6 +73,9 @@ int main(int argc, char **argv);
 #define NUMA_NO_CONFIG 0xFF
 #define UMA_NO_CONFIG  0xFF
 
+#define BYTES_PER_WORD  2
+#define IPV6_ADDR_LEN 16
+
 typedef uint8_t  lcoreid_t;
 typedef uint8_t  portid_t;
 typedef uint16_t queueid_t;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 08/20] i40e: match counter for flow director
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (6 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 07/20] app/test-pmd: add test commands to add/delete flow director filter Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 09/20] i40e: report flow director match info to mbuf Jingjing Wu
                   ` (13 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

support to get the fdir_match counter

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 9791519..565ee00 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1303,6 +1303,9 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			    I40E_GLPRT_PTC9522L(hw->port),
 			    pf->offset_loaded, &os->tx_size_big,
 			    &ns->tx_size_big);
+	i40e_stat_update_32(hw, I40E_GLQF_PCNT(pf->fdir.match_counter_index),
+			   pf->offset_loaded,
+			   &os->fd_sb_match, &ns->fd_sb_match);
 	/* GLPRT_MSPDC not supported */
 	/* GLPRT_XEC not supported */
 
@@ -1316,6 +1319,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 	stats->obytes   = ns->eth.tx_bytes;
 	stats->oerrors  = ns->eth.tx_errors;
 	stats->imcasts  = ns->eth.rx_multicast;
+	stats->fdirmatch = ns->fd_sb_match;
 
 	if (pf->main_vsi)
 		i40e_update_vsi_stats(pf->main_vsi);
@@ -1387,6 +1391,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			ns->mac_short_packet_dropped);
 	PMD_DRV_LOG(DEBUG, "checksum_error:           %lu",
 		    ns->checksum_error);
+	PMD_DRV_LOG(DEBUG, "fdir_match:               %lu", ns->fd_sb_match);
 	PMD_DRV_LOG(DEBUG, "***************** PF stats end ********************");
 }
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 09/20] i40e: report flow director match info to mbuf
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (7 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 08/20] i40e: match counter for flow director Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 10/20] lib/librte_ether: define structures for getting flow director information Jingjing Wu
                   ` (12 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

support to set the FDIR flag and report FD_ID in mbuf if match

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_rxtx.c | 48 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 48 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 4435367..c067cdd 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -105,6 +105,10 @@ i40e_rxd_status_to_pkt_flags(uint64_t qword)
 					I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
 			I40E_RX_DESC_FLTSTAT_RSS_HASH) ? PKT_RX_RSS_HASH : 0;
 
+	/* Check if FDIR Match */
+	flags |= (uint16_t)(qword & (1 << I40E_RX_DESC_STATUS_FLM_SHIFT) ?
+							PKT_RX_FDIR : 0);
+
 	return flags;
 }
 
@@ -641,6 +645,22 @@ i40e_rx_scan_hw_ring(struct i40e_rx_queue *rxq)
 			if (pkt_flags & PKT_RX_RSS_HASH)
 				mb->hash.rss = rte_le_to_cpu_32(\
 					rxdp->wb.qword0.hi_dword.rss);
+
+			if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				if (((qword1 >> I40E_RX_DESC_STATUS_FLTSTAT_SHIFT) &
+						I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
+						I40E_RX_DESC_FLTSTAT_RSV_FD_ID)
+					mb->hash.fdir.id = (uint16_t)
+						rte_le_to_cpu_32(rxdp[j].wb.qword0.hi_dword.fd);
+#else
+				if (((rxdp[j].wb.qword2.ext_status >>
+					I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+					0x03) == 0x01)
+					mb->hash.fdir.id = (uint16_t)
+						rte_le_to_cpu_32(rxdp[j].wb.qword3.hi_dword.fd_id);
+#endif
+			}
 		}
 
 		for (j = 0; j < I40E_LOOK_AHEAD; j++)
@@ -877,6 +897,20 @@ i40e_recv_pkts(void *rx_queue, struct rte_mbuf **rx_pkts, uint16_t nb_pkts)
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+			if (((qword1 >> I40E_RX_DESC_STATUS_FLTSTAT_SHIFT) &
+					I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
+					I40E_RX_DESC_FLTSTAT_RSV_FD_ID)
+				rxm->hash.fdir.id = (uint16_t)
+					rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.fd);
+#else
+			if (((rxd.wb.qword2.ext_status >> I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x01)
+				rxm->hash.fdir.id = (uint16_t)
+					rte_le_to_cpu_32(rxd.wb.qword3.hi_dword.fd_id);
+#endif
+		}
 
 		rx_pkts[nb_rx++] = rxm;
 	}
@@ -1031,6 +1065,20 @@ i40e_recv_scattered_pkts(void *rx_queue,
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+			if (((qword1 >> I40E_RX_DESC_STATUS_FLTSTAT_SHIFT) &
+					I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
+					I40E_RX_DESC_FLTSTAT_RSV_FD_ID)
+				rxm->hash.fdir.id = (uint16_t)
+					rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.fd);
+#else
+			if (((rxd.wb.qword2.ext_status >> I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x01)
+				rxm->hash.fdir.id = (uint16_t)
+					rte_le_to_cpu_32(rxd.wb.qword3.hi_dword.fd_id);
+#endif
+		}
 
 		/* Prefetch data of first segment, if configured to do so. */
 		rte_prefetch0(RTE_PTR_ADD(first_seg->buf_addr,
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 10/20] lib/librte_ether: define structures for getting flow director information
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (8 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 09/20] i40e: report flow director match info to mbuf Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 11/20] i40e: implement operations to get fdir info Jingjing Wu
                   ` (11 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

define structures for getting flow director information

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 40 ++++++++++++++++++++++++++++++++++++++++
 lib/librte_ether/rte_ethdev.h   | 23 -----------------------
 2 files changed, 40 insertions(+), 23 deletions(-)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index df1ce4b..208082e 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -230,6 +230,46 @@ struct rte_eth_fdir_filter {
 	struct rte_eth_fdir_action action;  /**< action taken when match */
 };
 
+/**
+ * A structure used to report the status of the flow director filters in use.
+ */
+struct rte_eth_fdir {
+	/** Number of filters with collision indication. */
+	uint16_t collision;
+	/** Number of free (non programmed) filters. */
+	uint16_t free;
+	/** The Lookup hash value of the added filter that updated the value
+	   of the MAXLEN field */
+	uint16_t maxhash;
+	/** Longest linked list of filters in the table. */
+	uint8_t maxlen;
+	/** Number of added filters. */
+	uint64_t add;
+	/** Number of removed filters. */
+	uint64_t remove;
+	/** Number of failed added filters (no more space in device). */
+	uint64_t f_add;
+	/** Number of failed removed filters. */
+	uint64_t f_remove;
+};
+
+struct rte_eth_fdir_ext {
+	uint16_t guarant_spc;  /**< guaranteed spaces.*/
+	uint16_t guarant_cnt;  /**< Number of filters in guaranteed spaces. */
+	uint16_t best_spc;     /**< best effort spaces.*/
+	uint16_t best_cnt;     /**< Number of filters in best effort spaces. */
+};
+
+/**
+ * A structure used for user to get the status information of flow director filter
+ * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_OP_GET_INFO operation.
+ */
+struct rte_eth_fdir_info {
+	int mode;                 /**< if 0 disbale, if 1 enable*/
+	struct rte_eth_fdir info;
+	struct rte_eth_fdir_ext info_ext;
+};
+
 #ifdef __cplusplus
 }
 #endif
diff --git a/lib/librte_ether/rte_ethdev.h b/lib/librte_ether/rte_ethdev.h
index e2ea84a..6407e5d 100644
--- a/lib/librte_ether/rte_ethdev.h
+++ b/lib/librte_ether/rte_ethdev.h
@@ -794,29 +794,6 @@ struct rte_fdir_masks {
 };
 
 /**
- *  A structure used to report the status of the flow director filters in use.
- */
-struct rte_eth_fdir {
-	/** Number of filters with collision indication. */
-	uint16_t collision;
-	/** Number of free (non programmed) filters. */
-	uint16_t free;
-	/** The Lookup hash value of the added filter that updated the value
-	   of the MAXLEN field */
-	uint16_t maxhash;
-	/** Longest linked list of filters in the table. */
-	uint8_t maxlen;
-	/** Number of added filters. */
-	uint64_t add;
-	/** Number of removed filters. */
-	uint64_t remove;
-	/** Number of failed added filters (no more space in device). */
-	uint64_t f_add;
-	/** Number of failed removed filters. */
-	uint64_t f_remove;
-};
-
-/**
  * A structure used to enable/disable specific device interrupts.
  */
 struct rte_intr_conf {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 11/20] i40e: implement operations to get fdir info
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (9 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 10/20] lib/librte_ether: define structures for getting flow director information Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 12/20] app/test-pmd: display fdir statistics Jingjing Wu
                   ` (10 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

implement operation to get flow director information in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 34 ++++++++++++++++++++++++++++++++++
 1 file changed, 34 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 82645df..d6c1793 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -92,6 +92,8 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			enum i40e_filter_pctype pctype,
 			struct rte_eth_fdir_filter *filter,
 			bool add);
+static void i40e_fdir_info_get(struct i40e_pf *pf,
+			   struct rte_eth_fdir_info *fdir);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -865,6 +867,35 @@ i40e_fdir_filter_programming(struct i40e_pf *pf,
 }
 
 /*
+ * i40e_fdir_info_get - get information of Flow Director
+ * @pf: ethernet device to get info from
+ * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
+ *    the flow director information.
+ */
+static void
+i40e_fdir_info_get(struct i40e_pf *pf, struct rte_eth_fdir_info *fdir)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t pfqf_ctl;
+
+	pfqf_ctl = I40E_READ_REG(hw, I40E_PFQF_CTL_0);
+	fdir->mode = pfqf_ctl & I40E_PFQF_CTL_0_FD_ENA_MASK ? 1 : 0;
+	fdir->info_ext.guarant_spc =
+		(uint16_t)hw->func_caps.fd_filters_guaranteed;
+	fdir->info_ext.guarant_cnt =
+		(uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	fdir->info_ext.best_spc =
+		(uint16_t)hw->func_caps.fd_filters_best_effort;
+	fdir->info_ext.best_cnt =
+		(uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			    I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	return;
+}
+
+/*
  * i40e_fdir_ctrl_func - deal with all operations on flow director.
  * @pf: board private structure
  * @filter_op:operation will be taken.
@@ -894,6 +925,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_OP_GET_INFO:
+		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
+		break;
 	default:
 		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
 		ret = -EINVAL;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 12/20] app/test-pmd: display fdir statistics
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (10 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 11/20] i40e: implement operations to get fdir info Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 13/20] i40e: implement operation to flush flow director table Jingjing Wu
                   ` (9 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

display flow director's statistics information

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 app/test-pmd/config.c | 40 +++++++++++++++++++++++++++++++---------
 1 file changed, 31 insertions(+), 9 deletions(-)

diff --git a/app/test-pmd/config.c b/app/test-pmd/config.c
index 2a1b93f..f28e338 100644
--- a/app/test-pmd/config.c
+++ b/app/test-pmd/config.c
@@ -1815,26 +1815,48 @@ fdir_remove_signature_filter(portid_t port_id,
 void
 fdir_get_infos(portid_t port_id)
 {
-	struct rte_eth_fdir fdir_infos;
+	struct rte_eth_fdir_info fdir_infos;
+	int ret;
 
 	static const char *fdir_stats_border = "########################";
 
 	if (port_id_is_invalid(port_id))
 		return;
 
-	rte_eth_dev_fdir_get_infos(port_id, &fdir_infos);
-
+	memset(&fdir_infos, 0, sizeof(fdir_infos));
+	ret = rte_eth_dev_filter_ctrl(port_id, RTE_ETH_FILTER_FDIR,
+			       RTE_ETH_FILTER_OP_GET_INFO, &fdir_infos);
+	if (ret < 0) {
+		ret = rte_eth_dev_fdir_get_infos(port_id, &fdir_infos.info);
+		if (ret < 0) {
+			printf("\n getting fdir info fails on port %-2d\n",
+				port_id);
+			return;
+		}
+		fdir_infos.mode = (fdir_conf.mode == RTE_FDIR_MODE_NONE) ? 0 : 1;
+	}
 	printf("\n  %s FDIR infos for port %-2d     %s\n",
 	       fdir_stats_border, port_id, fdir_stats_border);
-
+	if (fdir_infos.mode)
+			printf("  FDIR is enabled\n");
+	else
+			printf("  FDIR is disabled\n");
 	printf("  collision: %-10"PRIu64"  free:     %"PRIu64"\n"
 	       "  maxhash:   %-10"PRIu64"  maxlen:   %"PRIu64"\n"
-	       "  add:       %-10"PRIu64"  remove:   %"PRIu64"\n"
+	       "  add:	     %-10"PRIu64"  remove:   %"PRIu64"\n"
 	       "  f_add:     %-10"PRIu64"  f_remove: %"PRIu64"\n",
-	       (uint64_t)(fdir_infos.collision), (uint64_t)(fdir_infos.free),
-	       (uint64_t)(fdir_infos.maxhash), (uint64_t)(fdir_infos.maxlen),
-	       fdir_infos.add, fdir_infos.remove,
-	       fdir_infos.f_add, fdir_infos.f_remove);
+	       (uint64_t)(fdir_infos.info.collision), (uint64_t)(fdir_infos.info.free),
+	       (uint64_t)(fdir_infos.info.maxhash), (uint64_t)(fdir_infos.info.maxlen),
+	       fdir_infos.info.add, fdir_infos.info.remove,
+	       fdir_infos.info.f_add, fdir_infos.info.f_remove);
+	printf("  guarant_space: %-10"PRIu16
+	       "  best_space:    %-10"PRIu16"\n",
+	       fdir_infos.info_ext.guarant_spc,
+	       fdir_infos.info_ext.best_spc);
+	printf("  guarant_count: %-10"PRIu16
+	       "  best_count:    %-10"PRIu16"\n",
+	       fdir_infos.info_ext.guarant_cnt,
+	       fdir_infos.info_ext.best_cnt);
 	printf("  %s############################%s\n",
 	       fdir_stats_border, fdir_stats_border);
 }
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 13/20] i40e: implement operation to flush flow director table
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (11 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 12/20] app/test-pmd: display fdir statistics Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 14/20] app/test-pmd: add test command " Jingjing Wu
                   ` (8 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

implement operation to flush flow director table

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 43 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 43 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index d6c1793..973c8e0 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -92,6 +92,7 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			enum i40e_filter_pctype pctype,
 			struct rte_eth_fdir_filter *filter,
 			bool add);
+static int i40e_fdir_flush(struct i40e_pf *pf);
 static void i40e_fdir_info_get(struct i40e_pf *pf,
 			   struct rte_eth_fdir_info *fdir);
 
@@ -867,6 +868,45 @@ i40e_fdir_filter_programming(struct i40e_pf *pf,
 }
 
 /*
+ * i40e_fdir_flush - clear all filters of Flow Director
+ * @pf: board private structure
+ */
+static int
+i40e_fdir_flush(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t reg;
+	uint16_t guarant_cnt, best_cnt;
+	int i;
+
+	I40E_WRITE_REG(hw, I40E_PFQF_CTL_1, I40E_PFQF_CTL_1_CLEARFDTABLE_MASK);
+	I40E_WRITE_FLUSH(hw);
+
+	for (i = 0; i < I40E_FDIR_FLUSH_RETRY; i++) {
+		rte_delay_ms(I40E_FDIR_FLUSH_INTERVAL_MS);
+		reg = I40E_READ_REG(hw, I40E_PFQF_CTL_1);
+		if (!(reg & I40E_PFQF_CTL_1_CLEARFDTABLE_MASK))
+			break;
+	}
+	if (i >= I40E_FDIR_FLUSH_RETRY) {
+		PMD_DRV_LOG(ERR, "FD table did not flush, may need more time.");
+		return -ETIMEDOUT;
+	}
+	guarant_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	best_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	if (guarant_cnt != 0 || best_cnt != 0) {
+		PMD_DRV_LOG(ERR, "Failed to flush FD table.");
+		return -ENOSYS;
+	} else
+		PMD_DRV_LOG(INFO, "FD table Flush success.");
+	return 0;
+}
+
+/*
  * i40e_fdir_info_get - get information of Flow Director
  * @pf: ethernet device to get info from
  * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
@@ -925,6 +965,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_OP_FLUSH:
+		ret = i40e_fdir_flush(pf);
+		break;
 	case RTE_ETH_FILTER_OP_GET_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
 		break;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 14/20] app/test-pmd: add test command to flush flow director table
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (12 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 13/20] i40e: implement operation to flush flow director table Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 15/20] lib/librte_ether: define structures for configuring flexible payload Jingjing Wu
                   ` (7 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

add test command to flush flow director table

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 app/test-pmd/cmdline.c | 49 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 49 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 173e863..240a464 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -682,6 +682,9 @@ static void cmd_help_long_parsed(void *parsed_result,
 			" flexwords (flexwords_value) (drop|fwd)"
 			" queue (queue_id) fd_id (fd_id_value)\n"
 			"    Add/Del a SCTP type flow director filter.\n\n"
+
+			"flush_flow_diretor (port_id)\n"
+			"    Flush all flow director entries of a device.\n\n"
 		);
 	}
 }
@@ -7855,6 +7858,51 @@ cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
 	},
 };
 
+struct cmd_flush_flow_director_result {
+	cmdline_fixed_string_t flush_flow_director;
+	uint8_t port_id;
+};
+
+cmdline_parse_token_string_t cmd_flush_flow_director_flush =
+	TOKEN_STRING_INITIALIZER(struct cmd_flush_flow_director_result,
+				 flush_flow_director, "flush_flow_director");
+cmdline_parse_token_num_t cmd_flush_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flush_flow_director_result,
+			      port_id, UINT8);
+
+static void
+cmd_flush_flow_director_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+			RTE_ETH_FILTER_OP_FLUSH, NULL);
+	if (ret < 0)
+		printf("flow director table flushing error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_inst_t cmd_flush_flow_director = {
+	.f = cmd_flush_flow_director_parsed,
+	.data = NULL,
+	.help_str = "flush all flow director entries of a device on NIC",
+	.tokens = {
+		(void *)&cmd_flush_flow_director_flush,
+		(void *)&cmd_flush_flow_director_port_id,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7984,6 +8032,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 15/20] lib/librte_ether: define structures for configuring flexible payload
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (13 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 14/20] app/test-pmd: add test command " Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v316/20] i40e: implement operations to configure " Jingjing Wu
                   ` (6 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

define structures for configuring flexible payload

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 42 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 42 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 208082e..e412471 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -75,6 +75,25 @@ enum rte_filter_op {
  * Define all structures for Flow Director Filter type corresponding with specific operations.
  */
 
+
+/**
+ * A structure defined a field vector to specify each field.
+ */
+struct rte_eth_field_vector {
+	uint8_t offset;   /**< Source word offset */
+	uint8_t size;     /**< Field Size defined in word units */
+};
+
+/**
+ * payload type
+ */
+enum rte_eth_payload_type {
+	RTE_ETH_PAYLOAD_UNKNOWN = 0,
+	RTE_ETH_L2_PAYLOAD,
+	RTE_ETH_L3_PAYLOAD,
+	RTE_ETH_L4_PAYLOAD,
+};
+
 /**
  * flow type
  */
@@ -91,6 +110,29 @@ enum rte_eth_flow_type {
 };
 
 /**
+ * A structure used to select fields extracted from the protocol layers to
+ * the Field Vector as flexible payload for filter
+ */
+struct rte_eth_flex_payload_cfg {
+	enum rte_eth_payload_type type;  /**< payload type */
+	uint8_t nb_field;                /**< the number of folloing fieds */
+	struct rte_eth_field_vector field[0];
+};
+
+#define RTE_ETH_FDIR_CFG_FLX      0x0001
+/**
+ * A structure used to config FDIR filter global set
+ * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_OP_SET operation.
+ */
+struct rte_eth_fdir_cfg {
+	uint16_t cmd;  /**< define sub command in the generic OP_SET  */
+	/**
+	 * A pointer to structure for the configuration e.g.
+	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
+	*/
+	void *cfg;
+};
+/**
  * A structure used to define the input for IPV4 UDP flow
  */
 struct rte_eth_udpv4_flow {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v316/20] i40e: implement operations to configure flexible payload
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (14 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 15/20] lib/librte_ether: define structures for configuring flexible payload Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 17/20] app/test-pmd: add test command " Jingjing Wu
                   ` (5 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

implement operation to flexible payload in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 101 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 101 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 973c8e0..01693a2 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -80,8 +80,11 @@
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
 #define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+#define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 struct rte_eth_flex_payload_cfg *cfg);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -325,6 +328,97 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 	return;
 }
 
+/*
+ * i40e_set_flx_pld_cfg -configure the rule how bytes stream is extracted as flexible payload
+ * @pf: board private structure
+ * @cfg: the rule how bytes stream is extracted as flexible payload
+ */
+static int
+i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 struct rte_eth_flex_payload_cfg *cfg)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct rte_eth_fdir_info fdir;
+	uint32_t flx_pit;
+	uint16_t min_next_off = 0;
+	uint8_t idx = 0;
+	int i = 0;
+	int num_word = 0;
+	int ret;
+
+	if (cfg == NULL || cfg->nb_field > 3)
+		return -EINVAL;
+
+	if (cfg->type == RTE_ETH_L2_PAYLOAD)
+		idx = 0;
+	else if (cfg->type == RTE_ETH_L3_PAYLOAD)
+		idx = 1;
+	else if (cfg->type == RTE_ETH_L4_PAYLOAD)
+		idx = 2;
+	else {
+		PMD_DRV_LOG(ERR, "unknown payload type.");
+		return -EINVAL;
+	}
+	/*
+	 * flexible payload need to be configured before
+	 * flow director filters are added
+	 * If filters exist, flush them.
+	 */
+	memset(&fdir, 0, sizeof(fdir));
+	i40e_fdir_info_get(pf, &fdir);
+	if (fdir.info_ext.best_cnt + fdir.info_ext.guarant_cnt > 0) {
+		ret = i40e_fdir_flush(pf);
+		if (ret) {
+			PMD_DRV_LOG(ERR, " failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	for (i = 0; i < cfg->nb_field; i++) {
+		/*
+		 * check register's constrain
+		 * Current Offset >= previous offset + previous FSIZE.
+		 */
+		if (cfg->field[i].offset < min_next_off) {
+			PMD_DRV_LOG(ERR, "Offset should be larger than"
+				"previous offset + previous FSIZE.");
+			return -EINVAL;
+		}
+		flx_pit = (cfg->field[i].offset <<
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK;
+		flx_pit |= (cfg->field[i].size <<
+				I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) &
+				I40E_PRTQF_FLX_PIT_FSIZE_MASK;
+		flx_pit |= ((num_word + I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+				I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) &
+				I40E_PRTQF_FLX_PIT_DEST_OFF_MASK;
+		/* support no more than 8 words flexible payload*/
+		num_word += cfg->field[i].size;
+		if (num_word > 8)
+			return -EINVAL;
+
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(idx * 3 + i), flx_pit);
+		/* record the info in fdir structure */
+		pf->fdir.flex_set[idx][i].offset = cfg->field[i].offset;
+		pf->fdir.flex_set[idx][i].size = cfg->field[i].size;
+		min_next_off = cfg->field[i].offset + cfg->field[i].size;
+	}
+
+	for (; i < 3; i++) {
+		/* set the non-used register obeying register's constrain */
+		flx_pit = (min_next_off << I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK;
+		flx_pit |= (1 << I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) &
+			I40E_PRTQF_FLX_PIT_FSIZE_MASK;
+		flx_pit |= (63 << I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_DEST_OFF_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(idx * 3 + i), flx_pit);
+		min_next_off++;
+	}
+
+	return 0;
+}
 static int
 i40e_fdir_construct_pkt(struct i40e_pf *pf,
 			     struct rte_eth_fdir_input *fdir_input,
@@ -944,6 +1038,7 @@ i40e_fdir_info_get(struct i40e_pf *pf, struct rte_eth_fdir_info *fdir)
 int
 i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 {
+	struct rte_eth_fdir_cfg *fdir_cfg = NULL;
 	int ret = I40E_SUCCESS;
 
 	if (arg == NULL && filter_op != RTE_ETH_FILTER_OP_NONE &&
@@ -968,6 +1063,12 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 	case RTE_ETH_FILTER_OP_FLUSH:
 		ret = i40e_fdir_flush(pf);
 		break;
+	case RTE_ETH_FILTER_OP_SET:
+		fdir_cfg = (struct rte_eth_fdir_cfg *)arg;
+		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX)
+			ret = i40e_set_flx_pld_cfg(pf,
+				(struct rte_eth_flex_payload_cfg *)fdir_cfg->cfg);
+		break;
 	case RTE_ETH_FILTER_OP_GET_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
 		break;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 17/20] app/test-pmd: add test command to configure flexible payload
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (15 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v316/20] i40e: implement operations to configure " Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 18/20] lib/librte_ether: define structures for configuring flex masks Jingjing Wu
                   ` (4 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

add test command to configure flexible payload

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 app/test-pmd/cmdline.c | 144 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 144 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 240a464..da77752 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -58,6 +58,7 @@
 #include <rte_debug.h>
 #include <rte_cycles.h>
 #include <rte_memory.h>
+#include <rte_malloc.h>
 #include <rte_memzone.h>
 #include <rte_launch.h>
 #include <rte_tailq.h>
@@ -685,6 +686,10 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"flush_flow_diretor (port_id)\n"
 			"    Flush all flow director entries of a device.\n\n"
+
+			"flow_director_flex_payload (port_id)"
+			" (l2|l3|l4) (config)\n"
+			"    configure flexible payload selection.\n\n"
 		);
 	}
 }
@@ -7903,6 +7908,144 @@ cmdline_parse_inst_t cmd_flush_flow_director = {
 	},
 };
 
+/* *** deal with flow director flexible payload configuration *** */
+struct cmd_flow_director_flexpayload_result {
+	cmdline_fixed_string_t flow_director_flexpayload;
+	uint8_t port_id;
+	cmdline_fixed_string_t payload_layer;
+	cmdline_fixed_string_t payload_cfg;
+};
+
+static inline int
+parse_flex_payload_cfg(const char *q_arg,
+			     struct rte_eth_flex_payload_cfg *cfg)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	enum fieldnames {
+		FLD_OFFSET = 0,
+		FLD_SIZE,
+		_NUM_FLD
+	};
+	unsigned long int_fld[_NUM_FLD];
+	char *str_fld[_NUM_FLD];
+	int i;
+	unsigned size;
+
+	cfg->nb_field = 0;
+	p = strchr(p0, '(');
+	while (p != NULL) {
+		++p;
+		p0 = strchr(p, ')');
+		if (p0 == NULL)
+			return -1;
+
+		size = p0 - p;
+		if (size >= sizeof(s))
+			return -1;
+
+		snprintf(s, sizeof(s), "%.*s", size, p);
+		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') != _NUM_FLD)
+			return -1;
+		for (i = 0; i < _NUM_FLD; i++) {
+			errno = 0;
+			int_fld[i] = strtoul(str_fld[i], &end, 0);
+			if (errno != 0 || end == str_fld[i] || int_fld[i] > 255)
+				return -1;
+		}
+		cfg->field[cfg->nb_field].offset = (uint8_t)int_fld[FLD_OFFSET];
+		cfg->field[cfg->nb_field].size = (uint8_t)int_fld[FLD_SIZE];
+		cfg->nb_field++;
+		if (cfg->nb_field > 3) {
+			printf("exceeded max number of fields\n");
+			return -1;
+		}
+		p = strchr(p0, '(');
+	}
+	return 0;
+}
+
+static void
+cmd_flow_director_flxpld_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flexpayload_result *res = parsed_result;
+	struct rte_eth_fdir_cfg fdir_cfg;
+	struct rte_eth_flex_payload_cfg *flxpld_cfg;
+	int ret = 0;
+	int cfg_size = 3 * sizeof(struct rte_eth_field_vector) +
+		  offsetof(struct rte_eth_flex_payload_cfg, field);
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
+
+	flxpld_cfg = (struct rte_eth_flex_payload_cfg *)rte_zmalloc_socket("CLI",
+		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
+
+	if (flxpld_cfg == NULL) {
+		printf("fail to malloc memory to configure flexible payload\n");
+		return;
+	}
+
+	if (!strcmp(res->payload_layer, "l2"))
+		flxpld_cfg->type = RTE_ETH_L2_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l3"))
+		flxpld_cfg->type = RTE_ETH_L3_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l4"))
+		flxpld_cfg->type = RTE_ETH_L4_PAYLOAD;
+
+	ret = parse_flex_payload_cfg(res->payload_cfg, flxpld_cfg);
+	if (ret < 0) {
+		printf("fdir flexpayload parsing error: (%s)\n",
+			strerror(-ret));
+		rte_free(flxpld_cfg);
+		return;
+	}
+	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX;
+	fdir_cfg.cfg = flxpld_cfg;
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+				     RTE_ETH_FILTER_OP_SET, &fdir_cfg);
+	if (ret < 0)
+		printf("fdir flexpayload setting error: (%s)\n",
+			strerror(-ret));
+	rte_free(flxpld_cfg);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexpayload =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 flow_director_flexpayload,
+				 "flow_director_flex_payload");
+cmdline_parse_token_num_t cmd_flow_director_flexpayload_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_layer =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_layer, "l2#l3#l4");
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_cfg =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_cfg, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_payload = {
+	.f = cmd_flow_director_flxpld_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flexible payload on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexpayload,
+		(void *)&cmd_flow_director_flexpayload_port_id,
+		(void *)&cmd_flow_director_flexpayload_payload_layer,
+		(void *)&cmd_flow_director_flexpayload_payload_cfg,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8033,6 +8176,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 18/20] lib/librte_ether: define structures for configuring flex masks
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (16 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 17/20] app/test-pmd: add test command " Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 19/20] i40e: implement operations to configure flexible masks Jingjing Wu
                   ` (3 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

define structures for configuring flexible masks

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 24 ++++++++++++++++++++++++
 1 file changed, 24 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index e412471..13861c8 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -119,7 +119,28 @@ struct rte_eth_flex_payload_cfg {
 	struct rte_eth_field_vector field[0];
 };
 
+/**
+ * A structure defined to specify each word's bit mask
+ */
+struct rte_eth_flex_mask {
+	uint8_t offset;      /**< word offset of word in flexible payload */
+	uint16_t bitmask;    /**< bit mask for word defined by offset */
+};
+
+/**
+ * A structure used to configure FDIR masks for flexible payload
+ * for each flow type
+ */
+struct rte_eth_fdir_flex_masks {
+	enum rte_eth_flow_type flow_type;  /**< flow type */
+	uint8_t words_mask;  /**< bit i enables word i of 8 words flexible payload */
+	uint8_t nb_field;   /**< the number of folloing fieds */
+	struct rte_eth_flex_mask field[0];
+};
+
 #define RTE_ETH_FDIR_CFG_FLX      0x0001
+#define RTE_ETH_FDIR_CFG_MASK     0x0002
+#define RTE_ETH_FDIR_CFG_FLX_MASK 0x0003
 /**
  * A structure used to config FDIR filter global set
  * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_OP_SET operation.
@@ -129,9 +150,12 @@ struct rte_eth_fdir_cfg {
 	/**
 	 * A pointer to structure for the configuration e.g.
 	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
+	 * struct rte_fdir_masks mask for FDIR_MASK
+	 * struct rte_eth_fdir_flex_masks for FDIR_FLX_MASK
 	*/
 	void *cfg;
 };
+
 /**
  * A structure used to define the input for IPV4 UDP flow
  */
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 19/20] i40e: implement operations to configure flexible masks
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (17 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 18/20] lib/librte_ether: define structures for configuring flex masks Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command " Jingjing Wu
                   ` (2 subsequent siblings)
  21 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

implement operation to flexible masks for each flow type in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 121 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 121 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 01693a2..ddb436e 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -85,6 +85,8 @@
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
 static int i40e_set_flx_pld_cfg(struct i40e_pf *pf,
 			 struct rte_eth_flex_payload_cfg *cfg);
+static int i40e_set_fdir_flx_mask(struct i40e_pf *pf,
+			struct rte_eth_fdir_flex_masks *flex_masks);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -419,6 +421,122 @@ i40e_set_flx_pld_cfg(struct i40e_pf *pf,
 
 	return 0;
 }
+
+static inline void
+i40e_set_flex_mask_on_pctype(
+		struct i40e_hw *hw,
+		enum i40e_filter_pctype pctype,
+		struct rte_eth_fdir_flex_masks *flex_masks)
+{
+	uint32_t flxinset, mask;
+	int i;
+
+	flxinset = (flex_masks->words_mask <<
+		I40E_PRTQF_FD_FLXINSET_INSET_SHIFT) &
+		I40E_PRTQF_FD_FLXINSET_INSET_MASK;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), flxinset);
+
+	for (i = 0; i < flex_masks->nb_field; i++) {
+		mask = (flex_masks->field[i].bitmask <<
+			I40E_PRTQF_FD_MSK_MASK_SHIFT) &
+			I40E_PRTQF_FD_MSK_MASK_MASK;
+		mask |= ((flex_masks->field[i].offset +
+			I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+			I40E_PRTQF_FD_MSK_OFFSET_SHIFT) &
+			I40E_PRTQF_FD_MSK_OFFSET_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, i), mask);
+	}
+}
+
+/*
+ * i40e_set_fdir_flx_mask - configure the mask on flexible payload
+ */
+static int
+i40e_set_fdir_flx_mask(struct i40e_pf *pf,
+		struct rte_eth_fdir_flex_masks *flex_masks)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct rte_eth_fdir_info fdir;
+	int ret = 0;
+
+	if (flex_masks == NULL)
+		return -EINVAL;
+
+	if (flex_masks->nb_field > 2) {
+		PMD_DRV_LOG(ERR, "bit masks cannot support more than 2 words.");
+		return -EINVAL;
+	}
+	/*
+	 * flexible payload masks need to be configured before
+	 * flow director filters are added
+	 * If filters exist, flush them.
+	 */
+	memset(&fdir, 0, sizeof(fdir));
+	i40e_fdir_info_get(pf, &fdir);
+	if (fdir.info_ext.best_cnt + fdir.info_ext.guarant_cnt > 0) {
+		ret = i40e_fdir_flush(pf);
+		if (ret) {
+			PMD_DRV_LOG(ERR, " failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	switch (flex_masks->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		/* set mask for both NONF_IPV4 and FRAG_IPV4 PCTYPE*/
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+			flex_masks);
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_FRAG_IPV4,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+			flex_masks);
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		/* set mask for both NONF_IPV6 and FRAG_IPV6 PCTYPE*/
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+			flex_masks);
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_FRAG_IPV6,
+			flex_masks);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "invalid flow_type input.");
+		return -EINVAL;
+	}
+
+	return ret;
+}
+
 static int
 i40e_fdir_construct_pkt(struct i40e_pf *pf,
 			     struct rte_eth_fdir_input *fdir_input,
@@ -1068,6 +1186,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX)
 			ret = i40e_set_flx_pld_cfg(pf,
 				(struct rte_eth_flex_payload_cfg *)fdir_cfg->cfg);
+		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX_MASK)
+			ret = i40e_set_fdir_flx_mask(pf,
+				(struct rte_eth_fdir_flex_masks *)fdir_cfg->cfg);
 		break;
 	case RTE_ETH_FILTER_OP_GET_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command to configure flexible masks
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (18 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 19/20] i40e: implement operations to configure flexible masks Jingjing Wu
@ 2014-09-26  6:03 ` Jingjing Wu
  2014-10-13 15:58   ` De Lara Guarch, Pablo
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
  2014-10-30  7:12 ` [dpdk-dev] [PATCH v3 00/20] " Cao, Min
  21 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-09-26  6:03 UTC (permalink / raw)
  To: dev

add test command to configure flexible masks for each flow type

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
---
 app/test-pmd/cmdline.c | 173 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 173 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index da77752..073b929 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -690,6 +690,11 @@ static void cmd_help_long_parsed(void *parsed_result,
 			"flow_director_flex_payload (port_id)"
 			" (l2|l3|l4) (config)\n"
 			"    configure flexible payload selection.\n\n"
+
+			"flow_director_flex_mask (port_id)"
+			" flow (ether|ip4|tcp4|udp4|sctp4|ip6|tcp6|udp6|sctp6)"
+			" words_mask (words) (word_mask_list)"
+			"    configure masks of flexible payload.\n\n"
 		);
 	}
 }
@@ -8046,6 +8051,173 @@ cmdline_parse_inst_t cmd_set_flow_director_flex_payload = {
 	},
 };
 
+/* *** deal with flow director mask on flexible payload *** */
+struct cmd_flow_director_flex_mask_result {
+	cmdline_fixed_string_t flow_director_flexmask;
+	uint8_t port_id;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t words_mask;
+	uint8_t words;
+	cmdline_fixed_string_t word_mask_list;
+};
+
+static inline int
+parse_word_masks_cfg(const char *q_arg,
+			     struct rte_eth_fdir_flex_masks *masks)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	enum fieldnames {
+		FLD_OFFSET = 0,
+		FLD_MASK,
+		_NUM_FLD
+	};
+	unsigned long int_fld[_NUM_FLD];
+	char *str_fld[_NUM_FLD];
+	int i;
+	unsigned size;
+
+	masks->nb_field = 0;
+	p = strchr(p0, '(');
+	while (p != NULL) {
+		++p;
+		p0 = strchr(p, ')');
+		if (p0 == NULL)
+			return -1;
+
+		size = p0 - p;
+		if (size >= sizeof(s))
+			return -1;
+
+		snprintf(s, sizeof(s), "%.*s", size, p);
+		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') != _NUM_FLD)
+			return -1;
+		for (i = 0; i < _NUM_FLD; i++) {
+			errno = 0;
+			int_fld[i] = strtoul(str_fld[i], &end, 0);
+			if (errno != 0 || end == str_fld[i] || int_fld[i] > UINT16_MAX)
+				return -1;
+		}
+		masks->field[masks->nb_field].offset =
+			(uint16_t)int_fld[FLD_OFFSET];
+		masks->field[masks->nb_field].bitmask =
+			~(uint16_t)int_fld[FLD_MASK];
+		masks->nb_field++;
+		if (masks->nb_field > 2) {
+			printf("exceeded max number of fields: %hu\n",
+				masks->nb_field);
+			return -1;
+		}
+		p = strchr(p0, '(');
+	}
+	return 0;
+}
+
+static void
+cmd_flow_director_flex_mask_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flex_mask_result *res = parsed_result;
+	struct rte_eth_fdir_flex_masks *flex_masks;
+	struct rte_eth_fdir_cfg fdir_cfg;
+	int ret = 0;
+	int cfg_size = 2 * sizeof(struct rte_eth_flex_mask) +
+		  offsetof(struct rte_eth_fdir_flex_masks, field);
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
+
+	flex_masks = (struct rte_eth_fdir_flex_masks *)rte_zmalloc_socket("CLI",
+		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
+
+	if (flex_masks == NULL) {
+		printf("fail to malloc memory to configure flexi masks\n");
+		return;
+	}
+
+	if (!strcmp(res->flow_type, "ip4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_IPV4_OTHER;
+	else if (!strcmp(res->flow_type, "udp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
+	else if (!strcmp(res->flow_type, "tcp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
+	else if (!strcmp(res->flow_type, "sctp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
+	else if (!strcmp(res->flow_type, "ip6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_IPV6_OTHER;
+	else if (!strcmp(res->flow_type, "udp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
+	else if (!strcmp(res->flow_type, "tcp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
+	else if (!strcmp(res->flow_type, "sctp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
+
+	flex_masks->words_mask = res->words;
+	ret = parse_word_masks_cfg(res->word_mask_list, flex_masks);
+	if (ret < 0) {
+		printf("fdir flex masks error\n");
+		rte_free(flex_masks);
+		return;
+	}
+
+	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX_MASK;
+	fdir_cfg.cfg = flex_masks;
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+				     RTE_ETH_FILTER_OP_SET, &fdir_cfg);
+	if (ret < 0)
+		printf("fdir flex mask setting error: (%s)\n", strerror(-ret));
+	rte_free(flex_masks);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexmask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_director_flexmask,
+				 "flow_director_flex_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_type,
+				 "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_words_mask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 words_mask, "words_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_words =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      words, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_word_mask_list =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 word_mask_list, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_mask = {
+	.f = cmd_flow_director_flex_mask_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex masks on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexmask,
+		(void *)&cmd_flow_director_flexmask_port_id,
+		(void *)&cmd_flow_director_flexmask_flow,
+		(void *)&cmd_flow_director_flexmask_flow_type,
+		(void *)&cmd_flow_director_flexmask_words_mask,
+		(void *)&cmd_flow_director_flexmask_words,
+		(void *)&cmd_flow_director_flexmask_word_mask_list,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8177,6 +8349,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
 	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_mask,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command to configure flexible masks
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command " Jingjing Wu
@ 2014-10-13 15:58   ` De Lara Guarch, Pablo
  0 siblings, 0 replies; 123+ messages in thread
From: De Lara Guarch, Pablo @ 2014-10-13 15:58 UTC (permalink / raw)
  To: Wu, Jingjing, dev



> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Friday, September 26, 2014 7:04 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command to
> configure flexible masks
> 
> add test command to configure flexible masks for each flow type
> 
> Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
> Acked-by: Chen Jing D(Mark) <jing.d.chen@intel.com>
> Acked-by: Helin Zhang <helin.zhang@intel.com>
> ---
>  app/test-pmd/cmdline.c | 173
> +++++++++++++++++++++++++++++++++++++++++++++++++
>  1 file changed, 173 insertions(+)
> 
> diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
> index da77752..073b929 100644
> --- a/app/test-pmd/cmdline.c
> +++ b/app/test-pmd/cmdline.c
> @@ -690,6 +690,11 @@ static void cmd_help_long_parsed(void
> *parsed_result,
>  			"flow_director_flex_payload (port_id)"
>  			" (l2|l3|l4) (config)\n"
>  			"    configure flexible payload selection.\n\n"
> +
> +			"flow_director_flex_mask (port_id)"
> +			" flow
> (ether|ip4|tcp4|udp4|sctp4|ip6|tcp6|udp6|sctp6)"
> +			" words_mask (words) (word_mask_list)"
> +			"    configure masks of flexible payload.\n\n"
>  		);
>  	}
>  }
> @@ -8046,6 +8051,173 @@ cmdline_parse_inst_t
> cmd_set_flow_director_flex_payload = {
>  	},
>  };
> 
> +/* *** deal with flow director mask on flexible payload *** */
> +struct cmd_flow_director_flex_mask_result {
> +	cmdline_fixed_string_t flow_director_flexmask;
> +	uint8_t port_id;
> +	cmdline_fixed_string_t flow;
> +	cmdline_fixed_string_t flow_type;
> +	cmdline_fixed_string_t words_mask;
> +	uint8_t words;
> +	cmdline_fixed_string_t word_mask_list;
> +};
> +
> +static inline int
> +parse_word_masks_cfg(const char *q_arg,
> +			     struct rte_eth_fdir_flex_masks *masks)
> +{
> +	char s[256];
> +	const char *p, *p0 = q_arg;
> +	char *end;
> +	enum fieldnames {
> +		FLD_OFFSET = 0,
> +		FLD_MASK,
> +		_NUM_FLD
> +	};
> +	unsigned long int_fld[_NUM_FLD];
> +	char *str_fld[_NUM_FLD];
> +	int i;
> +	unsigned size;
> +
> +	masks->nb_field = 0;
> +	p = strchr(p0, '(');
> +	while (p != NULL) {
> +		++p;
> +		p0 = strchr(p, ')');
> +		if (p0 == NULL)
> +			return -1;
> +
> +		size = p0 - p;
> +		if (size >= sizeof(s))
> +			return -1;
> +
> +		snprintf(s, sizeof(s), "%.*s", size, p);
> +		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') !=
> _NUM_FLD)
> +			return -1;
> +		for (i = 0; i < _NUM_FLD; i++) {
> +			errno = 0;
> +			int_fld[i] = strtoul(str_fld[i], &end, 0);
> +			if (errno != 0 || end == str_fld[i] || int_fld[i] >
> UINT16_MAX)
> +				return -1;
> +		}
> +		masks->field[masks->nb_field].offset =
> +			(uint16_t)int_fld[FLD_OFFSET];
> +		masks->field[masks->nb_field].bitmask =
> +			~(uint16_t)int_fld[FLD_MASK];
> +		masks->nb_field++;
> +		if (masks->nb_field > 2) {
> +			printf("exceeded max number of fields: %hu\n",
> +				masks->nb_field);

masks->nb_field is an uint8_t, so you should change from %hu to %hhu or %PRIu8.

> +			return -1;
> +		}
> +		p = strchr(p0, '(');
> +	}
> +	return 0;
> +}
> +
> +static void
> +cmd_flow_director_flex_mask_parsed(void *parsed_result,
> +			  __attribute__((unused)) struct cmdline *cl,
> +			  __attribute__((unused)) void *data)
> +{
> +	struct cmd_flow_director_flex_mask_result *res = parsed_result;
> +	struct rte_eth_fdir_flex_masks *flex_masks;
> +	struct rte_eth_fdir_cfg fdir_cfg;
> +	int ret = 0;
> +	int cfg_size = 2 * sizeof(struct rte_eth_flex_mask) +
> +		  offsetof(struct rte_eth_fdir_flex_masks, field);
> +
> +	ret = rte_eth_dev_filter_supported(res->port_id,
> RTE_ETH_FILTER_FDIR);
> +	if (ret < 0) {
> +		printf("flow director is not supported on port %u.\n",
> +			res->port_id);
> +		return;
> +	}
> +
> +	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
> +
> +	flex_masks = (struct rte_eth_fdir_flex_masks
> *)rte_zmalloc_socket("CLI",
> +		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
> +
> +	if (flex_masks == NULL) {
> +		printf("fail to malloc memory to configure flexi masks\n");
> +		return;
> +	}
> +
> +	if (!strcmp(res->flow_type, "ip4"))
> +		flex_masks->flow_type =
> RTE_ETH_FLOW_TYPE_IPV4_OTHER;
> +	else if (!strcmp(res->flow_type, "udp4"))
> +		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
> +	else if (!strcmp(res->flow_type, "tcp4"))
> +		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
> +	else if (!strcmp(res->flow_type, "sctp4"))
> +		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
> +	else if (!strcmp(res->flow_type, "ip6"))
> +		flex_masks->flow_type =
> RTE_ETH_FLOW_TYPE_IPV6_OTHER;
> +	else if (!strcmp(res->flow_type, "udp6"))
> +		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
> +	else if (!strcmp(res->flow_type, "tcp6"))
> +		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
> +	else if (!strcmp(res->flow_type, "sctp6"))
> +		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
> +
> +	flex_masks->words_mask = res->words;
> +	ret = parse_word_masks_cfg(res->word_mask_list, flex_masks);
> +	if (ret < 0) {
> +		printf("fdir flex masks error\n");
> +		rte_free(flex_masks);
> +		return;
> +	}
> +
> +	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX_MASK;
> +	fdir_cfg.cfg = flex_masks;
> +	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
> +				     RTE_ETH_FILTER_OP_SET, &fdir_cfg);
> +	if (ret < 0)
> +		printf("fdir flex mask setting error: (%s)\n", strerror(-ret));
> +	rte_free(flex_masks);
> +}
> +
> +cmdline_parse_token_string_t cmd_flow_director_flexmask =
> +	TOKEN_STRING_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +				 flow_director_flexmask,
> +				 "flow_director_flex_mask");
> +cmdline_parse_token_num_t cmd_flow_director_flexmask_port_id =
> +	TOKEN_NUM_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +			      port_id, UINT8);
> +cmdline_parse_token_string_t cmd_flow_director_flexmask_flow =
> +	TOKEN_STRING_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +				 flow, "flow");
> +cmdline_parse_token_string_t cmd_flow_director_flexmask_flow_type =
> +	TOKEN_STRING_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +				 flow_type,
> +
> "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
> +cmdline_parse_token_string_t cmd_flow_director_flexmask_words_mask
> =
> +	TOKEN_STRING_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +				 words_mask, "words_mask");
> +cmdline_parse_token_num_t cmd_flow_director_flexmask_words =
> +	TOKEN_NUM_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +			      words, UINT8);
> +cmdline_parse_token_string_t
> cmd_flow_director_flexmask_word_mask_list =
> +	TOKEN_STRING_INITIALIZER(struct
> cmd_flow_director_flex_mask_result,
> +				 word_mask_list, NULL);
> +
> +cmdline_parse_inst_t cmd_set_flow_director_flex_mask = {
> +	.f = cmd_flow_director_flex_mask_parsed,
> +	.data = NULL,
> +	.help_str = "set flow director's flex masks on NIC",
> +	.tokens = {
> +		(void *)&cmd_flow_director_flexmask,
> +		(void *)&cmd_flow_director_flexmask_port_id,
> +		(void *)&cmd_flow_director_flexmask_flow,
> +		(void *)&cmd_flow_director_flexmask_flow_type,
> +		(void *)&cmd_flow_director_flexmask_words_mask,
> +		(void *)&cmd_flow_director_flexmask_words,
> +		(void *)&cmd_flow_director_flexmask_word_mask_list,
> +		NULL,
> +	},
> +};
> +
>  /*
> **********************************************************
> ********************** */
> 
>  /* list of instructions */
> @@ -8177,6 +8349,7 @@ cmdline_parse_ctx_t main_ctx[] = {
>  	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
>  	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
>  	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
> +	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_mask,
>  	NULL,
>  };
> 
> --
> 1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (19 preceding siblings ...)
  2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command " Jingjing Wu
@ 2014-10-22  1:01 ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 01/21] i40e: set up and initialize flow director Jingjing Wu
                     ` (25 more replies)
  2014-10-30  7:12 ` [dpdk-dev] [PATCH v3 00/20] " Cao, Min
  21 siblings, 26 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics, FD_ID report.
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison and flex bytes report.

v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 changes:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison 
 
v4 changes:
 - strip the filter APIs definitions from this patch set
 - extend mbuf field to support flex bytes report
 - fix typos

Jingjing Wu (21):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  ethdev: define structures for adding/deleting flow director
  i40e: implement operations to add/delete flow director
  testpmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  mbuf: extend fdir field
  i40e: report flow director match info to mbuf
  testpmd: print extended fdir info in mbuf
  ethdev: define structures for getting flow director information
  i40e: implement operations to get fdir info
  testpmd: display fdir statistics
  i40e: implement operation to flush flow director table
  testpmd: add test command to flush flow director table
  ethdev: define structures for configuring flexible payload
  i40e: implement operations to configure flexible payload
  testpmd: add test command to configure flexible payload
  ethdev:  define structures for configuring flex masks
  i40e: implement operations to configure flexible masks
  testpmd: add test command to configure flexible masks

 app/test-pmd/cmdline.c            |  812 ++++++++++++++++++++++++
 app/test-pmd/config.c             |   38 +-
 app/test-pmd/rxonly.c             |   14 +-
 app/test-pmd/testpmd.h            |    3 +
 lib/librte_ether/rte_eth_ctrl.h   |  266 ++++++++
 lib/librte_ether/rte_ethdev.h     |   23 -
 lib/librte_mbuf/rte_mbuf.h        |   12 +-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  127 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   34 +-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1222 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  225 ++++++-
 12 files changed, 2723 insertions(+), 55 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 01/21] i40e: set up and initialize flow director
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 02/21] i40e: tear down " Jingjing Wu
                     ` (24 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

set up fortville resources to support flow director, includes
 - queue 0 pair allocated and set up for flow director
 - create vsi
 - reserve memzone for flow director programming packet

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/Makefile      |   2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  79 +++++++++++---
 lib/librte_pmd_i40e/i40e_ethdev.h |  30 +++++-
 lib/librte_pmd_i40e/i40e_fdir.c   | 222 ++++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   | 127 ++++++++++++++++++++++
 5 files changed, 447 insertions(+), 13 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

diff --git a/lib/librte_pmd_i40e/Makefile b/lib/librte_pmd_i40e/Makefile
index bd3428f..98e4bdf 100644
--- a/lib/librte_pmd_i40e/Makefile
+++ b/lib/librte_pmd_i40e/Makefile
@@ -91,6 +91,8 @@ SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_rxtx.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev_vf.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_pf.c
+SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_fdir.c
+
 # this lib depends upon:
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_eal lib/librte_ether
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_mempool lib/librte_mbuf
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 3b75f0f..838dd1e 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -765,6 +765,12 @@ i40e_dev_start(struct rte_eth_dev *dev)
 	i40e_vsi_queues_bind_intr(vsi);
 	i40e_vsi_enable_queues_intr(vsi);
 
+	/* enable FDIR MSIX interrupt */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
+		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
+	}
+
 	/* Enable all queues which have been configured */
 	ret = i40e_vsi_switch_queues(vsi, TRUE);
 	if (ret != I40E_SUCCESS) {
@@ -2602,16 +2608,30 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	case I40E_VSI_SRIOV :
 		vsi->nb_qps = pf->vf_nb_qps;
 		break;
+	case I40E_VSI_FDIR:
+		vsi->nb_qps = pf->fdir_nb_qps;
+		break;
 	default:
 		goto fail_mem;
 	}
-	ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
-	if (ret < 0) {
-		PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
-				vsi->seid, ret);
-		goto fail_mem;
-	}
-	vsi->base_queue = ret;
+	/*
+	 * The filter status descriptor is reported in rx queue 0,
+	 * while the tx queue for fdir filter programming has no
+	 * such constraints, can be non-zero queues.
+	 * To simplify it, choose FDIR vsi use queue 0 pair.
+	 * To make sure it will use queue 0 pair, queue allocation
+	 * need be done before this function is called
+	 */
+	if (type != I40E_VSI_FDIR) {
+		ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
+			if (ret < 0) {
+				PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
+						vsi->seid, ret);
+				goto fail_mem;
+			}
+			vsi->base_queue = ret;
+	} else
+		vsi->base_queue = I40E_FDIR_QUEUE_ID;
 
 	/* VF has MSIX interrupt in VF range, don't allocate here */
 	if (type != I40E_VSI_SRIOV) {
@@ -2743,9 +2763,25 @@ i40e_vsi_setup(struct i40e_pf *pf,
 		 * Since VSI is not created yet, only configure parameter,
 		 * will add vsi below.
 		 */
-	}
-	else {
-		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet");
+	} else if (type == I40E_VSI_FDIR) {
+		vsi->uplink_seid = uplink_vsi->uplink_seid;
+		ctxt.pf_num = hw->pf_id;
+		ctxt.vf_num = 0;
+		ctxt.uplink_seid = vsi->uplink_seid;
+		ctxt.connection_type = 0x1;     /* regular data port */
+		ctxt.flags = I40E_AQ_VSI_TYPE_PF;
+		ret = i40e_vsi_config_tc_queue_mapping(vsi, &ctxt.info,
+						I40E_DEFAULT_TCMAP);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to configure "
+					"TC queue mapping\n");
+			goto fail_msix_alloc;
+		}
+		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
+		ctxt.info.valid_sections |=
+			rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
+	} else {
+		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet\n");
 		goto fail_msix_alloc;
 	}
 
@@ -2930,8 +2966,16 @@ i40e_pf_setup(struct i40e_pf *pf)
 		PMD_DRV_LOG(ERR, "Could not get switch config, err %d", ret);
 		return ret;
 	}
-
-	/* VSI setup */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		/* make queue allocated first, let FDIR use queue pair 0*/
+		ret = i40e_res_pool_alloc(&pf->qp_pool, I40E_DEFAULT_QP_NUM_FDIR);
+		if (ret != I40E_FDIR_QUEUE_ID) {
+			PMD_DRV_LOG(ERR, "queue allocation fails for FDIR :"
+				    " ret =%d", ret);
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+	/*  main VSI setup */
 	vsi = i40e_vsi_setup(pf, I40E_VSI_MAIN, NULL, 0);
 	if (!vsi) {
 		PMD_DRV_LOG(ERR, "Setup of main vsi failed");
@@ -2941,9 +2985,20 @@ i40e_pf_setup(struct i40e_pf *pf)
 	dev_data->nb_rx_queues = vsi->nb_qps;
 	dev_data->nb_tx_queues = vsi->nb_qps;
 
+	/* setup FDIR after main vsi created.*/
+	if (pf->flags & I40E_FLAG_FDIR) {
+		ret = i40e_fdir_setup(pf);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to setup flow director\n");
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+
 	/* Configure filter control */
 	memset(&settings, 0, sizeof(settings));
 	settings.hash_lut_size = I40E_HASH_LUT_SIZE_128;
+	if (pf->flags & I40E_FLAG_FDIR)
+		settings.enable_fdir = TRUE;
 	/* Enable ethtype and macvlan filters */
 	settings.enable_ethtype = TRUE;
 	settings.enable_macvlan = TRUE;
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 1d42cd2..327388b 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -46,11 +46,12 @@
 /* number of VSIs and queue default setting */
 #define I40E_MAX_QP_NUM_PER_VF    16
 #define I40E_DEFAULT_QP_NUM_VMDQ  64
-#define I40E_DEFAULT_QP_NUM_FDIR  64
+#define I40E_DEFAULT_QP_NUM_FDIR  1
 #define I40E_UINT32_BIT_SIZE      (CHAR_BIT * sizeof(uint32_t))
 #define I40E_VFTA_SIZE            (4096 / I40E_UINT32_BIT_SIZE)
 /* Default TC traffic in case DCB is not enabled */
 #define I40E_DEFAULT_TCMAP        0x1
+#define I40E_FDIR_QUEUE_ID        0
 
 /* i40e flags */
 #define I40E_FLAG_RSS                   (1ULL << 0)
@@ -219,6 +220,27 @@ struct i40e_pf_vf {
 };
 
 /*
+ *  A structure used to define fields of a FDIR related info.
+ */
+struct i40e_fdir_info {
+	struct i40e_vsi *fdir_vsi;     /* pointer to fdir VSI structure */
+	uint16_t match_counter_index;  /* Statistic counter index used for fdir*/
+	struct i40e_tx_queue *txq;
+	struct i40e_rx_queue *rxq;
+	void *prg_pkt;                 /* memory for fdir program packet */
+	uint64_t dma_addr;             /* physic address of packet memory*/
+	/*
+	 * the rule how bytes stream is extracted as flexible payload
+	 * for each payload layer, the setting can up to three elements
+	 */
+	struct {
+		uint8_t offset;        /* offset in words from the beginning of payload */
+		uint8_t size;          /* size in words */
+	} flex_set[3][3];
+
+};
+
+/*
  * Structure to store private data specific for PF instance.
  */
 struct i40e_pf {
@@ -246,6 +268,7 @@ struct i40e_pf {
 	uint16_t vmdq_nb_qps; /* The number of queue pairs of VMDq */
 	uint16_t vf_nb_qps; /* The number of queue pairs of VF */
 	uint16_t fdir_nb_qps; /* The number of queue pairs of Flow Director */
+	struct i40e_fdir_info fdir; /* flow director info */
 };
 
 enum pending_msg {
@@ -346,6 +369,11 @@ int i40e_vsi_vlan_pvid_set(struct i40e_vsi *vsi,
 int i40e_vsi_config_vlan_stripping(struct i40e_vsi *vsi, bool on);
 uint64_t i40e_config_hena(uint64_t flags);
 uint64_t i40e_parse_hena(uint64_t flags);
+enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+int i40e_fdir_setup(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
new file mode 100644
index 0000000..a44bb73
--- /dev/null
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -0,0 +1,222 @@
+/*-
+ *   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 <sys/queue.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdint.h>
+#include <string.h>
+#include <unistd.h>
+#include <stdarg.h>
+
+#include <rte_ether.h>
+#include <rte_ethdev.h>
+#include <rte_log.h>
+#include <rte_memzone.h>
+#include <rte_malloc.h>
+
+#include "i40e_logs.h"
+#include "i40e/i40e_type.h"
+#include "i40e_ethdev.h"
+#include "i40e_rxtx.h"
+
+#define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#define I40E_FDIR_PKT_LEN                   512
+
+#define I40E_COUNTER_PF           2
+/* Statistic counter index for one pf */
+#define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+#define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
+
+static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+
+static int
+i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
+{
+	struct i40e_hw *hw = I40E_VSI_TO_HW(rxq->vsi);
+	struct i40e_hmc_obj_rxq rx_ctx;
+	int err = I40E_SUCCESS;
+
+	memset(&rx_ctx, 0, sizeof(struct i40e_hmc_obj_rxq));
+	/* Init the RX queue in hardware */
+	rx_ctx.dbuff = I40E_RXBUF_SZ_1024 >> I40E_RXQ_CTX_DBUFF_SHIFT;
+	rx_ctx.hbuff = 0;
+	rx_ctx.base = rxq->rx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
+	rx_ctx.qlen = rxq->nb_rx_desc;
+#ifndef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+	rx_ctx.dsize = 1;
+#endif
+	rx_ctx.dtype = i40e_header_split_none;
+	rx_ctx.hsplit_0 = I40E_HEADER_SPLIT_NONE;
+	rx_ctx.rxmax = ETHER_MAX_LEN;
+	rx_ctx.tphrdesc_ena = 1;
+	rx_ctx.tphwdesc_ena = 1;
+	rx_ctx.tphdata_ena = 1;
+	rx_ctx.tphhead_ena = 1;
+	rx_ctx.lrxqthresh = 2;
+	rx_ctx.crcstrip = 0;
+	rx_ctx.l2tsel = 1;
+	rx_ctx.showiv = 1;
+	rx_ctx.prefena = 1;
+
+	err = i40e_clear_lan_rx_queue_context(hw, rxq->reg_idx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to clear FDIR RX queue context.");
+		return err;
+	}
+	err = i40e_set_lan_rx_queue_context(hw, rxq->reg_idx, &rx_ctx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to set FDIR RX queue context.");
+		return err;
+	}
+	rxq->qrx_tail = hw->hw_addr +
+		I40E_QRX_TAIL(rxq->vsi->base_queue);
+
+	rte_wmb();
+	/* Init the RX tail regieter. */
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, 0);
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, rxq->nb_rx_desc - 1);
+
+	return err;
+}
+
+/*
+ * i40e_fdir_setup - reserve and initialize the Flow Director resources
+ * @pf: board private structure
+ */
+int
+i40e_fdir_setup(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_vsi *vsi;
+	int err = I40E_SUCCESS;
+	char z_name[RTE_MEMZONE_NAMESIZE];
+	const struct rte_memzone *mz = NULL;
+	struct rte_eth_dev *eth_dev = pf->adapter->eth_dev;
+
+	PMD_DRV_LOG(INFO, "FDIR HW Capabilities: num_filters_guaranteed = %u,"
+			" num_filters_best_effort = %u.",
+			hw->func_caps.fd_filters_guaranteed,
+			hw->func_caps.fd_filters_best_effort);
+
+	vsi = pf->fdir.fdir_vsi;
+	if (vsi) {
+		PMD_DRV_LOG(ERR, "FDIR vsi pointer needs"
+				 "to be null before creation.");
+		return I40E_ERR_BAD_PTR;
+	}
+	/* make new FDIR VSI */
+	vsi = i40e_vsi_setup(pf, I40E_VSI_FDIR, pf->main_vsi, 0);
+	if (!vsi) {
+		PMD_DRV_LOG(ERR, "Couldn't create FDIR VSI.");
+		return I40E_ERR_NO_AVAILABLE_VSI;
+	}
+	pf->fdir.fdir_vsi = vsi;
+
+	/*Fdir tx queue setup*/
+	err = i40e_fdir_setup_tx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR TX resources.");
+		goto fail_setup_tx;
+	}
+
+	/*Fdir rx queue setup*/
+	err = i40e_fdir_setup_rx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR RX resources.");
+		goto fail_setup_rx;
+	}
+
+	err = i40e_tx_queue_init(pf->fdir.txq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR TX initialization.");
+		goto fail_mem;
+	}
+
+	/* need switch on before dev start*/
+	err = i40e_switch_tx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do fdir TX switch on.");
+		goto fail_mem;
+	}
+
+	/* Init the rx queue in hardware */
+	err = i40e_fdir_rx_queue_init(pf->fdir.rxq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX initialization.");
+		goto fail_mem;
+	}
+
+	/* switch on rx queue */
+	err = i40e_switch_rx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX switch on.");
+		goto fail_mem;
+	}
+
+	/* reserve memory for the fdir programming packet */
+	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
+			eth_dev->driver->pci_drv.name,
+			I40E_FDIR_MZ_NAME,
+			eth_dev->data->port_id);
+	mz = rte_memzone_lookup(z_name);
+	if (!mz) {
+		mz = rte_memzone_reserve(z_name,
+				I40E_FDIR_PKT_LEN,
+				rte_socket_id(),
+				0);
+		if (!mz) {
+			PMD_DRV_LOG(ERR, "Cannot init memzone for"
+				"flow director program packet.");
+			err = I40E_ERR_NO_MEMORY;
+			goto fail_mem;
+		}
+	}
+	pf->fdir.prg_pkt = mz->addr;
+	pf->fdir.dma_addr = (uint64_t)mz->phys_addr;
+	pf->fdir.match_counter_index = I40E_COUNTER_INDEX_FDIR(hw->pf_id);
+	PMD_DRV_LOG(INFO, "FDIR setup successfully, with programming queue %u.",
+		    vsi->base_queue);
+	return I40E_SUCCESS;
+
+fail_mem:
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+fail_setup_rx:
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+fail_setup_tx:
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return err;
+}
\ No newline at end of file
diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 2b53677..1017e3f 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -2107,6 +2107,8 @@ i40e_tx_queue_init(struct i40e_tx_queue *txq)
 	tx_ctx.base = txq->tx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
 	tx_ctx.qlen = txq->nb_tx_desc;
 	tx_ctx.rdylist = rte_le_to_cpu_16(vsi->info.qs_handle[0]);
+	if (vsi->type == I40E_VSI_FDIR)
+		tx_ctx.fd_ena = TRUE;
 
 	err = i40e_clear_lan_tx_queue_context(hw, pf_q);
 	if (err != I40E_SUCCESS) {
@@ -2323,3 +2325,128 @@ i40e_dev_clear_queues(struct rte_eth_dev *dev)
 		i40e_reset_rx_queue(dev->data->rx_queues[i]);
 	}
 }
+
+enum i40e_status_code
+i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_tx_queue *txq;
+	const struct rte_memzone *tz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_TX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	txq = rte_zmalloc_socket("i40e fdir tx queue",
+				  sizeof(struct i40e_tx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!txq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"tx queue structure\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(struct i40e_tx_desc) * I40E_FDIR_NUM_TX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	tz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_tx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!tz) {
+		i40e_dev_tx_queue_release(txq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for TX\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	txq->nb_tx_desc = I40E_FDIR_NUM_TX_DESC;
+	txq->queue_id = I40E_FDIR_QUEUE_ID;
+	txq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	txq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	txq->tx_ring_phys_addr = rte_mem_phy2mch(tz->memseg_id, tz->phys_addr);
+#else
+	txq->tx_ring_phys_addr = (uint64_t)tz->phys_addr;
+#endif
+	txq->tx_ring = (struct i40e_tx_desc *)tz->addr;
+	/*
+	 * don't need to allocate software ring and reset for the fdir
+	 * program queue just set the queue has been configured.
+	 */
+	txq->q_set = TRUE;
+	pf->fdir.txq = txq;
+
+	return I40E_SUCCESS;
+}
+
+enum i40e_status_code
+i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_rx_queue *rxq;
+	const struct rte_memzone *rz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_RX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	rxq = rte_zmalloc_socket("i40e fdir rx queue",
+				  sizeof(struct i40e_rx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!rxq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"rx queue structure\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(union i40e_rx_desc) * I40E_FDIR_NUM_RX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	rz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_rx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!rz) {
+		i40e_dev_rx_queue_release(rxq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for RX\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	rxq->nb_rx_desc = I40E_FDIR_NUM_RX_DESC;
+	rxq->queue_id = I40E_FDIR_QUEUE_ID;
+	rxq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	rxq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	rxq->rx_ring_phys_addr = rte_mem_phy2mch(rz->memseg_id, rz->phys_addr);
+#else
+	rxq->rx_ring_phys_addr = (uint64_t)rz->phys_addr;
+#endif
+	rxq->rx_ring = (union i40e_rx_desc *)rz->addr;
+
+	/*
+	 * Don't need to allocate software ring and reset for the fdir
+	 * rx queue, just set the queue has been configured.
+	 */
+	rxq->q_set = TRUE;
+	pf->fdir.rxq = rxq;
+
+	return I40E_SUCCESS;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 02/21] i40e: tear down flow director
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 01/21] i40e: set up and initialize flow director Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 03/21] i40e: initialize flexible payload setting Jingjing Wu
                     ` (23 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

release fortville resources on flow director, includes
 - queue 0 pair release
 - release vsi

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  4 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |  1 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 19 +++++++++++++++++++
 3 files changed, 23 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 838dd1e..0054a1e 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -508,7 +508,8 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 	return 0;
 
 err_setup_pf_switch:
-	rte_free(pf->main_vsi);
+	i40e_fdir_teardown(pf);
+	i40e_vsi_release(pf->main_vsi);
 err_get_mac_addr:
 err_configure_lan_hmc:
 	(void)i40e_shutdown_lan_hmc(hw);
@@ -836,6 +837,7 @@ i40e_dev_close(struct rte_eth_dev *dev)
 	i40e_shutdown_lan_hmc(hw);
 
 	/* release all the existing VSIs and VEBs */
+	i40e_fdir_teardown(pf);
 	i40e_vsi_release(pf->main_vsi);
 
 	/* shutdown the adminq */
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 327388b..d998980 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -374,6 +374,7 @@ enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
 enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
+void i40e_fdir_teardown(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index a44bb73..bb474d2 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -219,4 +219,23 @@ fail_setup_tx:
 	i40e_vsi_release(vsi);
 	pf->fdir.fdir_vsi = NULL;
 	return err;
+}
+
+/*
+ * i40e_fdir_teardown - release the Flow Director resources
+ * @pf: board private structure
+ */
+void
+i40e_fdir_teardown(struct i40e_pf *pf)
+{
+	struct i40e_vsi *vsi;
+
+	vsi = pf->fdir.fdir_vsi;
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return;
 }
\ No newline at end of file
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 03/21] i40e: initialize flexible payload setting
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 01/21] i40e: set up and initialize flow director Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 02/21] i40e: tear down " Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
                     ` (22 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

set flexible payload related registers to default value at initialization time.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 33 +++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_fdir.c   | 51 ++++++++++++++++++++++++++++++++++++++-
 2 files changed, 83 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 0054a1e..59a4b6a 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -322,6 +322,32 @@ static struct rte_driver rte_i40e_driver = {
 
 PMD_REGISTER_DRIVER(rte_i40e_driver);
 
+/*
+ * Initialize registers for flexible payload, which should be set by NVM.
+ * This should be removed from code once is fixed in NVM.
+ */
+static inline void i40e_flex_payload_reg_init(struct i40e_hw *hw)
+{
+	/* GLQF_ORT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(18), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(19), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(26), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(30), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(33), 0x000000E0);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(34), 0x000000E3);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(35), 0x000000E6);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(20), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(23), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(63), 0x0000002D);
+
+	/* GLQF_PIT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(16), 0x00007480);
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(17), 0x00007440);
+
+	/* GL_PRS_FVBM Registers */
+	I40E_WRITE_REG(hw, I40E_GL_PRS_FVBM(1), 0x8000035B);
+}
+
 static int
 eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
                   struct rte_eth_dev *dev)
@@ -385,6 +411,13 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 		return ret;
 	}
 
+	/*
+	 * To work around the NVM issue,initialize registers
+	 * for flexible payload by software.
+	 * It should be removed once issues are fixed in NVM.
+	 */
+	i40e_flex_payload_reg_init(hw);
+
 	/* Initialize the parameters for adminq */
 	i40e_init_adminq_parameter(hw);
 	ret = i40e_init_adminq(hw);
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index bb474d2..848fb92 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -111,6 +111,53 @@ i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
 }
 
 /*
+ * Initialize the configuration about bytes stream extracted as flexible payload
+ * and mask setting
+ */
+static inline void
+i40e_init_flx_pld(struct i40e_pf *pf)
+{
+	uint8_t pctype;
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+
+	/*
+	 * Define the bytes stream extracted as flexible payload in
+	 * field vector. By default, select 8 words from the beginning
+	 * of payload as flexible payload.
+	 */
+	memset(pf->fdir.flex_set, 0, sizeof(pf->fdir.flex_set));
+
+	/* initialize the flexible payload for L2 payload*/
+	pf->fdir.flex_set[0][0].offset = 0;
+	pf->fdir.flex_set[0][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(0), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(1), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(2), 0x0000FC2A);/*non-used*/
+
+	/* initialize the flexible payload for L3 payload*/
+	pf->fdir.flex_set[1][0].offset = 0;
+	pf->fdir.flex_set[1][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(3), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(4), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(5), 0x0000FC2A);/*non-used*/
+
+	/* initialize the flexible payload for L4 payload*/
+	pf->fdir.flex_set[2][0].offset = 0;
+	pf->fdir.flex_set[2][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(6), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(7), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(8), 0x0000FC2A);/*non-used*/
+
+	/* initialize the masks */
+	for (pctype = I40E_FILTER_PCTYPE_NONF_IPV4_UDP;
+	     pctype <= I40E_FILTER_PCTYPE_FRAG_IPV6; pctype++) {
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), 0);
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, 0), 0);
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, 1), 0);
+	}
+}
+
+/*
  * i40e_fdir_setup - reserve and initialize the Flow Director resources
  * @pf: board private structure
  */
@@ -184,6 +231,8 @@ i40e_fdir_setup(struct i40e_pf *pf)
 		goto fail_mem;
 	}
 
+	i40e_init_flx_pld(pf);
+
 	/* reserve memory for the fdir programming packet */
 	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
 			eth_dev->driver->pci_drv.name,
@@ -238,4 +287,4 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 	i40e_vsi_release(vsi);
 	pf->fdir.fdir_vsi = NULL;
 	return;
-}
\ No newline at end of file
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (2 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 03/21] i40e: initialize flexible payload setting Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-27 16:57     ` Thomas Monjalon
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 05/21] i40e: implement operations to add/delete " Jingjing Wu
                     ` (21 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

define structures to add or delete flow director filter

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 160 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 160 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index df21ac6..3efdaae 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -51,6 +51,7 @@ extern "C" {
  */
 enum rte_filter_type {
 	RTE_ETH_FILTER_NONE = 0,
+	RTE_ETH_FILTER_FDIR,
 	RTE_ETH_FILTER_MAX
 };
 
@@ -71,6 +72,165 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_OP_MAX
 };
 
+/**
+ * Define all structures for Flow Director Filter type corresponding with specific operations.
+ */
+
+/**
+ * flow type
+ */
+enum rte_eth_flow_type {
+	RTE_ETH_FLOW_TYPE_NONE = 0x0,
+	RTE_ETH_FLOW_TYPE_UDPV4,
+	RTE_ETH_FLOW_TYPE_TCPV4,
+	RTE_ETH_FLOW_TYPE_SCTPV4,
+	RTE_ETH_FLOW_TYPE_IPV4_OTHER,
+	RTE_ETH_FLOW_TYPE_UDPV6,
+	RTE_ETH_FLOW_TYPE_TCPV6,
+	RTE_ETH_FLOW_TYPE_SCTPV6,
+	RTE_ETH_FLOW_TYPE_IPV6_OTHER,
+};
+
+/**
+ * A structure used to define the input for IPV4 UDP flow
+ */
+struct rte_eth_udpv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+	uint16_t src_port;    /**< UDP Source port to match. */
+	uint16_t dst_port;    /**< UDP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 TCP flow
+ */
+struct rte_eth_tcpv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+	uint16_t src_port;    /**< TCP Source port to match. */
+	uint16_t dst_port;    /**< TCP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 SCTP flow
+ */
+struct rte_eth_sctpv4_flow {
+	uint32_t src_ip;          /**< IPv4 source address to match. */
+	uint32_t dst_ip;          /**< IPv4 destination address to match. */
+	uint32_t verify_tag;      /**< verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV4 flow
+ */
+struct rte_eth_ipv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 UDP flow
+ */
+struct rte_eth_udpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint16_t src_port;       /**< UDP Source port to match. */
+	uint16_t dst_port;       /**< UDP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 TCP flow
+ */
+struct rte_eth_tcpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint16_t src_port;       /**< TCP Source port to match. */
+	uint16_t dst_port;       /**< TCP Destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 SCTP flow
+ */
+struct rte_eth_sctpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint32_t verify_tag;     /**< verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV6 flow
+ */
+struct rte_eth_ipv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+};
+
+/**
+ * An union contains the inputs for all types of flow
+ */
+union rte_eth_fdir_flow {
+	struct rte_eth_udpv4_flow  udp4_flow;
+	struct rte_eth_tcpv4_flow  tcp4_flow;
+	struct rte_eth_sctpv4_flow sctp4_flow;
+	struct rte_eth_ipv4_flow   ip4_flow;
+	struct rte_eth_udpv6_flow  udp6_flow;
+	struct rte_eth_tcpv6_flow  tcp6_flow;
+	struct rte_eth_sctpv6_flow sctp6_flow;
+	struct rte_eth_ipv6_flow   ip6_flow;
+};
+
+#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
+/**
+ * A structure used to contain extend input of flow
+ */
+struct rte_eth_fdir_flow_ext {
+	uint16_t vlan_tci;
+	uint8_t num_flexwords;         /**< number of flexwords */
+	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
+	uint16_t dest_id;              /**< destination vsi or pool id*/
+};
+
+/**
+ * A structure used to define the input for an flow director filter entry
+ */
+struct rte_eth_fdir_input {
+	enum rte_eth_flow_type flow_type;      /**< type of flow */
+	union rte_eth_fdir_flow flow;          /**< specific flow structure */
+	struct rte_eth_fdir_flow_ext flow_ext; /**< specific flow info */
+};
+
+/**
+ * Flow director report status
+ */
+enum rte_eth_fdir_status {
+	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< no report FDIR. */
+	RTE_ETH_FDIR_REPORT_FD_ID,         /**< only report FD ID. */
+	RTE_ETH_FDIR_REPORT_FD_ID_FLEX_4,  /**< report FD ID and 4 flex bytes. */
+	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< report 8 flex bytes. */
+};
+
+/**
+ * A structure used to define an action when match FDIR packet filter.
+ */
+struct rte_eth_fdir_action {
+	uint16_t rx_queue;        /**< queue assigned to if fdir match. */
+	uint16_t cnt_idx;         /**< statistic counter index */
+	uint8_t  drop;            /**< accept or reject */
+	uint8_t  flex_off;        /**< offset used define words to report */
+	enum rte_eth_fdir_status report_status;  /**< status report option */
+};
+
+/**
+ * A structure used to define the flow director filter entry by filter_ctl API
+ * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
+ * RTE_ETH_FILTER_DELETE operations.
+ */
+struct rte_eth_fdir_filter {
+	uint32_t soft_id;                   /**< id */
+	struct rte_eth_fdir_input input;    /**< input set */
+	struct rte_eth_fdir_action action;  /**< action taken when match */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 05/21] i40e: implement operations to add/delete flow director
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (3 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
                     ` (20 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

deal with two operations for flow director
 - RTE_ETH_FILTER_ADD
 - RTE_ETH_FILTER_DELETE
encode the flow inputs to programming packet
sent the packet to filter programming queue and check status on the status report queue

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |   6 +-
 lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 622 ++++++++++++++++++++++++++++++++++++++
 3 files changed, 629 insertions(+), 2 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 59a4b6a..f56a4f6 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -4241,14 +4241,16 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 		     enum rte_filter_op filter_op,
 		     void *arg)
 {
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
 	int ret = 0;
-	(void)filter_op;
-	(void)arg;
 
 	if (dev == NULL)
 		return -EINVAL;
 
 	switch (filter_type) {
+	case RTE_ETH_FILTER_FDIR:
+		ret = i40e_fdir_ctrl_func(pf, filter_op, arg);
+		break;
 	default:
 		PMD_DRV_LOG(WARNING, "Filter type (%d) not supported",
 							filter_type);
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index d998980..a20c00e 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -375,6 +375,9 @@ enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
 void i40e_fdir_teardown(struct i40e_pf *pf);
+int i40e_fdir_ctrl_func(struct i40e_pf *pf,
+			  enum rte_filter_op filter_op,
+			  void *arg);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 848fb92..8996a1c 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -44,6 +44,10 @@
 #include <rte_log.h>
 #include <rte_memzone.h>
 #include <rte_malloc.h>
+#include <rte_ip.h>
+#include <rte_udp.h>
+#include <rte_tcp.h>
+#include <rte_sctp.h>
 
 #include "i40e_logs.h"
 #include "i40e/i40e_type.h"
@@ -51,7 +55,23 @@
 #include "i40e_rxtx.h"
 
 #define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#ifndef IPV6_ADDR_LEN
+#define IPV6_ADDR_LEN              16
+#endif
+
 #define I40E_FDIR_PKT_LEN                   512
+#define I40E_FDIR_IP_DEFAULT_LEN            420
+#define I40E_FDIR_IP_DEFAULT_TTL            0x40
+#define I40E_FDIR_IP_DEFAULT_VERSION_IHL    0x45
+#define I40E_FDIR_TCP_DEFAULT_DATAOFF       0x50
+#define I40E_FDIR_IPv6_DEFAULT_VTC_FLOW     0x60300000
+#define I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS   0xFF
+#define I40E_FDIR_IPv6_PAYLOAD_LEN          380
+#define I40E_FDIR_UDP_DEFAULT_LEN           400
+
+/* Wait count and inteval for fdir filter programming */
+#define I40E_FDIR_WAIT_COUNT       10
+#define I40E_FDIR_WAIT_INTERVAL_US 1000
 
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
@@ -59,6 +79,16 @@
 #define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
+				     struct rte_eth_fdir_input *fdir_input,
+				     unsigned char *raw_pkt);
+static int i40e_add_del_fdir_filter(struct i40e_pf *pf,
+			    struct rte_eth_fdir_filter *filter,
+			    bool add);
+static int i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			struct rte_eth_fdir_filter *filter,
+			bool add);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -288,3 +318,595 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 	pf->fdir.fdir_vsi = NULL;
 	return;
 }
+
+/*
+ * i40e_fdir_construct_pkt - construct packet based on fields in input
+ * @pf: board private structure
+ * @fdir_input: input set of the flow director entry
+ * @raw_pkt: a packet to be constructed
+ */
+static int
+i40e_fdir_construct_pkt(struct i40e_pf *pf,
+			     struct rte_eth_fdir_input *fdir_input,
+			     unsigned char *raw_pkt)
+{
+	struct ether_hdr *ether;
+	unsigned char *payload;
+	struct ipv4_hdr *ip;
+	struct ipv6_hdr *ip6;
+	struct udp_hdr *udp;
+	struct tcp_hdr *tcp;
+	struct sctp_hdr *sctp;
+	uint8_t size = 0;
+	int i, set_idx = 2; /* set_idx = 2 means using l4 pyload by default*/
+
+	switch (fdir_input->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct udp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		/* set len to by default */
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.udp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.udp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_UDP;
+		udp->src_port = fdir_input->flow.udp4_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp4_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_UDP_DEFAULT_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct tcp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.tcp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.tcp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_TCP;
+		tcp->src_port = fdir_input->flow.tcp4_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.tcp4_flow.src_port;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct sctp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.sctp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.sctp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_SCTP;
+		sctp->tag = fdir_input->flow.sctp4_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+		ip->next_proto_id = IPPROTO_IP;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.ip4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.ip4_flow.src_ip;
+		set_idx = 1; /* l3 pyload */
+		break;
+
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr) + sizeof(struct udp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.udp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.udp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_UDP;
+		udp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv6_hdr) + sizeof(struct tcp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.tcp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.tcp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_TCP;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		tcp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr) + sizeof(struct sctp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.sctp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.sctp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_SCTP;
+		sctp->tag = fdir_input->flow.sctp6_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) + sizeof(struct ipv6_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->proto = IPPROTO_NONE;
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.ip6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.ip6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		set_idx = 1; /* l3 pyload */
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown flow type %u.", fdir_input->flow_type);
+		return -EINVAL;
+	}
+
+	for (i = 0; i < 3; i++) {
+		if (pf->fdir.flex_set[set_idx][i].size == 0)
+			break;
+		(void)rte_memcpy(payload + 2 * pf->fdir.flex_set[set_idx][i].offset,
+				 fdir_input->flow_ext.flexwords + size,
+				 2 * pf->fdir.flex_set[set_idx][i].size);
+		size = pf->fdir.flex_set[set_idx][i].size;
+	}
+	return 0;
+}
+
+/* Construct the tx flags */
+static inline uint64_t
+i40e_build_ctob(uint32_t td_cmd,
+		uint32_t td_offset,
+		unsigned int size,
+		uint32_t td_tag)
+{
+	return rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DATA |
+			((uint64_t)td_cmd  << I40E_TXD_QW1_CMD_SHIFT) |
+			((uint64_t)td_offset << I40E_TXD_QW1_OFFSET_SHIFT) |
+			((uint64_t)size  << I40E_TXD_QW1_TX_BUF_SZ_SHIFT) |
+			((uint64_t)td_tag  << I40E_TXD_QW1_L2TAG1_SHIFT));
+}
+
+/*
+ * check the programming status descriptor in rx queue.
+ * done after Programming Flow Director is programmed on
+ * tx queue
+ */
+static inline int
+i40e_check_fdir_programming_status(struct i40e_rx_queue *rxq)
+{
+	volatile union i40e_rx_desc *rxdp;
+	uint64_t qword1;
+	uint32_t rx_status;
+	uint32_t len, id;
+	uint32_t error;
+	int ret = 0;
+
+	rxdp = &rxq->rx_ring[rxq->rx_tail];
+	qword1 = rte_le_to_cpu_64(rxdp->wb.qword1.status_error_len);
+	rx_status = (qword1 & I40E_RXD_QW1_STATUS_MASK)
+			>> I40E_RXD_QW1_STATUS_SHIFT;
+
+	if (rx_status & (1 << I40E_RX_DESC_STATUS_DD_SHIFT)) {
+		len = qword1 >> I40E_RX_PROG_STATUS_DESC_LENGTH_SHIFT;
+		id = (qword1 & I40E_RX_PROG_STATUS_DESC_QW1_PROGID_MASK) >>
+			    I40E_RX_PROG_STATUS_DESC_QW1_PROGID_SHIFT;
+
+		if (len  == I40E_RX_PROG_STATUS_DESC_LENGTH &&
+		    id == I40E_RX_PROG_STATUS_DESC_FD_FILTER_STATUS) {
+			error = (qword1 &
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_MASK) >>
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_SHIFT;
+			if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_FD_TBL_FULL_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to add FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_NO_FD_ENTRY_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to delete FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else
+				PMD_DRV_LOG(ERR, "invalid programming status"
+					    " reported, error = %u.", error);
+		} else
+			PMD_DRV_LOG(ERR, "unknown programming status"
+				    " reported, len = %d, id = %u.", len, id);
+		rxdp->wb.qword1.status_error_len = 0;
+		rxq->rx_tail++;
+		if (unlikely(rxq->rx_tail == rxq->nb_rx_desc))
+			rxq->rx_tail = 0;
+	}
+	return ret;
+}
+
+/*
+ * i40e_add_del_fdir_filter - add or remove a flow diretor filter.
+ * @pf: board private structure
+ * @filter: fdir filter entry
+ * @add: 0 - delelet, 1 - add
+ */
+static int
+i40e_add_del_fdir_filter(struct i40e_pf *pf,
+			    struct rte_eth_fdir_filter *filter,
+			    bool add)
+{
+	int ret = 0;
+	unsigned char *pkt = (unsigned char *)pf->fdir.prg_pkt;
+
+	if (!(pf->flags & I40E_FLAG_FDIR)) {
+		PMD_DRV_LOG(ERR, "FDIR is not enabled.");
+		return -ENOTSUP;
+	}
+
+	memset(pkt, 0, I40E_FDIR_PKT_LEN);
+
+	ret = i40e_fdir_construct_pkt(pf, &filter->input, pkt);
+	if (ret < 0) {
+		PMD_DRV_LOG(ERR, "construct packet for fdir fails.");
+		return ret;
+	}
+
+	switch (filter->input.flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_UDP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_TCP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_SCTP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		/* program on both NONF_IPV4 and FRAG_IPV4 PCTYPE*/
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_OTHER fdir programming fails.");
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_FRAG_IPV4,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_FRAG_IPV4 fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_UDP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_TCP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_SCTP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		/* program on both NONF_IPV6 and FRAG_IPV6 PCTYPE*/
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_OTHER fdir programming fails.");
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_FRAG_IPV6,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_FRAG_IPV6 fdir programming fails.");
+		break;
+	default:
+		PMD_DRV_LOG(ERR, " invalid flow_type input.");
+		ret = -EINVAL;
+	}
+	return ret;
+}
+
+/*
+ * i40e_fdir_filter_programming - Program a flow diretor filter rule.
+ * Is done by Flow Director Programming Descriptor followed by packet
+ * structure that contains the filter fields need to match.
+ * @pf: board private structure
+ * @pctype: pctype
+ * @filter: fdir filter entry
+ * @add: 0 - delelet, 1 - add
+ */
+static int
+i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			struct rte_eth_fdir_filter *filter,
+			bool add)
+{
+	struct i40e_tx_queue *txq = pf->fdir.txq;
+	struct i40e_rx_queue *rxq = pf->fdir.rxq;
+	struct rte_eth_fdir_input *fdir_input = &filter->input;
+	struct rte_eth_fdir_action *fdir_action = &filter->action;
+	volatile struct i40e_tx_desc *txdp;
+	volatile struct i40e_filter_program_desc *fdirdp;
+	uint32_t td_cmd;
+	uint16_t i;
+	uint8_t dest;
+
+	PMD_DRV_LOG(INFO, "filling filter programming descriptor.");
+	fdirdp = (volatile struct i40e_filter_program_desc *)
+			(&(txq->tx_ring[txq->tx_tail]));
+
+	fdirdp->qindex_flex_ptype_vsi =
+			rte_cpu_to_le_32((fdir_action->rx_queue <<
+					  I40E_TXD_FLTR_QW0_QINDEX_SHIFT) &
+					  I40E_TXD_FLTR_QW0_QINDEX_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_action->flex_off <<
+					  I40E_TXD_FLTR_QW0_FLEXOFF_SHIFT) &
+					  I40E_TXD_FLTR_QW0_FLEXOFF_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pctype <<
+					  I40E_TXD_FLTR_QW0_PCTYPE_SHIFT) &
+					  I40E_TXD_FLTR_QW0_PCTYPE_MASK);
+
+	/* Use LAN VSI Id if not programmed by user */
+	if (fdir_input->flow_ext.dest_id == 0)
+		fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pf->main_vsi->vsi_id <<
+					  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+					  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+	else
+		fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_input->flow_ext.dest_id <<
+					  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+					  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+
+	fdirdp->dtype_cmd_cntindex =
+			rte_cpu_to_le_32(I40E_TX_DESC_DTYPE_FILTER_PROG);
+
+	if (add)
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_ADD_UPDATE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+	else
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_REMOVE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+
+	if (fdir_action->drop)
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DROP_PACKET;
+	else
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DIRECT_PACKET_QINDEX;
+	fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32((dest <<
+				I40E_TXD_FLTR_QW1_DEST_SHIFT) &
+				I40E_TXD_FLTR_QW1_DEST_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+		rte_cpu_to_le_32((fdir_action->report_status<<
+				I40E_TXD_FLTR_QW1_FD_STATUS_SHIFT) &
+				I40E_TXD_FLTR_QW1_FD_STATUS_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+			rte_cpu_to_le_32(I40E_TXD_FLTR_QW1_CNT_ENA_MASK);
+	if (fdir_action->cnt_idx != 0)
+		fdirdp->dtype_cmd_cntindex |=
+				rte_cpu_to_le_32((fdir_action->cnt_idx <<
+				I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+				I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+	else
+		fdirdp->dtype_cmd_cntindex |=
+				rte_cpu_to_le_32((pf->fdir.match_counter_index <<
+				I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+				I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+
+	fdirdp->fd_id = rte_cpu_to_le_32(filter->soft_id);
+	txq->tx_tail++;
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+
+	PMD_DRV_LOG(INFO, "filling transmit descriptor.");
+	txdp = &(txq->tx_ring[txq->tx_tail]);
+	txdp->buffer_addr = rte_cpu_to_le_64(pf->fdir.dma_addr);
+	td_cmd = I40E_TX_DESC_CMD_EOP |
+		 I40E_TX_DESC_CMD_RS  |
+		 I40E_TX_DESC_CMD_DUMMY;
+
+	txdp->cmd_type_offset_bsz =
+		i40e_build_ctob(td_cmd, 0, I40E_FDIR_PKT_LEN, 0);
+
+	txq->tx_tail++;
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+	/* Update the tx tail register */
+	rte_wmb();
+	I40E_PCI_REG_WRITE(txq->qtx_tail, txq->tx_tail);
+
+	for (i = 0; i < I40E_FDIR_WAIT_COUNT; i++) {
+		rte_delay_us(I40E_FDIR_WAIT_INTERVAL_US);
+		if (txdp->cmd_type_offset_bsz &
+				rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DESC_DONE))
+			break;
+	}
+	if (i >= I40E_FDIR_WAIT_COUNT) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " timeout to get DD on tx queue.");
+		return -ETIMEDOUT;
+	}
+	/* totally delay 10 ms to check programming status*/
+	rte_delay_us((I40E_FDIR_WAIT_COUNT - i) * I40E_FDIR_WAIT_INTERVAL_US);
+	if (i40e_check_fdir_programming_status(rxq) < 0) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " programming status reported.");
+		return -ENOSYS;
+	}
+
+	return 0;
+}
+
+/*
+ * i40e_fdir_ctrl_func - deal with all operations on flow director.
+ * @pf: board private structure
+ * @filter_op:operation will be taken.
+ * @arg: a pointer to specific structure corresponding to the filter_op
+ */
+int
+i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
+{
+	int ret = 0;
+
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_NOP &&
+	    filter_op != RTE_ETH_FILTER_FLUSH)
+		return -EINVAL;
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_NOP:
+		if (!(pf->flags & I40E_FLAG_FDIR))
+			ret = -ENOTSUP;
+		break;
+	case RTE_ETH_FILTER_ADD:
+		ret = i40e_add_del_fdir_filter(pf,
+			(struct rte_eth_fdir_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_DELETE:
+		ret = i40e_add_del_fdir_filter(pf,
+			(struct rte_eth_fdir_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
+		ret = -EINVAL;
+		break;
+	}
+	return ret;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 06/21] testpmd: add test commands to add/delete flow director filter
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (4 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 05/21] i40e: implement operations to add/delete " Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-28 13:23     ` Thomas Monjalon
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 07/21] i40e: match counter for flow director Jingjing Wu
                     ` (19 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

add commands which can be used to test adding or deleting 8 flow
types of the flow director filters: ipv4, tcpv4, udpv4, sctpv4,
ipv6, tcpv6, udpv6, sctpv6

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 447 +++++++++++++++++++++++++++++++++++++++++++++++++
 app/test-pmd/testpmd.h |   3 +
 2 files changed, 450 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 0b972f9..5705b65 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -660,6 +660,28 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"get_flex_filter (port_id) index (idx)\n"
 			"    get info of a flex filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del|update)"
+			" flow (ip4|ip6) src (src_ip_address) dst (dst_ip_address)"
+			" flexwords (flexwords_value)"
+			" (drop|fwd) queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a IP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del|update)"
+			" flow (udp4|tcp4|udp6|tcp6)"
+			" src (src_ip_address) (src_port)"
+			" dst (dst_ip_address) (dst_port)"
+			" flexwords (flexwords_value)"
+			" (drop|fwd) queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a UDP/TCP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del|update)"
+			" flow (sctp4|sctp6)"
+			" src (src_ip_address) dst (dst_ip_address)"
+			" tag (verification_tag)"
+			" flexwords (flexwords_value) (drop|fwd)"
+			" queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a SCTP type flow director filter.\n\n"
 		);
 	}
 }
@@ -7415,6 +7437,428 @@ cmdline_parse_inst_t cmd_get_flex_filter = {
 	},
 };
 
+/* *** Filters Control *** */
+
+/* *** deal with flow director filter *** */
+struct cmd_flow_director_result {
+	cmdline_fixed_string_t flow_director_filter;
+	uint8_t port_id;
+	cmdline_fixed_string_t ops;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t src;
+	cmdline_ipaddr_t ip_src;
+	uint16_t port_src;
+	cmdline_fixed_string_t dst;
+	cmdline_ipaddr_t ip_dst;
+	uint16_t port_dst;
+	cmdline_fixed_string_t verify_tag;
+	uint32_t verify_tag_value;
+	cmdline_fixed_string_t flexwords;
+	cmdline_fixed_string_t flexwords_value;
+	cmdline_fixed_string_t drop;
+	cmdline_fixed_string_t queue;
+	uint16_t  queue_id;
+	cmdline_fixed_string_t fd_id;
+	uint32_t  fd_id_value;
+};
+
+static inline int
+parse_flexwords(const char *q_arg, uint16_t *flexwords)
+{
+#define MAX_NUM_WORD 8
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	unsigned long int_fld[MAX_NUM_WORD];
+	char *str_fld[MAX_NUM_WORD];
+	int i;
+	unsigned size;
+	int num_words = -1;
+
+	p = strchr(p0, '(');
+	if (p == NULL)
+		return -1;
+	++p;
+	p0 = strchr(p, ')');
+	if (p0 == NULL)
+		return -1;
+
+	size = p0 - p;
+	if (size >= sizeof(s))
+		return -1;
+
+	snprintf(s, sizeof(s), "%.*s", size, p);
+	num_words = rte_strsplit(s, sizeof(s), str_fld, MAX_NUM_WORD, ',');
+	if (num_words < 0 || num_words > MAX_NUM_WORD)
+		return -1;
+	for (i = 0; i < num_words; i++) {
+		errno = 0;
+		int_fld[i] = strtoul(str_fld[i], &end, 0);
+		if (errno != 0 || end == str_fld[i] || int_fld[i] > UINT16_MAX)
+			return -1;
+		flexwords[i] = rte_cpu_to_be_16((uint16_t)int_fld[i]);
+	}
+	return num_words;
+}
+
+static void
+cmd_flow_director_filter_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	struct rte_eth_fdir_filter entry;
+	uint16_t flexwords[8];
+	int num_flexwords;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+	memset(flexwords, 0, sizeof(flexwords));
+	memset(&entry, 0, sizeof(struct rte_eth_fdir_filter));
+	num_flexwords = parse_flexwords(res->flexwords_value, flexwords);
+	if (num_flexwords < 0) {
+		printf("error: Cannot parse flexwords input.\n");
+		return;
+	}
+
+	if (!strcmp(res->flow_type, "ip4")) {
+		/* no need to convert, already big endian. */
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.ip4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.ip4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_IPV4_OTHER;
+	} else if (!strcmp(res->flow_type, "udp4")) {
+		/* no need to convert, already big endian. */
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.udp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.udp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.udp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
+	} else if (!strcmp(res->flow_type, "tcp4")) {
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.tcp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.tcp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.tcp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.tcp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
+	} else if (!strcmp(res->flow_type, "sctp4")) {
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.sctp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.sctp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.sctp4_flow.verify_tag =
+				rte_cpu_to_be_32(res->verify_tag_value);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
+	} else if (!strcmp(res->flow_type, "ip6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.ip6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.ip6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_IPV6_OTHER;
+	} else if (!strcmp(res->flow_type, "udp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.udp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.udp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow.udp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
+	} else if (!strcmp(res->flow_type, "tcp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.tcp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.tcp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow.tcp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.tcp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
+	} else if (!strcmp(res->flow_type, "sctp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.sctp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.sctp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error paramters.\n");
+			return;
+		}
+		entry.input.flow.sctp6_flow.verify_tag =
+			rte_cpu_to_be_32(res->verify_tag_value);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
+	}
+
+	entry.input.flow_ext.num_flexwords = num_flexwords;
+	rte_memcpy(entry.input.flow_ext.flexwords,
+		   flexwords,
+		   BYTES_PER_WORD * num_flexwords);
+
+	entry.input.flow_ext.dest_id = 0; /* if set to 0, will use main vsi by default */
+	entry.action.flex_off = 0;  /*use 0 by default */
+	if (!strcmp(res->drop, "drop"))
+		entry.action.drop = 1;
+	else
+		entry.action.drop = 0;
+	/* set to report FD ID by default */
+	entry.action.report_status = RTE_ETH_FDIR_REPORT_FD_ID;
+	entry.action.rx_queue = res->queue_id;
+	/* use 0 by default, will set it to fdir counter per dev */
+	entry.action.cnt_idx = 0;
+	entry.soft_id = res->fd_id_value;
+	if (!strcmp(res->ops, "add"))
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_ADD, &entry);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_DELETE, &entry);
+	if (ret < 0)
+		printf("flow director programming error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_token_string_t cmd_flow_director_filter =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_director_filter, "flow_director_filter");
+cmdline_parse_token_num_t cmd_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_ops =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 ops, "add#del#update");
+cmdline_parse_token_string_t cmd_flow_director_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_type,
+				 "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_src =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 src, "src");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_src =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_src);
+cmdline_parse_token_num_t cmd_flow_director_port_src =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_src, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_dst =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 dst, "dst");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_dst =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_dst);
+cmdline_parse_token_num_t cmd_flow_director_port_dst =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_dst, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_verify_tag =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				  verify_tag, "verify_tag");
+cmdline_parse_token_num_t cmd_flow_director_verify_tag_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      verify_tag_value, UINT32);
+cmdline_parse_token_string_t cmd_flow_director_flexwords =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flexwords, "flexwords");
+cmdline_parse_token_string_t cmd_flow_director_flexwords_value =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+			      flexwords_value, NULL);
+cmdline_parse_token_string_t cmd_flow_director_drop =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 drop, "drop#fwd");
+cmdline_parse_token_string_t cmd_flow_director_queue =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 queue, "queue");
+cmdline_parse_token_num_t cmd_flow_director_queue_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      queue_id, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_fd_id =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 fd_id, "fd_id");
+cmdline_parse_token_num_t cmd_flow_director_fd_id_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      fd_id_value, UINT32);
+
+cmdline_parse_inst_t cmd_add_del_ip_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a ip flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_udp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a udp/tcp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_port_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_port_dst,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a sctp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_verify_tag,
+		(void *)&cmd_flow_director_verify_tag_value,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7541,6 +7985,9 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_remove_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_get_flex_filter,
+	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	NULL,
 };
 
diff --git a/app/test-pmd/testpmd.h b/app/test-pmd/testpmd.h
index 9cbfeac..74c0c0c 100644
--- a/app/test-pmd/testpmd.h
+++ b/app/test-pmd/testpmd.h
@@ -73,6 +73,9 @@ int main(int argc, char **argv);
 #define NUMA_NO_CONFIG 0xFF
 #define UMA_NO_CONFIG  0xFF
 
+#define BYTES_PER_WORD  2
+#define IPV6_ADDR_LEN 16
+
 typedef uint8_t  lcoreid_t;
 typedef uint8_t  portid_t;
 typedef uint16_t queueid_t;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 07/21] i40e: match counter for flow director
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (5 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field Jingjing Wu
                     ` (18 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

support to get the fdir_match counter

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index f56a4f6..3ff3965 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1285,6 +1285,9 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			    I40E_GLPRT_PTC9522L(hw->port),
 			    pf->offset_loaded, &os->tx_size_big,
 			    &ns->tx_size_big);
+	i40e_stat_update_32(hw, I40E_GLQF_PCNT(pf->fdir.match_counter_index),
+			   pf->offset_loaded,
+			   &os->fd_sb_match, &ns->fd_sb_match);
 	/* GLPRT_MSPDC not supported */
 	/* GLPRT_XEC not supported */
 
@@ -1301,6 +1304,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 	stats->obytes   = ns->eth.tx_bytes;
 	stats->oerrors  = ns->eth.tx_errors;
 	stats->imcasts  = ns->eth.rx_multicast;
+	stats->fdirmatch = ns->fd_sb_match;
 
 	/* Rx Errors */
 	stats->ibadcrc  = ns->crc_errors;
@@ -1376,6 +1380,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			ns->mac_short_packet_dropped);
 	PMD_DRV_LOG(DEBUG, "checksum_error:           %lu",
 		    ns->checksum_error);
+	PMD_DRV_LOG(DEBUG, "fdir_match:               %lu", ns->fd_sb_match);
 	PMD_DRV_LOG(DEBUG, "***************** PF stats end ********************");
 }
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (6 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 07/21] i40e: match counter for flow director Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-28 13:28     ` Thomas Monjalon
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 09/21] i40e: report flow director match info to mbuf Jingjing Wu
                     ` (17 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

extend fdir field to support flex bytes reported when fdir match

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_mbuf/rte_mbuf.h | 12 ++++++++++--
 1 file changed, 10 insertions(+), 2 deletions(-)

diff --git a/lib/librte_mbuf/rte_mbuf.h b/lib/librte_mbuf/rte_mbuf.h
index ddadc21..d2fbf40 100644
--- a/lib/librte_mbuf/rte_mbuf.h
+++ b/lib/librte_mbuf/rte_mbuf.h
@@ -91,6 +91,8 @@ extern "C" {
 #define PKT_RX_IPV6_HDR_EXT  (1ULL << 8)  /**< RX packet with extended IPv6 header. */
 #define PKT_RX_IEEE1588_PTP  (1ULL << 9)  /**< RX IEEE1588 L2 Ethernet PT Packet. */
 #define PKT_RX_IEEE1588_TMST (1ULL << 10) /**< RX IEEE1588 L2/L4 timestamped packet.*/
+#define PKT_RX_FDIR_ID       (1ULL << 11) /**< FD id reported if FDIR match. */
+#define PKT_RX_FDIR_FLX      (1ULL << 12) /**< Flexible bytes reported if FDIR match. */
 
 #define PKT_TX_VLAN_PKT      (1ULL << 55) /**< TX packet is a 802.1q VLAN packet. */
 #define PKT_TX_IP_CKSUM      (1ULL << 54) /**< IP cksum of TX pkt. computed by NIC. */
@@ -171,8 +173,14 @@ struct rte_mbuf {
 	union {
 		uint32_t rss;     /**< RSS hash result if RSS enabled */
 		struct {
-			uint16_t hash;
-			uint16_t id;
+			union {
+				struct {
+					uint16_t hash;
+					uint16_t id;
+				};
+				uint32_t lo; /**< flexible bytes low*/
+			};
+			uint32_t hi;         /**< flexible bytes high*/
 		} fdir;           /**< Filter identifier if FDIR enabled */
 		uint32_t sched;   /**< Hierarchical scheduler */
 	} hash;                   /**< hash information */
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 09/21] i40e: report flow director match info to mbuf
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (7 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 10/21] testpmd: print extended fdir info in mbuf Jingjing Wu
                     ` (16 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

support to set the FDIR information in mbuf if match

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_rxtx.c | 98 +++++++++++++++++++++++++++++++++++++++--
 1 file changed, 95 insertions(+), 3 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 1017e3f..5a361ca 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -105,6 +105,10 @@ i40e_rxd_status_to_pkt_flags(uint64_t qword)
 					I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
 			I40E_RX_DESC_FLTSTAT_RSS_HASH) ? PKT_RX_RSS_HASH : 0;
 
+	/* Check if FDIR Match */
+	flags |= (uint16_t)(qword & (1 << I40E_RX_DESC_STATUS_FLM_SHIFT) ?
+							PKT_RX_FDIR : 0);
+
 	return flags;
 }
 
@@ -637,10 +641,38 @@ i40e_rx_scan_hw_ring(struct i40e_rx_queue *rxq)
 			pkt_flags = i40e_rxd_status_to_pkt_flags(qword1);
 			pkt_flags |= i40e_rxd_error_to_pkt_flags(qword1);
 			pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
-			mb->ol_flags = pkt_flags;
 			if (pkt_flags & PKT_RX_RSS_HASH)
 				mb->hash.rss = rte_le_to_cpu_32(\
 					rxdp->wb.qword0.hi_dword.rss);
+
+			if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				mb->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxdp[j].wb.qword0.hi_dword.fd);
+				pkt_flags |= PKT_RX_FDIR_ID;
+#else
+				if (((rxdp[j].wb.qword2.ext_status >>
+					I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+					0x03) == 0x01) {
+					mb->hash.fdir.hi =
+						rte_le_to_cpu_32(\
+						rxdp[j].wb.qword3.hi_dword.fd_id);
+					pkt_flags |= PKT_RX_FDIR_ID;
+				} else if (((rxdp[j].wb.qword2.ext_status >>
+					I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+					0x03) == 0x02) {
+					mb->hash.fdir.hi =
+						rte_le_to_cpu_32(\
+						rxdp[j].wb.qword3.hi_dword.flex_bytes_hi);
+					pkt_flags |= PKT_RX_FDIR_FLX;
+				}
+				mb->hash.fdir.lo =
+					rte_le_to_cpu_32(\
+					rxdp[j].wb.qword3.lo_dword.flex_bytes_lo);
+#endif
+			}
+			mb->ol_flags = pkt_flags;
 		}
 
 		for (j = 0; j < I40E_LOOK_AHEAD; j++)
@@ -873,10 +905,40 @@ i40e_recv_pkts(void *rx_queue, struct rte_mbuf **rx_pkts, uint16_t nb_pkts)
 		pkt_flags = i40e_rxd_status_to_pkt_flags(qword1);
 		pkt_flags |= i40e_rxd_error_to_pkt_flags(qword1);
 		pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
-		rxm->ol_flags = pkt_flags;
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword0.hi_dword.fd);
+				pkt_flags |= PKT_RX_FDIR_ID;
+#else
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x01) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.fd_id);
+				pkt_flags |= PKT_RX_FDIR_ID;
+			} else if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x02) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.flex_bytes_hi);
+				pkt_flags |= PKT_RX_FDIR_FLX;
+			}
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBL_SHIFT) &
+				0x03) == 0x01)
+				rxm->hash.fdir.lo =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.lo_dword.flex_bytes_lo);
+#endif
+		}
+		rxm->ol_flags = pkt_flags;
 
 		rx_pkts[nb_rx++] = rxm;
 	}
@@ -1027,10 +1089,40 @@ i40e_recv_scattered_pkts(void *rx_queue,
 		pkt_flags = i40e_rxd_status_to_pkt_flags(qword1);
 		pkt_flags |= i40e_rxd_error_to_pkt_flags(qword1);
 		pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
-		first_seg->ol_flags = pkt_flags;
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword0.hi_dword.fd);
+				pkt_flags |= PKT_RX_FDIR_ID;
+#else
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x01) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.fd_id);
+				pkt_flags |= PKT_RX_FDIR_ID;
+			} else if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x02) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.flex_bytes_hi);
+				pkt_flags |= PKT_RX_FDIR_FLX;
+			}
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBL_SHIFT) &
+				0x03) == 0x01)
+				rxm->hash.fdir.lo =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.lo_dword.flex_bytes_lo);
+#endif
+		}
+		first_seg->ol_flags = pkt_flags;
 
 		/* Prefetch data of first segment, if configured to do so. */
 		rte_prefetch0(RTE_PTR_ADD(first_seg->buf_addr,
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 10/21] testpmd: print extended fdir info in mbuf
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (8 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 09/21] i40e: report flow director match info to mbuf Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information Jingjing Wu
                     ` (15 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

print extend fdir info in rxonly fwd engine when fdir match.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/rxonly.c | 14 +++++++++++---
 1 file changed, 11 insertions(+), 3 deletions(-)

diff --git a/app/test-pmd/rxonly.c b/app/test-pmd/rxonly.c
index 98c788b..7f5099c 100644
--- a/app/test-pmd/rxonly.c
+++ b/app/test-pmd/rxonly.c
@@ -160,10 +160,18 @@ pkt_burst_receive(struct fwd_stream *fs)
 		if (ol_flags & PKT_RX_RSS_HASH) {
 			printf(" - RSS hash=0x%x", (unsigned) mb->hash.rss);
 			printf(" - RSS queue=0x%x",(unsigned) fs->rx_queue);
+		} else if (ol_flags & PKT_RX_FDIR) {
+			printf(" - FDIR matched ");
+			if (ol_flags & PKT_RX_FDIR_ID)
+				printf("ID=0x%x",
+				       mb->hash.fdir.hi);
+			else if (ol_flags & PKT_RX_FDIR_FLX)
+				printf("flex bytes=0x%08x %08x",
+				       mb->hash.fdir.hi, mb->hash.fdir.lo);
+			else
+				printf("hash=0x%x ID=0x%x ",
+				       mb->hash.fdir.hash, mb->hash.fdir.id);
 		}
-		else if (ol_flags & PKT_RX_FDIR)
-			printf(" - FDIR hash=0x%x - FDIR id=0x%x ",
-			       mb->hash.fdir.hash, mb->hash.fdir.id);
 		if (ol_flags & PKT_RX_VLAN_PKT)
 			printf(" - VLAN tci=0x%x", mb->vlan_tci);
 		printf("\n");
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (9 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 10/21] testpmd: print extended fdir info in mbuf Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-28 13:44     ` Thomas Monjalon
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 12/21] i40e: implement operations to get fdir info Jingjing Wu
                     ` (14 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

define structures for getting flow director information

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 40 ++++++++++++++++++++++++++++++++++++++++
 lib/librte_ether/rte_ethdev.h   | 23 -----------------------
 2 files changed, 40 insertions(+), 23 deletions(-)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 3efdaae..7ca1d6b 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -231,6 +231,46 @@ struct rte_eth_fdir_filter {
 	struct rte_eth_fdir_action action;  /**< action taken when match */
 };
 
+/**
+ * A structure used to report the status of the flow director filters in use.
+ */
+struct rte_eth_fdir {
+	/** Number of filters with collision indication. */
+	uint16_t collision;
+	/** Number of free (non programmed) filters. */
+	uint16_t free;
+	/** The Lookup hash value of the added filter that updated the value
+	   of the MAXLEN field */
+	uint16_t maxhash;
+	/** Longest linked list of filters in the table. */
+	uint8_t maxlen;
+	/** Number of added filters. */
+	uint64_t add;
+	/** Number of removed filters. */
+	uint64_t remove;
+	/** Number of failed added filters (no more space in device). */
+	uint64_t f_add;
+	/** Number of failed removed filters. */
+	uint64_t f_remove;
+};
+
+struct rte_eth_fdir_ext {
+	uint16_t guarant_spc;  /**< guaranteed spaces.*/
+	uint16_t guarant_cnt;  /**< Number of filters in guaranteed spaces. */
+	uint16_t best_spc;     /**< best effort spaces.*/
+	uint16_t best_cnt;     /**< Number of filters in best effort spaces. */
+};
+
+/**
+ * A structure used to get the status information of flow director filter.
+ * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_INFO operation.
+ */
+struct rte_eth_fdir_info {
+	int mode;                 /**< if 0 disbale, if 1 enable*/
+	struct rte_eth_fdir info;
+	struct rte_eth_fdir_ext info_ext;
+};
+
 #ifdef __cplusplus
 }
 #endif
diff --git a/lib/librte_ether/rte_ethdev.h b/lib/librte_ether/rte_ethdev.h
index b69a6af..0dc399d 100644
--- a/lib/librte_ether/rte_ethdev.h
+++ b/lib/librte_ether/rte_ethdev.h
@@ -795,29 +795,6 @@ struct rte_fdir_masks {
 };
 
 /**
- *  A structure used to report the status of the flow director filters in use.
- */
-struct rte_eth_fdir {
-	/** Number of filters with collision indication. */
-	uint16_t collision;
-	/** Number of free (non programmed) filters. */
-	uint16_t free;
-	/** The Lookup hash value of the added filter that updated the value
-	   of the MAXLEN field */
-	uint16_t maxhash;
-	/** Longest linked list of filters in the table. */
-	uint8_t maxlen;
-	/** Number of added filters. */
-	uint64_t add;
-	/** Number of removed filters. */
-	uint64_t remove;
-	/** Number of failed added filters (no more space in device). */
-	uint64_t f_add;
-	/** Number of failed removed filters. */
-	uint64_t f_remove;
-};
-
-/**
  * A structure used to enable/disable specific device interrupts.
  */
 struct rte_intr_conf {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 12/21] i40e: implement operations to get fdir info
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (10 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 13/21] testpmd: display fdir statistics Jingjing Wu
                     ` (13 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

implement operation to get flow director information in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 35 +++++++++++++++++++++++++++++++++++
 1 file changed, 35 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 8996a1c..d2c8304 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -89,6 +89,8 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			enum i40e_filter_pctype pctype,
 			struct rte_eth_fdir_filter *filter,
 			bool add);
+static void i40e_fdir_info_get(struct i40e_pf *pf,
+			   struct rte_eth_fdir_info *fdir);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -874,6 +876,36 @@ i40e_fdir_filter_programming(struct i40e_pf *pf,
 }
 
 /*
+ * i40e_fdir_info_get - get information of Flow Director
+ * @pf: ethernet device to get info from
+ * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
+ *    the flow director information.
+ */
+static void
+i40e_fdir_info_get(struct i40e_pf *pf, struct rte_eth_fdir_info *fdir)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t pfqf_ctl;
+
+	pfqf_ctl = I40E_READ_REG(hw, I40E_PFQF_CTL_0);
+	fdir->mode = pfqf_ctl & I40E_PFQF_CTL_0_FD_ENA_MASK ?
+		     RTE_FDIR_MODE_PERFECT : RTE_FDIR_MODE_NONE;
+	fdir->info_ext.guarant_spc =
+		(uint16_t)hw->func_caps.fd_filters_guaranteed;
+	fdir->info_ext.guarant_cnt =
+		(uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	fdir->info_ext.best_spc =
+		(uint16_t)hw->func_caps.fd_filters_best_effort;
+	fdir->info_ext.best_cnt =
+		(uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			    I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	return;
+}
+
+/*
  * i40e_fdir_ctrl_func - deal with all operations on flow director.
  * @pf: board private structure
  * @filter_op:operation will be taken.
@@ -903,6 +935,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_INFO:
+		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
+		break;
 	default:
 		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
 		ret = -EINVAL;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 13/21] testpmd: display fdir statistics
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (11 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 12/21] i40e: implement operations to get fdir info Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 14/21] i40e: implement operation to flush flow director table Jingjing Wu
                     ` (12 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

display flow director's statistics information

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/config.c | 38 ++++++++++++++++++++++++++++++--------
 1 file changed, 30 insertions(+), 8 deletions(-)

diff --git a/app/test-pmd/config.c b/app/test-pmd/config.c
index 2a1b93f..8625251 100644
--- a/app/test-pmd/config.c
+++ b/app/test-pmd/config.c
@@ -1815,26 +1815,48 @@ fdir_remove_signature_filter(portid_t port_id,
 void
 fdir_get_infos(portid_t port_id)
 {
-	struct rte_eth_fdir fdir_infos;
+	struct rte_eth_fdir_info fdir_infos;
+	int ret;
 
 	static const char *fdir_stats_border = "########################";
 
 	if (port_id_is_invalid(port_id))
 		return;
 
-	rte_eth_dev_fdir_get_infos(port_id, &fdir_infos);
-
+	memset(&fdir_infos, 0, sizeof(fdir_infos));
+	ret = rte_eth_dev_filter_ctrl(port_id, RTE_ETH_FILTER_FDIR,
+			       RTE_ETH_FILTER_INFO, &fdir_infos);
+	if (ret < 0) {
+		ret = rte_eth_dev_fdir_get_infos(port_id, &fdir_infos.info);
+		if (ret < 0) {
+			printf("\n getting fdir info fails on port %-2d\n",
+				port_id);
+			return;
+		}
+		fdir_infos.mode = (fdir_conf.mode == RTE_FDIR_MODE_NONE) ? 0 : 1;
+	}
 	printf("\n  %s FDIR infos for port %-2d     %s\n",
 	       fdir_stats_border, port_id, fdir_stats_border);
-
+	if (fdir_infos.mode)
+			printf("  FDIR is enabled\n");
+	else
+			printf("  FDIR is disabled\n");
 	printf("  collision: %-10"PRIu64"  free:     %"PRIu64"\n"
 	       "  maxhash:   %-10"PRIu64"  maxlen:   %"PRIu64"\n"
 	       "  add:       %-10"PRIu64"  remove:   %"PRIu64"\n"
 	       "  f_add:     %-10"PRIu64"  f_remove: %"PRIu64"\n",
-	       (uint64_t)(fdir_infos.collision), (uint64_t)(fdir_infos.free),
-	       (uint64_t)(fdir_infos.maxhash), (uint64_t)(fdir_infos.maxlen),
-	       fdir_infos.add, fdir_infos.remove,
-	       fdir_infos.f_add, fdir_infos.f_remove);
+	       (uint64_t)(fdir_infos.info.collision), (uint64_t)(fdir_infos.info.free),
+	       (uint64_t)(fdir_infos.info.maxhash), (uint64_t)(fdir_infos.info.maxlen),
+	       fdir_infos.info.add, fdir_infos.info.remove,
+	       fdir_infos.info.f_add, fdir_infos.info.f_remove);
+	printf("  guarant_space: %-10"PRIu16
+	       "  best_space:    %-10"PRIu16"\n",
+	       fdir_infos.info_ext.guarant_spc,
+	       fdir_infos.info_ext.best_spc);
+	printf("  guarant_count: %-10"PRIu16
+	       "  best_count:    %-10"PRIu16"\n",
+	       fdir_infos.info_ext.guarant_cnt,
+	       fdir_infos.info_ext.best_cnt);
 	printf("  %s############################%s\n",
 	       fdir_stats_border, fdir_stats_border);
 }
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 14/21] i40e: implement operation to flush flow director table
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (12 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 13/21] testpmd: display fdir statistics Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 15/21] testpmd: add test command " Jingjing Wu
                     ` (11 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

implement operation to flush flow director table

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 47 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 47 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index d2c8304..00ee470 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -73,6 +73,10 @@
 #define I40E_FDIR_WAIT_COUNT       10
 #define I40E_FDIR_WAIT_INTERVAL_US 1000
 
+/* Wait count and inteval for fdir filter flush */
+#define I40E_FDIR_FLUSH_RETRY       50
+#define I40E_FDIR_FLUSH_INTERVAL_MS 5
+
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
 #define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
@@ -89,6 +93,7 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			enum i40e_filter_pctype pctype,
 			struct rte_eth_fdir_filter *filter,
 			bool add);
+static int i40e_fdir_flush(struct i40e_pf *pf);
 static void i40e_fdir_info_get(struct i40e_pf *pf,
 			   struct rte_eth_fdir_info *fdir);
 
@@ -876,6 +881,45 @@ i40e_fdir_filter_programming(struct i40e_pf *pf,
 }
 
 /*
+ * i40e_fdir_flush - clear all filters of Flow Director table
+ * @pf: board private structure
+ */
+static int
+i40e_fdir_flush(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t reg;
+	uint16_t guarant_cnt, best_cnt;
+	int i;
+
+	I40E_WRITE_REG(hw, I40E_PFQF_CTL_1, I40E_PFQF_CTL_1_CLEARFDTABLE_MASK);
+	I40E_WRITE_FLUSH(hw);
+
+	for (i = 0; i < I40E_FDIR_FLUSH_RETRY; i++) {
+		rte_delay_ms(I40E_FDIR_FLUSH_INTERVAL_MS);
+		reg = I40E_READ_REG(hw, I40E_PFQF_CTL_1);
+		if (!(reg & I40E_PFQF_CTL_1_CLEARFDTABLE_MASK))
+			break;
+	}
+	if (i >= I40E_FDIR_FLUSH_RETRY) {
+		PMD_DRV_LOG(ERR, "FD table did not flush, may need more time.");
+		return -ETIMEDOUT;
+	}
+	guarant_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	best_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	if (guarant_cnt != 0 || best_cnt != 0) {
+		PMD_DRV_LOG(ERR, "Failed to flush FD table.");
+		return -ENOSYS;
+	} else
+		PMD_DRV_LOG(INFO, "FD table Flush success.");
+	return 0;
+}
+
+/*
  * i40e_fdir_info_get - get information of Flow Director
  * @pf: ethernet device to get info from
  * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
@@ -935,6 +979,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_FLUSH:
+		ret = i40e_fdir_flush(pf);
+		break;
 	case RTE_ETH_FILTER_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
 		break;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 15/21] testpmd: add test command to flush flow director table
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (13 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 14/21] i40e: implement operation to flush flow director table Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-28 13:53     ` Thomas Monjalon
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
                     ` (10 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

add test command to flush flow director table

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 49 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 49 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 5705b65..7324783 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -682,6 +682,9 @@ static void cmd_help_long_parsed(void *parsed_result,
 			" flexwords (flexwords_value) (drop|fwd)"
 			" queue (queue_id) fd_id (fd_id_value)\n"
 			"    Add/Del a SCTP type flow director filter.\n\n"
+
+			"flush_flow_diretor (port_id)\n"
+			"    Flush all flow director entries of a device.\n\n"
 		);
 	}
 }
@@ -7859,6 +7862,51 @@ cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
 	},
 };
 
+struct cmd_flush_flow_director_result {
+	cmdline_fixed_string_t flush_flow_director;
+	uint8_t port_id;
+};
+
+cmdline_parse_token_string_t cmd_flush_flow_director_flush =
+	TOKEN_STRING_INITIALIZER(struct cmd_flush_flow_director_result,
+				 flush_flow_director, "flush_flow_director");
+cmdline_parse_token_num_t cmd_flush_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flush_flow_director_result,
+			      port_id, UINT8);
+
+static void
+cmd_flush_flow_director_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+			RTE_ETH_FILTER_FLUSH, NULL);
+	if (ret < 0)
+		printf("flow director table flushing error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_inst_t cmd_flush_flow_director = {
+	.f = cmd_flush_flow_director_parsed,
+	.data = NULL,
+	.help_str = "flush all flow director entries of a device on NIC",
+	.tokens = {
+		(void *)&cmd_flush_flow_director_flush,
+		(void *)&cmd_flush_flow_director_port_id,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7988,6 +8036,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (14 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 15/21] testpmd: add test command " Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-28 14:14     ` Thomas Monjalon
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 17/21] i40e: implement operations to configure " Jingjing Wu
                     ` (9 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

define structures for configuring flexible payload

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 43 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 43 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 7ca1d6b..ca21313 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -76,6 +76,25 @@ enum rte_filter_op {
  * Define all structures for Flow Director Filter type corresponding with specific operations.
  */
 
+
+/**
+ * A structure defined a field vector to specify each field.
+ */
+struct rte_eth_field_vector {
+	uint8_t offset;   /**< Source word offset */
+	uint8_t size;     /**< Field Size defined in word units */
+};
+
+/**
+ * payload type
+ */
+enum rte_eth_payload_type {
+	RTE_ETH_PAYLOAD_UNKNOWN = 0,
+	RTE_ETH_L2_PAYLOAD,
+	RTE_ETH_L3_PAYLOAD,
+	RTE_ETH_L4_PAYLOAD,
+};
+
 /**
  * flow type
  */
@@ -92,6 +111,30 @@ enum rte_eth_flow_type {
 };
 
 /**
+ * A structure used to select fields extracted from the protocol layers to
+ * the Field Vector as flexible payload for filter
+ */
+struct rte_eth_flex_payload_cfg {
+	enum rte_eth_payload_type type;  /**< payload type */
+	uint8_t nb_field;                /**< the number of following fields */
+	struct rte_eth_field_vector field[0];
+};
+
+#define RTE_ETH_FDIR_CFG_FLX      0x0001
+/**
+ * A structure used to config FDIR filter global set
+ * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_SET operation.
+ */
+struct rte_eth_fdir_cfg {
+	uint16_t cmd;  /**< sub command  */
+	/**
+	 * A pointer to structure for the configuration e.g.
+	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
+	*/
+	void *cfg;
+};
+
+/**
  * A structure used to define the input for IPV4 UDP flow
  */
 struct rte_eth_udpv4_flow {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 17/21] i40e: implement operations to configure flexible payload
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (15 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 18/21] testpmd: add test command " Jingjing Wu
                     ` (8 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

implement operation to flexible payload in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 106 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 106 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 00ee470..67498ff 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -83,6 +83,8 @@
 #define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 struct rte_eth_flex_payload_cfg *cfg);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -327,6 +329,98 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 }
 
 /*
+ * i40e_set_flx_pld_cfg -configure the rule how bytes stream is extracted as flexible payload
+ * @pf: board private structure
+ * @cfg: the rule how bytes stream is extracted as flexible payload
+ */
+static int
+i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 struct rte_eth_flex_payload_cfg *cfg)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct rte_eth_fdir_info fdir;
+	uint32_t flx_pit;
+	uint16_t min_next_off = 0;
+	uint8_t idx = 0;
+	int i = 0;
+	int num_word = 0;
+	int ret;
+
+	if (cfg == NULL || cfg->nb_field > 3)
+		return -EINVAL;
+
+	if (cfg->type == RTE_ETH_L2_PAYLOAD)
+		idx = 0;
+	else if (cfg->type == RTE_ETH_L3_PAYLOAD)
+		idx = 1;
+	else if (cfg->type == RTE_ETH_L4_PAYLOAD)
+		idx = 2;
+	else {
+		PMD_DRV_LOG(ERR, "unknown payload type.");
+		return -EINVAL;
+	}
+	/*
+	 * flexible payload need to be configured before
+	 * flow director filters are added
+	 * If filters exist, flush them.
+	 */
+	memset(&fdir, 0, sizeof(fdir));
+	i40e_fdir_info_get(pf, &fdir);
+	if (fdir.info_ext.best_cnt + fdir.info_ext.guarant_cnt > 0) {
+		ret = i40e_fdir_flush(pf);
+		if (ret) {
+			PMD_DRV_LOG(ERR, " failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	for (i = 0; i < cfg->nb_field; i++) {
+		/*
+		 * check register's constrain
+		 * Current Offset >= previous offset + previous FSIZE.
+		 */
+		if (cfg->field[i].offset < min_next_off) {
+			PMD_DRV_LOG(ERR, "Offset should be larger than"
+				"previous offset + previous FSIZE.");
+			return -EINVAL;
+		}
+		flx_pit = (cfg->field[i].offset <<
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK;
+		flx_pit |= (cfg->field[i].size <<
+				I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) &
+				I40E_PRTQF_FLX_PIT_FSIZE_MASK;
+		flx_pit |= ((num_word + I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+				I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) &
+				I40E_PRTQF_FLX_PIT_DEST_OFF_MASK;
+		/* support no more than 8 words flexible payload*/
+		num_word += cfg->field[i].size;
+		if (num_word > 8)
+			return -EINVAL;
+
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(idx * 3 + i), flx_pit);
+		/* record the info in fdir structure */
+		pf->fdir.flex_set[idx][i].offset = cfg->field[i].offset;
+		pf->fdir.flex_set[idx][i].size = cfg->field[i].size;
+		min_next_off = cfg->field[i].offset + cfg->field[i].size;
+	}
+
+	for (; i < 3; i++) {
+		/* set the non-used register obeying register's constrain */
+		flx_pit = (min_next_off << I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK;
+		flx_pit |= (1 << I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) &
+			I40E_PRTQF_FLX_PIT_FSIZE_MASK;
+		flx_pit |= (63 << I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_DEST_OFF_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(idx * 3 + i), flx_pit);
+		min_next_off++;
+	}
+
+	return 0;
+}
+
+/*
  * i40e_fdir_construct_pkt - construct packet based on fields in input
  * @pf: board private structure
  * @fdir_input: input set of the flow director entry
@@ -958,6 +1052,7 @@ i40e_fdir_info_get(struct i40e_pf *pf, struct rte_eth_fdir_info *fdir)
 int
 i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 {
+	struct rte_eth_fdir_cfg *fdir_cfg = NULL;
 	int ret = 0;
 
 	if (arg == NULL && filter_op != RTE_ETH_FILTER_NOP &&
@@ -982,6 +1077,17 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 	case RTE_ETH_FILTER_FLUSH:
 		ret = i40e_fdir_flush(pf);
 		break;
+	case RTE_ETH_FILTER_SET:
+		fdir_cfg = (struct rte_eth_fdir_cfg *)arg;
+		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX)
+			ret = i40e_set_flx_pld_cfg(pf,
+				(struct rte_eth_flex_payload_cfg *)fdir_cfg->cfg);
+		else {
+			PMD_DRV_LOG(WARNING, "unsupported configuration command %u.",
+				    fdir_cfg->cmd);
+			return -EINVAL;
+		}
+		break;
 	case RTE_ETH_FILTER_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
 		break;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 18/21] testpmd: add test command to configure flexible payload
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (16 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 17/21] i40e: implement operations to configure " Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 19/21] ethdev: define structures for configuring flex masks Jingjing Wu
                     ` (7 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

add test command to configure flexible payload

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 143 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 143 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 7324783..1caca54 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -58,6 +58,7 @@
 #include <rte_debug.h>
 #include <rte_cycles.h>
 #include <rte_memory.h>
+#include <rte_malloc.h>
 #include <rte_memzone.h>
 #include <rte_launch.h>
 #include <rte_tailq.h>
@@ -685,6 +686,10 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"flush_flow_diretor (port_id)\n"
 			"    Flush all flow director entries of a device.\n\n"
+
+			"flow_director_flex_payload (port_id)"
+			" (l2|l3|l4) (config)\n"
+			"    Configure flex payload selection.\n\n"
 		);
 	}
 }
@@ -7907,6 +7912,143 @@ cmdline_parse_inst_t cmd_flush_flow_director = {
 	},
 };
 
+/* *** deal with flow director flexible payload configuration *** */
+struct cmd_flow_director_flexpayload_result {
+	cmdline_fixed_string_t flow_director_flexpayload;
+	uint8_t port_id;
+	cmdline_fixed_string_t payload_layer;
+	cmdline_fixed_string_t payload_cfg;
+};
+
+static inline int
+parse_flex_payload_cfg(const char *q_arg,
+			     struct rte_eth_flex_payload_cfg *cfg)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	enum fieldnames {
+		FLD_OFFSET = 0,
+		FLD_SIZE,
+		_NUM_FLD
+	};
+	unsigned long int_fld[_NUM_FLD];
+	char *str_fld[_NUM_FLD];
+	int i;
+	unsigned size;
+
+	cfg->nb_field = 0;
+	p = strchr(p0, '(');
+	while (p != NULL) {
+		++p;
+		p0 = strchr(p, ')');
+		if (p0 == NULL)
+			return -1;
+
+		size = p0 - p;
+		if (size >= sizeof(s))
+			return -1;
+
+		snprintf(s, sizeof(s), "%.*s", size, p);
+		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') != _NUM_FLD)
+			return -1;
+		for (i = 0; i < _NUM_FLD; i++) {
+			errno = 0;
+			int_fld[i] = strtoul(str_fld[i], &end, 0);
+			if (errno != 0 || end == str_fld[i] || int_fld[i] > 255)
+				return -1;
+		}
+		cfg->field[cfg->nb_field].offset = (uint8_t)int_fld[FLD_OFFSET];
+		cfg->field[cfg->nb_field].size = (uint8_t)int_fld[FLD_SIZE];
+		cfg->nb_field++;
+		if (cfg->nb_field > 3) {
+			printf("exceeded max number of fields\n");
+			return -1;
+		}
+		p = strchr(p0, '(');
+	}
+	return 0;
+}
+
+static void
+cmd_flow_director_flxpld_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flexpayload_result *res = parsed_result;
+	struct rte_eth_fdir_cfg fdir_cfg;
+	struct rte_eth_flex_payload_cfg *flxpld_cfg;
+	int ret = 0;
+	int cfg_size = 3 * sizeof(struct rte_eth_field_vector) +
+		  offsetof(struct rte_eth_flex_payload_cfg, field);
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
+
+	flxpld_cfg = (struct rte_eth_flex_payload_cfg *)rte_zmalloc_socket("CLI",
+		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
+
+	if (flxpld_cfg == NULL) {
+		printf("fail to malloc memory to configure flex payload\n");
+		return;
+	}
+
+	if (!strcmp(res->payload_layer, "l2"))
+		flxpld_cfg->type = RTE_ETH_L2_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l3"))
+		flxpld_cfg->type = RTE_ETH_L3_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l4"))
+		flxpld_cfg->type = RTE_ETH_L4_PAYLOAD;
+
+	ret = parse_flex_payload_cfg(res->payload_cfg, flxpld_cfg);
+	if (ret < 0) {
+		printf("error: Cannot parse flex payload input.\n");
+		rte_free(flxpld_cfg);
+		return;
+	}
+	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX;
+	fdir_cfg.cfg = flxpld_cfg;
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+				     RTE_ETH_FILTER_SET, &fdir_cfg);
+	if (ret < 0)
+		printf("fdir flex payload setting error: (%s)\n",
+			strerror(-ret));
+	rte_free(flxpld_cfg);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexpayload =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 flow_director_flexpayload,
+				 "flow_director_flex_payload");
+cmdline_parse_token_num_t cmd_flow_director_flexpayload_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_layer =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_layer, "l2#l3#l4");
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_cfg =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_cfg, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_payload = {
+	.f = cmd_flow_director_flxpld_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex payload on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexpayload,
+		(void *)&cmd_flow_director_flexpayload_port_id,
+		(void *)&cmd_flow_director_flexpayload_payload_layer,
+		(void *)&cmd_flow_director_flexpayload_payload_cfg,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8037,6 +8179,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 19/21] ethdev: define structures for configuring flex masks
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (17 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 18/21] testpmd: add test command " Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 20/21] i40e: implement operations to configure flexible masks Jingjing Wu
                     ` (6 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

define structures for configuring flexible masks

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 23 +++++++++++++++++++++++
 1 file changed, 23 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index ca21313..3b336e4 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -120,7 +120,28 @@ struct rte_eth_flex_payload_cfg {
 	struct rte_eth_field_vector field[0];
 };
 
+/**
+ * A structure defined to specify each word's bit mask
+ */
+struct rte_eth_flex_mask {
+	uint8_t offset;      /**< word offset in flexible payload */
+	uint16_t bitmask;    /**< bit mask for word defined by offset */
+};
+
+/**
+ * A structure used to configure FDIR masks for flexible payload
+ * for each flow type
+ */
+struct rte_eth_fdir_flex_masks {
+	enum rte_eth_flow_type flow_type;  /**< flow type */
+	uint8_t words_mask;  /**< bit i enables word i of 8 words flexible payload */
+	uint8_t nb_field;    /**< the number of following fields */
+	struct rte_eth_flex_mask field[0];
+};
+
 #define RTE_ETH_FDIR_CFG_FLX      0x0001
+#define RTE_ETH_FDIR_CFG_MASK     0x0002
+#define RTE_ETH_FDIR_CFG_FLX_MASK 0x0003
 /**
  * A structure used to config FDIR filter global set
  * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_SET operation.
@@ -130,6 +151,8 @@ struct rte_eth_fdir_cfg {
 	/**
 	 * A pointer to structure for the configuration e.g.
 	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
+	 * struct rte_fdir_masks for FDIR_MASK
+	 * struct rte_eth_fdir_flex_masks for FDIR_FLX_MASK
 	*/
 	void *cfg;
 };
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 20/21] i40e: implement operations to configure flexible masks
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (18 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 19/21] ethdev: define structures for configuring flex masks Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 21/21] testpmd: add test command " Jingjing Wu
                     ` (5 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

implement operation to flexible masks for each flow type in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 124 +++++++++++++++++++++++++++++++++++++++-
 1 file changed, 123 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 67498ff..2184d93 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -85,6 +85,8 @@
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
 static int i40e_set_flx_pld_cfg(struct i40e_pf *pf,
 			 struct rte_eth_flex_payload_cfg *cfg);
+static int i40e_set_fdir_flx_mask(struct i40e_pf *pf,
+			struct rte_eth_fdir_flex_masks *flex_masks);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -420,6 +422,123 @@ i40e_set_flx_pld_cfg(struct i40e_pf *pf,
 	return 0;
 }
 
+static inline void
+i40e_set_flex_mask_on_pctype(
+		struct i40e_hw *hw,
+		enum i40e_filter_pctype pctype,
+		struct rte_eth_fdir_flex_masks *flex_masks)
+{
+	uint32_t flxinset, mask;
+	int i;
+
+	flxinset = (flex_masks->words_mask <<
+		I40E_PRTQF_FD_FLXINSET_INSET_SHIFT) &
+		I40E_PRTQF_FD_FLXINSET_INSET_MASK;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), flxinset);
+
+	for (i = 0; i < flex_masks->nb_field; i++) {
+		mask = (flex_masks->field[i].bitmask <<
+			I40E_PRTQF_FD_MSK_MASK_SHIFT) &
+			I40E_PRTQF_FD_MSK_MASK_MASK;
+		mask |= ((flex_masks->field[i].offset +
+			I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+			I40E_PRTQF_FD_MSK_OFFSET_SHIFT) &
+			I40E_PRTQF_FD_MSK_OFFSET_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, i), mask);
+	}
+}
+
+/*
+ * i40e_set_fdir_flx_mask - configure the mask on flexible payload
+ * @pf: board private structure
+ * @flex_masks: mask for flexible payload
+ */
+static int
+i40e_set_fdir_flx_mask(struct i40e_pf *pf,
+		struct rte_eth_fdir_flex_masks *flex_masks)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct rte_eth_fdir_info fdir;
+	int ret = 0;
+
+	if (flex_masks == NULL)
+		return -EINVAL;
+
+	if (flex_masks->nb_field > 2) {
+		PMD_DRV_LOG(ERR, "bit masks cannot support more than 2 words.");
+		return -EINVAL;
+	}
+	/*
+	 * flexible payload masks need to be configured before
+	 * flow director filters are added
+	 * If filters exist, flush them.
+	 */
+	memset(&fdir, 0, sizeof(fdir));
+	i40e_fdir_info_get(pf, &fdir);
+	if (fdir.info_ext.best_cnt + fdir.info_ext.guarant_cnt > 0) {
+		ret = i40e_fdir_flush(pf);
+		if (ret) {
+			PMD_DRV_LOG(ERR, "failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	switch (flex_masks->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		/* set mask for both NONF_IPV4 and FRAG_IPV4 PCTYPE*/
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+			flex_masks);
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_FRAG_IPV4,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+			flex_masks);
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		/* set mask for both NONF_IPV6 and FRAG_IPV6 PCTYPE*/
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+			flex_masks);
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_FRAG_IPV6,
+			flex_masks);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "invalid flow_type input.");
+		return -EINVAL;
+	}
+
+	return ret;
+}
+
 /*
  * i40e_fdir_construct_pkt - construct packet based on fields in input
  * @pf: board private structure
@@ -1082,8 +1201,11 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX)
 			ret = i40e_set_flx_pld_cfg(pf,
 				(struct rte_eth_flex_payload_cfg *)fdir_cfg->cfg);
+		else if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX_MASK)
+			ret = i40e_set_fdir_flx_mask(pf,
+				(struct rte_eth_fdir_flex_masks *)fdir_cfg->cfg);
 		else {
-			PMD_DRV_LOG(WARNING, "unsupported configuration command %u.",
+			PMD_DRV_LOG(ERR, "unsupported configuration command %u.",
 				    fdir_cfg->cmd);
 			return -EINVAL;
 		}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v4 21/21] testpmd: add test command to configure flexible masks
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (19 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 20/21] i40e: implement operations to configure flexible masks Jingjing Wu
@ 2014-10-22  1:01   ` Jingjing Wu
  2014-10-28 14:18     ` Thomas Monjalon
  2014-10-27 15:22   ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Thomas Monjalon
                     ` (4 subsequent siblings)
  25 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-22  1:01 UTC (permalink / raw)
  To: dev

add test command to configure flexible masks for each flow type

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 173 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 173 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 1caca54..e7f9ce5 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -687,6 +687,11 @@ static void cmd_help_long_parsed(void *parsed_result,
 			"flush_flow_diretor (port_id)\n"
 			"    Flush all flow director entries of a device.\n\n"
 
+			"flow_director_flex_mask (port_id)"
+			" flow (ether|ip4|tcp4|udp4|sctp4|ip6|tcp6|udp6|sctp6)"
+			" words_mask (words) (word_mask_list)\n"
+			"    Configure mask of flex payload.\n\n"
+
 			"flow_director_flex_payload (port_id)"
 			" (l2|l3|l4) (config)\n"
 			"    Configure flex payload selection.\n\n"
@@ -7912,6 +7917,173 @@ cmdline_parse_inst_t cmd_flush_flow_director = {
 	},
 };
 
+/* *** deal with flow director mask on flexible payload *** */
+struct cmd_flow_director_flex_mask_result {
+	cmdline_fixed_string_t flow_director_flexmask;
+	uint8_t port_id;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t words_mask;
+	uint8_t words;
+	cmdline_fixed_string_t word_mask_list;
+};
+
+static inline int
+parse_word_masks_cfg(const char *q_arg,
+			     struct rte_eth_fdir_flex_masks *masks)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	enum fieldnames {
+		FLD_OFFSET = 0,
+		FLD_MASK,
+		_NUM_FLD
+	};
+	unsigned long int_fld[_NUM_FLD];
+	char *str_fld[_NUM_FLD];
+	int i;
+	unsigned size;
+
+	masks->nb_field = 0;
+	p = strchr(p0, '(');
+	while (p != NULL) {
+		++p;
+		p0 = strchr(p, ')');
+		if (p0 == NULL)
+			return -1;
+
+		size = p0 - p;
+		if (size >= sizeof(s))
+			return -1;
+
+		snprintf(s, sizeof(s), "%.*s", size, p);
+		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') != _NUM_FLD)
+			return -1;
+		for (i = 0; i < _NUM_FLD; i++) {
+			errno = 0;
+			int_fld[i] = strtoul(str_fld[i], &end, 0);
+			if (errno != 0 || end == str_fld[i] || int_fld[i] > UINT16_MAX)
+				return -1;
+		}
+		masks->field[masks->nb_field].offset =
+			(uint16_t)int_fld[FLD_OFFSET];
+		masks->field[masks->nb_field].bitmask =
+			~(uint16_t)int_fld[FLD_MASK];
+		masks->nb_field++;
+		if (masks->nb_field > 2) {
+			printf("exceeded max number of fields: %hu\n",
+				masks->nb_field);
+			return -1;
+		}
+		p = strchr(p0, '(');
+	}
+	return 0;
+}
+
+static void
+cmd_flow_director_flex_mask_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flex_mask_result *res = parsed_result;
+	struct rte_eth_fdir_flex_masks *flex_masks;
+	struct rte_eth_fdir_cfg fdir_cfg;
+	int ret = 0;
+	int cfg_size = 2 * sizeof(struct rte_eth_flex_mask) +
+		  offsetof(struct rte_eth_fdir_flex_masks, field);
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
+
+	flex_masks = (struct rte_eth_fdir_flex_masks *)rte_zmalloc_socket("CLI",
+		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
+
+	if (flex_masks == NULL) {
+		printf("fail to malloc memory to configure flex mask.\n");
+		return;
+	}
+
+	if (!strcmp(res->flow_type, "ip4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_IPV4_OTHER;
+	else if (!strcmp(res->flow_type, "udp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
+	else if (!strcmp(res->flow_type, "tcp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
+	else if (!strcmp(res->flow_type, "sctp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
+	else if (!strcmp(res->flow_type, "ip6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_IPV6_OTHER;
+	else if (!strcmp(res->flow_type, "udp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
+	else if (!strcmp(res->flow_type, "tcp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
+	else if (!strcmp(res->flow_type, "sctp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
+
+	flex_masks->words_mask = res->words;
+	ret = parse_word_masks_cfg(res->word_mask_list, flex_masks);
+	if (ret < 0) {
+		printf("error: Cannot parse words masks input.\n");
+		rte_free(flex_masks);
+		return;
+	}
+
+	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX_MASK;
+	fdir_cfg.cfg = flex_masks;
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+				     RTE_ETH_FILTER_SET, &fdir_cfg);
+	if (ret < 0)
+		printf("fdir flex mask setting error: (%s)\n", strerror(-ret));
+	rte_free(flex_masks);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexmask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_director_flexmask,
+				 "flow_director_flex_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_type,
+				 "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_words_mask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 words_mask, "words_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_words =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      words, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_word_mask_list =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 word_mask_list, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_mask = {
+	.f = cmd_flow_director_flex_mask_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex mask on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexmask,
+		(void *)&cmd_flow_director_flexmask_port_id,
+		(void *)&cmd_flow_director_flexmask_flow,
+		(void *)&cmd_flow_director_flexmask_flow_type,
+		(void *)&cmd_flow_director_flexmask_words_mask,
+		(void *)&cmd_flow_director_flexmask_words,
+		(void *)&cmd_flow_director_flexmask_word_mask_list,
+		NULL,
+	},
+};
+
 /* *** deal with flow director flexible payload configuration *** */
 struct cmd_flow_director_flexpayload_result {
 	cmdline_fixed_string_t flow_director_flexpayload;
@@ -8179,6 +8351,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_mask,
 	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
 	NULL,
 };
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (20 preceding siblings ...)
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 21/21] testpmd: add test command " Jingjing Wu
@ 2014-10-27 15:22   ` Thomas Monjalon
  2014-10-28  0:48   ` Zhang, Helin
                     ` (3 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-27 15:22 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> The patch set supports flow director on fortville.
> It includes:
>  - set up/tear down fortville resources to support flow director, such as queue and vsi.
>  - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
>  - support flushing flow director table (all filters).
>  - support operation to get flow director information.
>  - match status statistics, FD_ID report.
>  - support operation to configure flexible payload and its mask
>  - support flexible payload involved in comparison and flex bytes report.
> 
> v2 changes:
>  - create real fdir vsi and assign queue 0 pair to it.
>  - check filter status report on the rx queue 0
>  
> v3 changes:
>  - redefine filter APIs to support multi-kind filters
>  - support sctpv4 and sctpv6 type flows
>  - support flexible payload involved in comparison 
>  
> v4 changes:
>  - strip the filter APIs definitions from this patch set
>  - extend mbuf field to support flex bytes report
>  - fix typos

Previous version was acked by Chen Jing D(Mark) and Helin Zhang.
Have they reviewed the v4?
I won't review neither i40e nor testpmd parts in detail.
I prefer focusing on API (mbuf and ethdev) for my review.

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
@ 2014-10-27 16:57     ` Thomas Monjalon
  2014-10-28  1:18       ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-27 16:57 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> +/**
> + * A structure used to define the input for IPV4 UDP flow
> + */
> +struct rte_eth_udpv4_flow {
> +	uint32_t src_ip;      /**< IPv4 source address to match. */
> +	uint32_t dst_ip;      /**< IPv4 destination address to match. */
> +	uint16_t src_port;    /**< UDP Source port to match. */
> +	uint16_t dst_port;    /**< UDP Destination port to match. */
> +};
> +
> +/**
> + * A structure used to define the input for IPV4 TCP flow
> + */
> +struct rte_eth_tcpv4_flow {
> +	uint32_t src_ip;      /**< IPv4 source address to match. */
> +	uint32_t dst_ip;      /**< IPv4 destination address to match. */
> +	uint16_t src_port;    /**< TCP Source port to match. */
> +	uint16_t dst_port;    /**< TCP Destination port to match. */
> +};
> +
> +/**
> + * A structure used to define the input for IPV4 SCTP flow
> + */
> +struct rte_eth_sctpv4_flow {
> +	uint32_t src_ip;          /**< IPv4 source address to match. */
> +	uint32_t dst_ip;          /**< IPv4 destination address to match. */
> +	uint32_t verify_tag;      /**< verify tag to match */
> +};
> +
> +/**
> + * A structure used to define the input for IPV4 flow
> + */
> +struct rte_eth_ipv4_flow {
> +	uint32_t src_ip;      /**< IPv4 source address to match. */
> +	uint32_t dst_ip;      /**< IPv4 destination address to match. */
> +};

Why not defining only 1 structure?
struct rte_eth_ipv4_flow {
	uint32_t src_ip;
	uint32_t dst_ip;
	uint16_t src_port;
	uint16_t dst_port;
	uint32_t sctp_tag;
};

I think the same structure could be used for many filters (not only
flow director).

> +#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
> +/**
> + * A structure used to contain extend input of flow
> + */
> +struct rte_eth_fdir_flow_ext {
> +	uint16_t vlan_tci;
> +	uint8_t num_flexwords;         /**< number of flexwords */
> +	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
> +	uint16_t dest_id;              /**< destination vsi or pool id*/
> +};

Flexword should be explained.

> +/**
> + * A structure used to define the input for an flow director filter entry

typo: for *a* flow director

> + */
> +struct rte_eth_fdir_input {
> +	enum rte_eth_flow_type flow_type;      /**< type of flow */
> +	union rte_eth_fdir_flow flow;          /**< specific flow structure */
> +	struct rte_eth_fdir_flow_ext flow_ext; /**< specific flow info */
> +};

I don't understand the logic behind flow/flow_ext.
Why flow_ext is not merged into flow ?

> +/**
> + * Flow director report status
> + */
> +enum rte_eth_fdir_status {
> +	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< no report FDIR. */
> +	RTE_ETH_FDIR_REPORT_FD_ID,         /**< only report FD ID. */
> +	RTE_ETH_FDIR_REPORT_FD_ID_FLEX_4,  /**< report FD ID and 4 flex bytes. */
> +	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< report 8 flex bytes. */
> +};

The names and explanations are cryptics.
Is FD redundant with FDIR?

> +/**
> + * A structure used to define an action when match FDIR packet filter.
> + */
> +struct rte_eth_fdir_action {
> +	uint16_t rx_queue;        /**< queue assigned to if fdir match. */
> +	uint16_t cnt_idx;         /**< statistic counter index */

what is the action of "statistic counter index"?

> +	uint8_t  drop;            /**< accept or reject */
> +	uint8_t  flex_off;        /**< offset used define words to report */

still difficult to understand the flex logic

> +	enum rte_eth_fdir_status report_status;  /**< status report option */
> +};

> +/**
> + * A structure used to define the flow director filter entry by filter_ctl API
> + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
> + * RTE_ETH_FILTER_DELETE operations.
> + */
> +struct rte_eth_fdir_filter {
> +	uint32_t soft_id;                   /**< id */

Should the application handle the id numbering?
Why is it soft_id instead of id?

> +	struct rte_eth_fdir_input input;    /**< input set */
> +	struct rte_eth_fdir_action action;  /**< action taken when match */
> +};

It's really a hard job to define a clear and easy to use API.
It would be really interesting to have more people involved in this discussion.
Thanks
-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (21 preceding siblings ...)
  2014-10-27 15:22   ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Thomas Monjalon
@ 2014-10-28  0:48   ` Zhang, Helin
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                     ` (2 subsequent siblings)
  25 siblings, 0 replies; 123+ messages in thread
From: Zhang, Helin @ 2014-10-28  0:48 UTC (permalink / raw)
  To: Wu, Jingjing, dev

Acked-by: Helin Zhang <helin.zhang@intel.com>

I have reviewed the differences between v3 and v4. It seems OK for me.

> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Wednesday, October 22, 2014 9:01 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH v4 00/21] Support flow director programming on
> Fortville
> 
> The patch set supports flow director on fortville.
> It includes:
>  - set up/tear down fortville resources to support flow director, such as queue
> and vsi.
>  - support operation to add or delete 8 flow types of the flow director filters,
> they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
>  - support flushing flow director table (all filters).
>  - support operation to get flow director information.
>  - match status statistics, FD_ID report.
>  - support operation to configure flexible payload and its mask
>  - support flexible payload involved in comparison and flex bytes report.
> 
> v2 changes:
>  - create real fdir vsi and assign queue 0 pair to it.
>  - check filter status report on the rx queue 0
> 
> v3 changes:
>  - redefine filter APIs to support multi-kind filters
>  - support sctpv4 and sctpv6 type flows
>  - support flexible payload involved in comparison
> 
> v4 changes:
>  - strip the filter APIs definitions from this patch set
>  - extend mbuf field to support flex bytes report
>  - fix typos
> 
> Jingjing Wu (21):
>   i40e: set up and initialize flow director
>   i40e: tear down flow director
>   i40e: initialize flexible payload setting
>   ethdev: define structures for adding/deleting flow director
>   i40e: implement operations to add/delete flow director
>   testpmd: add test commands to add/delete flow director filter
>   i40e: match counter for flow director
>   mbuf: extend fdir field
>   i40e: report flow director match info to mbuf
>   testpmd: print extended fdir info in mbuf
>   ethdev: define structures for getting flow director information
>   i40e: implement operations to get fdir info
>   testpmd: display fdir statistics
>   i40e: implement operation to flush flow director table
>   testpmd: add test command to flush flow director table
>   ethdev: define structures for configuring flexible payload
>   i40e: implement operations to configure flexible payload
>   testpmd: add test command to configure flexible payload
>   ethdev:  define structures for configuring flex masks
>   i40e: implement operations to configure flexible masks
>   testpmd: add test command to configure flexible masks
> 
>  app/test-pmd/cmdline.c            |  812 ++++++++++++++++++++++++
>  app/test-pmd/config.c             |   38 +-
>  app/test-pmd/rxonly.c             |   14 +-
>  app/test-pmd/testpmd.h            |    3 +
>  lib/librte_ether/rte_eth_ctrl.h   |  266 ++++++++
>  lib/librte_ether/rte_ethdev.h     |   23 -
>  lib/librte_mbuf/rte_mbuf.h        |   12 +-
>  lib/librte_pmd_i40e/Makefile      |    2 +
>  lib/librte_pmd_i40e/i40e_ethdev.c |  127 +++-
>  lib/librte_pmd_i40e/i40e_ethdev.h |   34 +-
>  lib/librte_pmd_i40e/i40e_fdir.c   | 1222
> +++++++++++++++++++++++++++++++++++++
>  lib/librte_pmd_i40e/i40e_rxtx.c   |  225 ++++++-
>  12 files changed, 2723 insertions(+), 55 deletions(-)  create mode 100644
> lib/librte_pmd_i40e/i40e_fdir.c
> 
> --
> 1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director
  2014-10-27 16:57     ` Thomas Monjalon
@ 2014-10-28  1:18       ` Wu, Jingjing
  2014-10-28 13:17         ` Thomas Monjalon
  0 siblings, 1 reply; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-28  1:18 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Tuesday, October 28, 2014 12:58 AM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for
> adding/deleting flow director
> 
> 2014-10-22 09:01, Jingjing Wu:
> > +/**
> > + * A structure used to define the input for IPV4 UDP flow  */ struct
> > +rte_eth_udpv4_flow {
> > +	uint32_t src_ip;      /**< IPv4 source address to match. */
> > +	uint32_t dst_ip;      /**< IPv4 destination address to match. */
> > +	uint16_t src_port;    /**< UDP Source port to match. */
> > +	uint16_t dst_port;    /**< UDP Destination port to match. */
> > +};
> > +
> > +/**
> > + * A structure used to define the input for IPV4 TCP flow  */ struct
> > +rte_eth_tcpv4_flow {
> > +	uint32_t src_ip;      /**< IPv4 source address to match. */
> > +	uint32_t dst_ip;      /**< IPv4 destination address to match. */
> > +	uint16_t src_port;    /**< TCP Source port to match. */
> > +	uint16_t dst_port;    /**< TCP Destination port to match. */
> > +};
> > +
> > +/**
> > + * A structure used to define the input for IPV4 SCTP flow  */ struct
> > +rte_eth_sctpv4_flow {
> > +	uint32_t src_ip;          /**< IPv4 source address to match. */
> > +	uint32_t dst_ip;          /**< IPv4 destination address to match. */
> > +	uint32_t verify_tag;      /**< verify tag to match */
> > +};
> > +
> > +/**
> > + * A structure used to define the input for IPV4 flow  */ struct
> > +rte_eth_ipv4_flow {
> > +	uint32_t src_ip;      /**< IPv4 source address to match. */
> > +	uint32_t dst_ip;      /**< IPv4 destination address to match. */
> > +};
> 
> Why not defining only 1 structure?
> struct rte_eth_ipv4_flow {
> 	uint32_t src_ip;
> 	uint32_t dst_ip;
> 	uint16_t src_port;
> 	uint16_t dst_port;
> 	uint32_t sctp_tag;
> };
> 
> I think the same structure could be used for many filters (not only flow
> director).
> 
Yes, one structure can contain all the elements we need, but I think it will be clearer that each kind of flow type has its key words.
 
> > +#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
> > +/**
> > + * A structure used to contain extend input of flow  */ struct
> > +rte_eth_fdir_flow_ext {
> > +	uint16_t vlan_tci;
> > +	uint8_t num_flexwords;         /**< number of flexwords */
> > +	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
> > +	uint16_t dest_id;              /**< destination vsi or pool id*/
> > +};
> 
> Flexword should be explained.
> 
The flexword means the application can choose a part of packet's payload as key words to compare match. It is flexible. In Ixgbe, the flexwords is 1 word (2 bytes), while Fortville extend it to 8 words.

> > +/**
> > + * A structure used to define the input for an flow director filter
> > +entry
> 
> typo: for *a* flow director
Yes, will change.
> 
> > + */
> > +struct rte_eth_fdir_input {
> > +	enum rte_eth_flow_type flow_type;      /**< type of flow */
> > +	union rte_eth_fdir_flow flow;          /**< specific flow structure */
> > +	struct rte_eth_fdir_flow_ext flow_ext; /**< specific flow info */ };
> 
> I don't understand the logic behind flow/flow_ext.
> Why flow_ext is not merged into flow ?
> 
The flow defines the key words for each flow_type, while the flow_ext has other elements which have little to do with flow_type. For example the flexword, dst_id (can used as pool id), I think it is not reasonable to make it as an element in the flow.
> > +/**
> > + * Flow director report status
> > + */
> > +enum rte_eth_fdir_status {
> > +	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< no report FDIR. */
> > +	RTE_ETH_FDIR_REPORT_FD_ID,         /**< only report FD ID. */
> > +	RTE_ETH_FDIR_REPORT_FD_ID_FLEX_4,  /**< report FD ID and 4 flex
> bytes. */
> > +	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< report 8 flex bytes. */
> > +};
> 
> The names and explanations are cryptics.
The enum defines what will be reported when FIR match. Can be FD_ID or flex bytes
> Is FD redundant with FDIR?
Yes, good point. Will remove FD.
> 
> > +/**
> > + * A structure used to define an action when match FDIR packet filter.
> > + */
> > +struct rte_eth_fdir_action {
> > +	uint16_t rx_queue;        /**< queue assigned to if fdir match. */
> > +	uint16_t cnt_idx;         /**< statistic counter index */
> 
> what is the action of "statistic counter index"?
When FD match happened, the counter will increase. Fortville can support to configure the different counter for filter entries. The action is a part of a filter entry, so this element means which counter the entry will use.  
> 
> > +	uint8_t  drop;            /**< accept or reject */
> > +	uint8_t  flex_off;        /**< offset used define words to report */
> 
> still difficult to understand the flex logic
Just as mentioned above, Fortville can support 8 flex words comparing. But for reporting, only 4 or 8 bytes in the flex words can be reported. So need to specify the offset to choose the 4 or 8 bytes.
> 
> > +	enum rte_eth_fdir_status report_status;  /**< status report option
> > +*/ };
> 
> > +/**
> > + * A structure used to define the flow director filter entry by
> > +filter_ctl API
> > + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
> > + * RTE_ETH_FILTER_DELETE operations.
> > + */
> > +struct rte_eth_fdir_filter {
> > +	uint32_t soft_id;                   /**< id */
> 
> Should the application handle the id numbering?
> Why is it soft_id instead of id?
Yes, the soft_id is just id, is also reported id when entry match. The id is specified by user, and can be used to identify this entry, application should handle it.
> 
> > +	struct rte_eth_fdir_input input;    /**< input set */
> > +	struct rte_eth_fdir_action action;  /**< action taken when match */
> > +};
> 
> It's really a hard job to define a clear and easy to use API.
> It would be really interesting to have more people involved in this discussion.
Agree too.
Thank you!
> Thanks
> --
> Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director
  2014-10-28  1:18       ` Wu, Jingjing
@ 2014-10-28 13:17         ` Thomas Monjalon
  2014-10-29  1:29           ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 13:17 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

2014-10-28 01:18, Wu, Jingjing:
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> > 2014-10-22 09:01, Jingjing Wu:
> > > +#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
> > > +/**
> > > + * A structure used to contain extend input of flow  */ struct
> > > +rte_eth_fdir_flow_ext {
> > > +	uint16_t vlan_tci;
> > > +	uint8_t num_flexwords;         /**< number of flexwords */
> > > +	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
> > > +	uint16_t dest_id;              /**< destination vsi or pool id*/
> > > +};
> > 
> > Flexword should be explained.
> > 
> The flexword means the application can choose a part of packet's payload
> as key words to compare match. It is flexible.
> In Ixgbe, the flexwords is 1 word (2 bytes), while Fortville extend it to 8 words.

OK. The problem is that I don't know how to fill the flexwords bytes.
You should explain it in the doxygen comment.
You say it's flexible. Is it usable with a non-IP packet?
Please explain constraints and syntax.

> > > +struct rte_eth_fdir_input {
> > > +	enum rte_eth_flow_type flow_type;      /**< type of flow */
> > > +	union rte_eth_fdir_flow flow;          /**< specific flow structure */
> > > +	struct rte_eth_fdir_flow_ext flow_ext; /**< specific flow info */ };
> > 
> > I don't understand the logic behind flow/flow_ext.
> > Why flow_ext is not merged into flow ?
> > 
> The flow defines the key words for each flow_type, while the flow_ext
> has other elements which have little to do with flow_type.
> For example the flexword, dst_id (can used as pool id), I think it is not
> reasonable to make it as an element in the flow.

Sorry, I don't understand.
flow and flow_ext are associated with a flow type.
The comments are "specific flow structure" and "specific flow info" which
doesn't bring any useful information.

> > > +/**
> > > + * Flow director report status
> > > + */
> > > +enum rte_eth_fdir_status {
> > > +	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< no report FDIR. */
> > > +	RTE_ETH_FDIR_REPORT_FD_ID,         /**< only report FD ID. */
> > > +	RTE_ETH_FDIR_REPORT_FD_ID_FLEX_4,  /**< report FD ID and 4 flex bytes. */
> > > +	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< report 8 flex bytes. */
> > > +};
> > 
> > The names and explanations are cryptics.
> 
> The enum defines what will be reported when FIR match.
> Can be FD_ID or flex bytes

Just to be sure, have you understood that I'm requesting more explanations
in the comments to allow users of your API to understand it?

> > > +/**
> > > + * A structure used to define an action when match FDIR packet filter.
> > > + */
> > > +struct rte_eth_fdir_action {
> > > +	uint16_t rx_queue;        /**< queue assigned to if fdir match. */
> > > +	uint16_t cnt_idx;         /**< statistic counter index */
> > 
> > what is the action of "statistic counter index"?
> 
> When FD match happened, the counter will increase.

Which counter?
Which value should be set in cnt_idx?

> Fortville can support to configure the different counter for filter entries.
> The action is a part of a filter entry, so this element means which counter the entry will use.

I perfectly understand that you are writing some code to allow usage of
Fortville features through DPDK. Thank you for bringing new features.
But I want to know if I'm allowed to use it without reading the Fortville datasheet?
And could this API be shared by other hardwares (e.g. ixgbe)?

> > > +	uint8_t  drop;            /**< accept or reject */
> > > +	uint8_t  flex_off;        /**< offset used define words to report */
> > 
> > still difficult to understand the flex logic
> 
> Just as mentioned above, Fortville can support 8 flex words comparing.
> But for reporting, only 4 or 8 bytes in the flex words can be reported.
> So need to specify the offset to choose the 4 or 8 bytes.

I don't even know what are the meaning of these 4 or 8 bytes.
Please don't consider that every DPDK user know the Fortville datasheet.

> > > +/**
> > > + * A structure used to define the flow director filter entry by
> > > +filter_ctl API
> > > + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
> > > + * RTE_ETH_FILTER_DELETE operations.
> > > + */
> > > +struct rte_eth_fdir_filter {
> > > +	uint32_t soft_id;                   /**< id */
> > 
> > Should the application handle the id numbering?
> > Why is it soft_id instead of id?
> 
> Yes, the soft_id is just id, is also reported id when entry match.
> The id is specified by user, and can be used to identify this entry,
> application should handle it.

OK, so explain it in comments.
Or better, generate and return the id when creating a filter.

Thanks
-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 06/21] testpmd: add test commands to add/delete flow director filter
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
@ 2014-10-28 13:23     ` Thomas Monjalon
  0 siblings, 0 replies; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 13:23 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> --- a/app/test-pmd/testpmd.h
> +++ b/app/test-pmd/testpmd.h
> @@ -73,6 +73,9 @@ int main(int argc, char **argv);
>  #define NUMA_NO_CONFIG 0xFF
>  #define UMA_NO_CONFIG  0xFF
>  
> +#define BYTES_PER_WORD  2

This is an example of a constant which have a meaning.
But it should be in lib/librte_eal/common/include/rte_common.h

> +#define IPV6_ADDR_LEN 16

This one should be in lib/librte_net/rte_ip.h and should be used in ipv6_hdr.

Thanks
-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field Jingjing Wu
@ 2014-10-28 13:28     ` Thomas Monjalon
  2014-10-29  1:45       ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 13:28 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> extend fdir field to support flex bytes reported when fdir match

The commit log should explain why it is required (i40e?).
It will help to understand when digging into git history of mbuf file.

> --- a/lib/librte_mbuf/rte_mbuf.h
> +++ b/lib/librte_mbuf/rte_mbuf.h
> @@ -171,8 +173,14 @@ struct rte_mbuf {
>  	union {
>  		uint32_t rss;     /**< RSS hash result if RSS enabled */
>  		struct {
> -			uint16_t hash;
> -			uint16_t id;
> +			union {
> +				struct {
> +					uint16_t hash;
> +					uint16_t id;
> +				};
> +				uint32_t lo; /**< flexible bytes low*/
> +			};
> +			uint32_t hi;         /**< flexible bytes high*/
>  		} fdir;           /**< Filter identifier if FDIR enabled */

Please explain what could be the data of "flexible bytes high".

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information Jingjing Wu
@ 2014-10-28 13:44     ` Thomas Monjalon
  2014-10-29  2:10       ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 13:44 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> +/**
> + * A structure used to report the status of the flow director filters in use.
> + */
> +struct rte_eth_fdir {
> +	/** Number of filters with collision indication. */
> +	uint16_t collision;
> +	/** Number of free (non programmed) filters. */
> +	uint16_t free;
> +	/** The Lookup hash value of the added filter that updated the value
> +	   of the MAXLEN field */
> +	uint16_t maxhash;
> +	/** Longest linked list of filters in the table. */
> +	uint8_t maxlen;
> +	/** Number of added filters. */
> +	uint64_t add;
> +	/** Number of removed filters. */
> +	uint64_t remove;
> +	/** Number of failed added filters (no more space in device). */
> +	uint64_t f_add;
> +	/** Number of failed removed filters. */
> +	uint64_t f_remove;
> +};

rte_eth_fdir is a name which doesn't say what it really is.
This structure looks like a collection of statistics.
Why not rte_eth_fdir_stats?

> +struct rte_eth_fdir_ext {
> +	uint16_t guarant_spc;  /**< guaranteed spaces.*/
> +	uint16_t guarant_cnt;  /**< Number of filters in guaranteed spaces. */
> +	uint16_t best_spc;     /**< best effort spaces.*/
> +	uint16_t best_cnt;     /**< Number of filters in best effort spaces. */
> +};

I don't understand why this "extended" structure is not merged in the first one.
Adding new fields don't break old API.

> +/**
> + * A structure used to get the status information of flow director filter.
> + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_INFO operation.
> + */

OK content of this comment is good.
But the second sentence has no start.
Please try to have an uppercase letter at the beginning of your sentences,
and a subject followed by a verb.
(side note: this is also true for commit logs)

> +struct rte_eth_fdir_info {
> +	int mode;                 /**< if 0 disbale, if 1 enable*/

Typo: disbale

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 15/21] testpmd: add test command to flush flow director table
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 15/21] testpmd: add test command " Jingjing Wu
@ 2014-10-28 13:53     ` Thomas Monjalon
  0 siblings, 0 replies; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 13:53 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> +			"flush_flow_diretor (port_id)\n"

Typo: diretor

I know it's hard to write so much code in a small timeframe without any typo.
Especially when you are not english native.

But I'd like such simple errors would have been already reviewed
after the fourth version of a patchset.

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
@ 2014-10-28 14:14     ` Thomas Monjalon
  2014-10-29  3:21       ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 14:14 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> +/**
> + * A structure defined a field vector to specify each field.
> + */
> +struct rte_eth_field_vector {
> +	uint8_t offset;   /**< Source word offset */
> +	uint8_t size;     /**< Field Size defined in word units */
> +};

I'm sorry but I don't understand this patch at all.
I think the reason is that I need more information about flex filter.

> +
> +/**
> + * payload type
> + */
> +enum rte_eth_payload_type {
> +	RTE_ETH_PAYLOAD_UNKNOWN = 0,
> +	RTE_ETH_L2_PAYLOAD,
> +	RTE_ETH_L3_PAYLOAD,
> +	RTE_ETH_L4_PAYLOAD,
> +};
> +
>  /**
>   * flow type
>   */
> @@ -92,6 +111,30 @@ enum rte_eth_flow_type {
>  };
>  
>  /**
> + * A structure used to select fields extracted from the protocol layers to
> + * the Field Vector as flexible payload for filter
> + */
> +struct rte_eth_flex_payload_cfg {
> +	enum rte_eth_payload_type type;  /**< payload type */
> +	uint8_t nb_field;                /**< the number of following fields */
> +	struct rte_eth_field_vector field[0];
> +};
> +
> +#define RTE_ETH_FDIR_CFG_FLX      0x0001
> +/**
> + * A structure used to config FDIR filter global set
> + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_SET operation.
> + */
> +struct rte_eth_fdir_cfg {
> +	uint16_t cmd;  /**< sub command  */
> +	/**
> +	 * A pointer to structure for the configuration e.g.
> +	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
> +	*/
> +	void *cfg;
> +};

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 21/21] testpmd: add test command to configure flexible masks
  2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 21/21] testpmd: add test command " Jingjing Wu
@ 2014-10-28 14:18     ` Thomas Monjalon
  2014-10-29  2:35       ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-28 14:18 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 09:01, Jingjing Wu:
> add test command to configure flexible masks for each flow type
[...]
> --- a/app/test-pmd/cmdline.c
> +++ b/app/test-pmd/cmdline.c
> +			"flow_director_flex_mask (port_id)"
> +			" flow (ether|ip4|tcp4|udp4|sctp4|ip6|tcp6|udp6|sctp6)"
> +			" words_mask (words) (word_mask_list)\n"
> +			"    Configure mask of flex payload.\n\n"

Does it mean we cannot use it for PPP? or for IP over PPPoE?

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director
  2014-10-28 13:17         ` Thomas Monjalon
@ 2014-10-29  1:29           ` Wu, Jingjing
  0 siblings, 0 replies; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-29  1:29 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

Thanks for your comments.

Jingjing

> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Tuesday, October 28, 2014 9:18 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for
> adding/deleting flow director
> 
> 2014-10-28 01:18, Wu, Jingjing:
> > From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> > > 2014-10-22 09:01, Jingjing Wu:
> > > > +#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
> > > > +/**
> > > > + * A structure used to contain extend input of flow  */ struct
> > > > +rte_eth_fdir_flow_ext {
> > > > +	uint16_t vlan_tci;
> > > > +	uint8_t num_flexwords;         /**< number of flexwords */
> > > > +	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
> > > > +	uint16_t dest_id;              /**< destination vsi or pool id*/
> > > > +};
> > >
> > > Flexword should be explained.
> > >
> > The flexword means the application can choose a part of packet's
> > payload as key words to compare match. It is flexible.
> > In Ixgbe, the flexwords is 1 word (2 bytes), while Fortville extend it to 8
> words.
> 
> OK. The problem is that I don't know how to fill the flexwords bytes.
> You should explain it in the doxygen comment.
> You say it's flexible. Is it usable with a non-IP packet?
> Please explain constraints and syntax.
> 
OK. Will add more explanations in comments.

> > > > +struct rte_eth_fdir_input {
> > > > +	enum rte_eth_flow_type flow_type;      /**< type of flow */
> > > > +	union rte_eth_fdir_flow flow;          /**< specific flow structure */
> > > > +	struct rte_eth_fdir_flow_ext flow_ext; /**< specific flow info
> > > > +*/ };
> > >
> > > I don't understand the logic behind flow/flow_ext.
> > > Why flow_ext is not merged into flow ?
> > >
> > The flow defines the key words for each flow_type, while the flow_ext
> > has other elements which have little to do with flow_type.
> > For example the flexword, dst_id (can used as pool id), I think it is
> > not reasonable to make it as an element in the flow.
> 
> Sorry, I don't understand.
> flow and flow_ext are associated with a flow type.
Take an example like: flow_type is IPV4, and the key words in IP is supposed
to be dst_ip and src_ip. Other fields like dst_id has little to do with IPV4.

> The comments are "specific flow structure" and "specific flow info" which
> doesn't bring any useful information.
> 
OK, I think I need to change the comments.

> > > > +/**
> > > > + * Flow director report status
> > > > + */
> > > > +enum rte_eth_fdir_status {
> > > > +	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< no report FDIR. */
> > > > +	RTE_ETH_FDIR_REPORT_FD_ID,         /**< only report FD ID. */
> > > > +	RTE_ETH_FDIR_REPORT_FD_ID_FLEX_4,  /**< report FD ID and 4 flex
> bytes. */
> > > > +	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< report 8 flex bytes. */
> > > > +};
> > >
> > > The names and explanations are cryptics.
> >
> > The enum defines what will be reported when FIR match.
> > Can be FD_ID or flex bytes
> 
> Just to be sure, have you understood that I'm requesting more explanations
> in the comments to allow users of your API to understand it?
>
OK, get it.
 
> > > > +/**
> > > > + * A structure used to define an action when match FDIR packet filter.
> > > > + */
> > > > +struct rte_eth_fdir_action {
> > > > +	uint16_t rx_queue;        /**< queue assigned to if fdir match. */
> > > > +	uint16_t cnt_idx;         /**< statistic counter index */
> > >
> > > what is the action of "statistic counter index"?
> >
> > When FD match happened, the counter will increase.
> 
> Which counter?
> Which value should be set in cnt_idx?
> 
A hardware counter provided in Fortville. It supposed that the user know about
the hardware, or just set to 0 if don't specify a counter, a default counter will be
used for all entries. I will add more comments. 

> > Fortville can support to configure the different counter for filter entries.
> > The action is a part of a filter entry, so this element means which counter
> the entry will use.
> 
> I perfectly understand that you are writing some code to allow usage of
> Fortville features through DPDK. Thank you for bringing new features.
> But I want to know if I'm allowed to use it without reading the Fortville
> datasheet?
Yes, you can. But for same extended functions, need more explanation.
You are correct, I need to add more explanation.

> And could this API be shared by other hardwares (e.g. ixgbe)?
Yes, I also considered about it during design. And the integrating ixgbe's flow 
director to the API is ready. I plan to send another patch for it when 
this patch set is applied.

> 
> > > > +	uint8_t  drop;            /**< accept or reject */
> > > > +	uint8_t  flex_off;        /**< offset used define words to report */
> > >
> > > still difficult to understand the flex logic
> >
> > Just as mentioned above, Fortville can support 8 flex words comparing.
> > But for reporting, only 4 or 8 bytes in the flex words can be reported.
> > So need to specify the offset to choose the 4 or 8 bytes.
> 
> I don't even know what are the meaning of these 4 or 8 bytes.
Additional, these 4 or 8 bytes are a part of the 8 flex words.
> Please don't consider that every DPDK user know the Fortville datasheet.
OK. More comments.
> 
> > > > +/**
> > > > + * A structure used to define the flow director filter entry by
> > > > +filter_ctl API
> > > > + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
> > > > + * RTE_ETH_FILTER_DELETE operations.
> > > > + */
> > > > +struct rte_eth_fdir_filter {
> > > > +	uint32_t soft_id;                   /**< id */
> > >
> > > Should the application handle the id numbering?
> > > Why is it soft_id instead of id?
> >
> > Yes, the soft_id is just id, is also reported id when entry match.
> > The id is specified by user, and can be used to identify this entry,
> > application should handle it.
> 
> OK, so explain it in comments.
OK.
> Or better, generate and return the id when creating a filter.
> 
> Thanks
> --
> Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field
  2014-10-28 13:28     ` Thomas Monjalon
@ 2014-10-29  1:45       ` Wu, Jingjing
  0 siblings, 0 replies; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-29  1:45 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

Thanks for your comments.

Jingjing

> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Tuesday, October 28, 2014 9:28 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field
> 
> 2014-10-22 09:01, Jingjing Wu:
> > extend fdir field to support flex bytes reported when fdir match
> 
> The commit log should explain why it is required (i40e?).
> It will help to understand when digging into git history of mbuf file.
> 
OK. Will explain.

> > --- a/lib/librte_mbuf/rte_mbuf.h
> > +++ b/lib/librte_mbuf/rte_mbuf.h
> > @@ -171,8 +173,14 @@ struct rte_mbuf {
> >  	union {
> >  		uint32_t rss;     /**< RSS hash result if RSS enabled */
> >  		struct {
> > -			uint16_t hash;
> > -			uint16_t id;
> > +			union {
> > +				struct {
> > +					uint16_t hash;
> > +					uint16_t id;
> > +				};
> > +				uint32_t lo; /**< flexible bytes low*/
> > +			};
> > +			uint32_t hi;         /**< flexible bytes high*/
> >  		} fdir;           /**< Filter identifier if FDIR enabled */
> 
> Please explain what could be the data of "flexible bytes high".
> 
When set the report status to report flex bytes, flexible bytes high field
report first 4 bytes in "little endian" notation.
OK. Will add comments in detail.
> --
> Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information
  2014-10-28 13:44     ` Thomas Monjalon
@ 2014-10-29  2:10       ` Wu, Jingjing
  2014-10-29  9:48         ` Thomas Monjalon
  0 siblings, 1 reply; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-29  2:10 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

Thanks for your comments.

Jingjing

> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Tuesday, October 28, 2014 9:45 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for
> getting flow director information
> 
> 2014-10-22 09:01, Jingjing Wu:
> > +/**
> > + * A structure used to report the status of the flow director filters in use.
> > + */
> > +struct rte_eth_fdir {
> > +	/** Number of filters with collision indication. */
> > +	uint16_t collision;
> > +	/** Number of free (non programmed) filters. */
> > +	uint16_t free;
> > +	/** The Lookup hash value of the added filter that updated the value
> > +	   of the MAXLEN field */
> > +	uint16_t maxhash;
> > +	/** Longest linked list of filters in the table. */
> > +	uint8_t maxlen;
> > +	/** Number of added filters. */
> > +	uint64_t add;
> > +	/** Number of removed filters. */
> > +	uint64_t remove;
> > +	/** Number of failed added filters (no more space in device). */
> > +	uint64_t f_add;
> > +	/** Number of failed removed filters. */
> > +	uint64_t f_remove;
> > +};
> 
> rte_eth_fdir is a name which doesn't say what it really is.
> This structure looks like a collection of statistics.
> Why not rte_eth_fdir_stats?
> 
This structure is used in old flow director API. I moved it from rte_ethdev.h to rte_eth_ctrl.h and reuse it. As we discussed before, I think the old and new APIs will co-exist for one version. I also thought the name is not good enough, but I didn't change it because I want to keep the compatibility with the API used for ixgbe.
I think we can rename it when we are ready to remove the old flow director APIs. 

> > +struct rte_eth_fdir_ext {
> > +	uint16_t guarant_spc;  /**< guaranteed spaces.*/
> > +	uint16_t guarant_cnt;  /**< Number of filters in guaranteed spaces.
> */
> > +	uint16_t best_spc;     /**< best effort spaces.*/
> > +	uint16_t best_cnt;     /**< Number of filters in best effort spaces. */
> > +};
> 
> I don't understand why this "extended" structure is not merged in the first
> one.
> Adding new fields don't break old API.
> 
Just as you say the name of rte_eth_fdir is not suitable, but I didn't want to change 
It. What I want to use for operation RTE_ETH_FILTER_INFO is structure 
rte_eth_fdir_info. And then I define a new rte_eth_fdir_ext to get the info
rte_eth_fdir doesn't contain.
Of course we also can merger all the elements to the struct rte_eth_fdir_info 
Like below without reusing the old struct rte_eth_fdir, what do you think? 
struct rte_eth_fdir_info {
	int mode; 
	uint16_t collision;
	uint16_t free;
	uint16_t maxhash;
	uint8_t maxlen;
	uint64_t add;
	uint64_t remove;
	uint64_t f_add;
	uint64_t f_remove;
 	uint16_t guarant_spc;
	uint16_t guarant_cnt;
	uint16_t best_spc;
	uint16_t best_cnt;
};

> > +/**
> > + * A structure used to get the status information of flow director filter.
> > + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_INFO
> operation.
> > + */
> 
> OK content of this comment is good.
> But the second sentence has no start.
> Please try to have an uppercase letter at the beginning of your sentences,
> and a subject followed by a verb.
> (side note: this is also true for commit logs)
> 
OK, will change.

> > +struct rte_eth_fdir_info {
> > +	int mode;                 /**< if 0 disbale, if 1 enable*/
> 
> Typo: disbale
> 
OK, will change.
> --
> Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 21/21] testpmd: add test command to configure flexible masks
  2014-10-28 14:18     ` Thomas Monjalon
@ 2014-10-29  2:35       ` Wu, Jingjing
  0 siblings, 0 replies; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-29  2:35 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev



> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Tuesday, October 28, 2014 10:18 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v4 21/21] testpmd: add test command to
> configure flexible masks
> 
> 2014-10-22 09:01, Jingjing Wu:
> > add test command to configure flexible masks for each flow type
> [...]
> > --- a/app/test-pmd/cmdline.c
> > +++ b/app/test-pmd/cmdline.c
> > +			"flow_director_flex_mask (port_id)"
> > +			" flow
> (ether|ip4|tcp4|udp4|sctp4|ip6|tcp6|udp6|sctp6)"
> > +			" words_mask (words) (word_mask_list)\n"
> > +			"    Configure mask of flex payload.\n\n"
> 
> Does it mean we cannot use it for PPP? or for IP over PPPoE?
> 

Yes, we cannot use it for PPP. While about IP over PPPoE, I haven't test it yet. I have no idea
What the hardware will consider such packet as IP or Ethernet? I guess it will be Ethernet.

> --
> Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload
  2014-10-28 14:14     ` Thomas Monjalon
@ 2014-10-29  3:21       ` Wu, Jingjing
  2014-10-29  9:55         ` Thomas Monjalon
  0 siblings, 1 reply; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-29  3:21 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev



> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Tuesday, October 28, 2014 10:15 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for
> configuring flexible payload
> 
> 2014-10-22 09:01, Jingjing Wu:
> > +/**
> > + * A structure defined a field vector to specify each field.
> > + */
> > +struct rte_eth_field_vector {
> > +	uint8_t offset;   /**< Source word offset */
> > +	uint8_t size;     /**< Field Size defined in word units */
> > +};
> 
> I'm sorry but I don't understand this patch at all.
> I think the reason is that I need more information about flex filter.
> 

Yes, it is a little difficult to understand the behavior. Let me explain it as I can.
<1> flex words:
We can select where the 8 flex words are. It can be constituted of 1-3 partitions.
Each partition is defined as rte_eth_field_vector. 
For example:
if we set 
rte_eth_flex_payload_cfg = {
	.type = RTE_ETH_L4_PAYLOAD;
	.nb_field = 1;
	.field = {
		{0, 8},  /*offset = 0, size =8*/
	};
};
This means the 8 words from the beginning of l4 payload will be consider as flex words.
If we set 
rte_eth_flex_payload_cfg = {
	.type = RTE_ETH_L4_PAYLOAD;
	.nb_field = 1;
	.field = {
		{0, 2},  /*offset = 0, size =2*/
		{4, 6},  /*offset = 4, size =6*/
	};
};
This means the 2 words from the beginning of l4 payload plus 6 words form the offset 4
will be consider as flex words.

<2> flex mask:
As the <1> configuration, we already select 8 words as flex words. Then the flex mask
Will help us to define whether these word will participate in comparing. 
The flex mask can be constituted of 2 partitions. One is word mask, another is bit mask.
Word mask is defined in rte_eth_fdir_flex_masks.words_mask, it means bit i enables word i of flex words.
rte_eth_fdir_flex_masks.field specify each word's bit mask, Fortville support 2 word bitmask.

> > +
> > +/**
> > + * payload type
> > + */
> > +enum rte_eth_payload_type {
> > +	RTE_ETH_PAYLOAD_UNKNOWN = 0,
> > +	RTE_ETH_L2_PAYLOAD,
> > +	RTE_ETH_L3_PAYLOAD,
> > +	RTE_ETH_L4_PAYLOAD,
> > +};
> > +
> >  /**
> >   * flow type
> >   */
> > @@ -92,6 +111,30 @@ enum rte_eth_flow_type {  };
> >
> >  /**
> > + * A structure used to select fields extracted from the protocol
> > +layers to
> > + * the Field Vector as flexible payload for filter  */ struct
> > +rte_eth_flex_payload_cfg {
> > +	enum rte_eth_payload_type type;  /**< payload type */
> > +	uint8_t nb_field;                /**< the number of following fields */
> > +	struct rte_eth_field_vector field[0]; };
> > +
> > +#define RTE_ETH_FDIR_CFG_FLX      0x0001
> > +/**
> > + * A structure used to config FDIR filter global set
> > + * to support RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_SET operation.
> > + */
> > +struct rte_eth_fdir_cfg {
> > +	uint16_t cmd;  /**< sub command  */
> > +	/**
> > +	 * A pointer to structure for the configuration e.g.
> > +	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
> > +	*/
> > +	void *cfg;
> > +};

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information
  2014-10-29  2:10       ` Wu, Jingjing
@ 2014-10-29  9:48         ` Thomas Monjalon
  0 siblings, 0 replies; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-29  9:48 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

2014-10-29 02:10, Wu, Jingjing:
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> > 2014-10-22 09:01, Jingjing Wu:
> > > +/**
> > > + * A structure used to report the status of the flow director filters in use.
> > > + */
> > > +struct rte_eth_fdir {
> > > +	/** Number of filters with collision indication. */
> > > +	uint16_t collision;
> > > +	/** Number of free (non programmed) filters. */
> > > +	uint16_t free;
> > > +	/** The Lookup hash value of the added filter that updated the value
> > > +	   of the MAXLEN field */
> > > +	uint16_t maxhash;
> > > +	/** Longest linked list of filters in the table. */
> > > +	uint8_t maxlen;
> > > +	/** Number of added filters. */
> > > +	uint64_t add;
> > > +	/** Number of removed filters. */
> > > +	uint64_t remove;
> > > +	/** Number of failed added filters (no more space in device). */
> > > +	uint64_t f_add;
> > > +	/** Number of failed removed filters. */
> > > +	uint64_t f_remove;
> > > +};
> > 
> > rte_eth_fdir is a name which doesn't say what it really is.
> > This structure looks like a collection of statistics.
> > Why not rte_eth_fdir_stats?
> > 
> This structure is used in old flow director API. I moved it from rte_ethdev.h to rte_eth_ctrl.h and reuse it. As we discussed before, I think the old and new APIs will co-exist for one version. I also thought the name is not good enough, but I didn't change it because I want to keep the compatibility with the API used for ixgbe.
> I think we can rename it when we are ready to remove the old flow director APIs. 
> 
> > > +struct rte_eth_fdir_ext {
> > > +	uint16_t guarant_spc;  /**< guaranteed spaces.*/
> > > +	uint16_t guarant_cnt;  /**< Number of filters in guaranteed spaces.
> > */
> > > +	uint16_t best_spc;     /**< best effort spaces.*/
> > > +	uint16_t best_cnt;     /**< Number of filters in best effort spaces. */
> > > +};
> > 
> > I don't understand why this "extended" structure is not merged in the first
> > one.
> > Adding new fields don't break old API.
> > 
> Just as you say the name of rte_eth_fdir is not suitable, but I didn't want to change 
> It. What I want to use for operation RTE_ETH_FILTER_INFO is structure 
> rte_eth_fdir_info. And then I define a new rte_eth_fdir_ext to get the info
> rte_eth_fdir doesn't contain.
> Of course we also can merger all the elements to the struct rte_eth_fdir_info 
> Like below without reusing the old struct rte_eth_fdir, what do you think? 
> struct rte_eth_fdir_info {
> 	int mode; 
> 	uint16_t collision;
> 	uint16_t free;
> 	uint16_t maxhash;
> 	uint8_t maxlen;
> 	uint64_t add;
> 	uint64_t remove;
> 	uint64_t f_add;
> 	uint64_t f_remove;
>  	uint16_t guarant_spc;
> 	uint16_t guarant_cnt;
> 	uint16_t best_spc;
> 	uint16_t best_cnt;
> };

Yes, you are adding a new API while keeping temporarily the old one.
So it's better to add new structures with good names, so we will be able
to remove the whole old API without any other API change in next release.

Thanks
-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload
  2014-10-29  3:21       ` Wu, Jingjing
@ 2014-10-29  9:55         ` Thomas Monjalon
  0 siblings, 0 replies; 123+ messages in thread
From: Thomas Monjalon @ 2014-10-29  9:55 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

2014-10-29 03:21, Wu, Jingjing:
> 
> > -----Original Message-----
> > From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> > Sent: Tuesday, October 28, 2014 10:15 PM
> > To: Wu, Jingjing
> > Cc: dev@dpdk.org
> > Subject: Re: [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for
> > configuring flexible payload
> > 
> > 2014-10-22 09:01, Jingjing Wu:
> > > +/**
> > > + * A structure defined a field vector to specify each field.
> > > + */
> > > +struct rte_eth_field_vector {
> > > +	uint8_t offset;   /**< Source word offset */
> > > +	uint8_t size;     /**< Field Size defined in word units */
> > > +};
> > 
> > I'm sorry but I don't understand this patch at all.
> > I think the reason is that I need more information about flex filter.
> > 
> 
> Yes, it is a little difficult to understand the behavior. Let me explain it as I can.
> <1> flex words:
> We can select where the 8 flex words are. It can be constituted of 1-3 partitions.
> Each partition is defined as rte_eth_field_vector. 
> For example:
> if we set 
> rte_eth_flex_payload_cfg = {
> 	.type = RTE_ETH_L4_PAYLOAD;
> 	.nb_field = 1;
> 	.field = {
> 		{0, 8},  /*offset = 0, size =8*/
> 	};
> };
> This means the 8 words from the beginning of l4 payload will be consider as flex words.
> If we set 
> rte_eth_flex_payload_cfg = {
> 	.type = RTE_ETH_L4_PAYLOAD;
> 	.nb_field = 1;
> 	.field = {
> 		{0, 2},  /*offset = 0, size =2*/
> 		{4, 6},  /*offset = 4, size =6*/
> 	};
> };
> This means the 2 words from the beginning of l4 payload plus 6 words form the offset 4
> will be consider as flex words.
> 
> <2> flex mask:
> As the <1> configuration, we already select 8 words as flex words. Then the flex mask
> Will help us to define whether these word will participate in comparing. 
> The flex mask can be constituted of 2 partitions. One is word mask, another is bit mask.
> Word mask is defined in rte_eth_fdir_flex_masks.words_mask, it means bit i enables word i of flex words.
> rte_eth_fdir_flex_masks.field specify each word's bit mask, Fortville support 2 word bitmask.

OK thanks.
The most difficult task will be to explain it in the doxygen comment :)
Please try to be precise and concise in doxygen comments. It must be a
reference when using the API. If more examples are required, the developer
can look into the programmer's guide.

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville
  2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
                   ` (20 preceding siblings ...)
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
@ 2014-10-30  7:12 ` Cao, Min
  21 siblings, 0 replies; 123+ messages in thread
From: Cao, Min @ 2014-10-30  7:12 UTC (permalink / raw)
  To: Wu, Jingjing, dev

Tested-by: Min Cao <min.cao@intel.com>

Patch name: 		Support flow director programming on Fortville
Brief description: 	add flexible payload
Test Flag: 			Tested-by
Tester name: 		min.cao@intel.com
Result summary:		total 3 cases, 3 passed, 0 failed

Test Case 1:		
Name:				Fortville flow director with no flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 2:		
Name:				Fortville flow director with flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 3:		
Name:				Fortville flow director flush
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED


-----Original Message-----
From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
Sent: Friday, September 26, 2014 2:03 PM
To: dev@dpdk.org
Subject: [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - define new APIs to support multi-kind filters and their operations.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics and FD_ID report .
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison
 
v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 change:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison

Jingjing Wu (20):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  lib/librte_ether: new filter APIs definition
  lib/librte_ether: define structures for adding/deleting flow director
  i40e: implement operations to add/delete flow director
  app/test-pmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  i40e: report flow director match info to mbuf
  lib/librte_ether: define structures for getting flow director information
  i40e: implement operations to get fdir info
  app/test-pmd: display fdir statistics
  i40e: implement operation to flush flow director table
  app/test-pmd: add test command to flush flow director table
  lib/librte_ether: define structures for configuring flexible payload
  i40e: implement operations to configure flexible payload
  app/test-pmd: add test command to configure flexible payload
  lib/librte_ether: define structures for configuring flex masks
  i40e: implement operations to configure flexible masks
  app/test-pmd: add test command to configure flexible masks

 app/test-pmd/cmdline.c            |  813 +++++++++++++++++++++++++
 app/test-pmd/config.c             |   40 +-
 app/test-pmd/testpmd.h            |    3 +
 lib/librte_ether/Makefile         |    1 +
 lib/librte_ether/rte_eth_ctrl.h   |  343 +++++++++++
 lib/librte_ether/rte_ethdev.c     |   32 +
 lib/librte_ether/rte_ethdev.h     |   67 ++-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  148 ++++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   34 +-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1202 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  175 ++++++
 12 files changed, 2815 insertions(+), 45 deletions(-)
 create mode 100644 lib/librte_ether/rte_eth_ctrl.h
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 00/21] Support flow director programming on Fortville
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (22 preceding siblings ...)
  2014-10-28  0:48   ` Zhang, Helin
@ 2014-10-30  7:26   ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
                       ` (22 more replies)
  2014-10-30  7:34   ` [dpdk-dev] [PATCH v4 00/21] " Cao, Min
  2014-11-19  7:53   ` Cao, Min
  25 siblings, 23 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics, FD_ID report.
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison and flex bytes report.
 
v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 changes:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison
 
v4 changes:
 - strip the filter APIs definitions from this patch set
 - extend mbuf field to support flex bytes report
 - fix typos
 
v5 changes:
 - redefine structure rte_eth_fdir_info
 - add doxygen comments about flexible payload and mbuf extend
 - fix typos

Jingjing Wu (21):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  ethdev: define structures for adding/deleting flow director
  i40e: implement operations to add/delete flow director
  testpmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  mbuf: extend fdir field
  i40e: report flow director match info to mbuf
  testpmd: print extended fdir info in mbuf
  ethdev: define structures for getting flow director information
  i40e: implement operations to get fdir info
  testpmd: display fdir statistics
  i40e: implement operation to flush flow director table
  testpmd: add test command to flush flow director table
  ethdev: define structures for configuring flexible payload
  i40e: implement operations to configure flexible payload
  testpmd: add test command to configure flexible payload
  ethdev:  define structures for configuring flex masks
  i40e: implement operations to configure flexible masks
  testpmd: add test command to configure flexible masks

 app/test-pmd/cmdline.c            |  813 ++++++++++++++++++++++++
 app/test-pmd/config.c             |   42 +-
 app/test-pmd/rxonly.c             |   14 +-
 lib/librte_ether/rte_eth_ctrl.h   |  261 ++++++++
 lib/librte_mbuf/rte_mbuf.h        |   14 +-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  128 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   35 +-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1221 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  226 ++++++-
 10 files changed, 2728 insertions(+), 28 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  8:25       ` Wu, Jingjing
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 02/21] i40e: tear down " Jingjing Wu
                       ` (21 subsequent siblings)
  22 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

To support flow director, this patch sets up fortville resources. It  includes
 - Queue 0 pair allocated and set up for flow director
 - Create vsi
 - Reserve memzone for flow director programming packet

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/Makefile      |   2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  79 +++++++++++---
 lib/librte_pmd_i40e/i40e_ethdev.h |  31 +++++-
 lib/librte_pmd_i40e/i40e_fdir.c   | 222 ++++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   | 127 ++++++++++++++++++++++
 5 files changed, 447 insertions(+), 14 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

diff --git a/lib/librte_pmd_i40e/Makefile b/lib/librte_pmd_i40e/Makefile
index bd3428f..98e4bdf 100644
--- a/lib/librte_pmd_i40e/Makefile
+++ b/lib/librte_pmd_i40e/Makefile
@@ -91,6 +91,8 @@ SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_rxtx.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev_vf.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_pf.c
+SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_fdir.c
+
 # this lib depends upon:
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_eal lib/librte_ether
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_mempool lib/librte_mbuf
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index c39eedc..cea7725 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -778,6 +778,12 @@ i40e_dev_start(struct rte_eth_dev *dev)
 	i40e_vsi_queues_bind_intr(vsi);
 	i40e_vsi_enable_queues_intr(vsi);
 
+	/* enable FDIR MSIX interrupt */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
+		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
+	}
+
 	/* Enable all queues which have been configured */
 	ret = i40e_vsi_switch_queues(vsi, TRUE);
 	if (ret != I40E_SUCCESS) {
@@ -2615,16 +2621,30 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	case I40E_VSI_SRIOV :
 		vsi->nb_qps = pf->vf_nb_qps;
 		break;
+	case I40E_VSI_FDIR:
+		vsi->nb_qps = pf->fdir_nb_qps;
+		break;
 	default:
 		goto fail_mem;
 	}
-	ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
-	if (ret < 0) {
-		PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
-				vsi->seid, ret);
-		goto fail_mem;
-	}
-	vsi->base_queue = ret;
+	/*
+	 * The filter status descriptor is reported in rx queue 0,
+	 * while the tx queue for fdir filter programming has no
+	 * such constraints, can be non-zero queues.
+	 * To simplify it, choose FDIR vsi use queue 0 pair.
+	 * To make sure it will use queue 0 pair, queue allocation
+	 * need be done before this function is called
+	 */
+	if (type != I40E_VSI_FDIR) {
+		ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
+			if (ret < 0) {
+				PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
+						vsi->seid, ret);
+				goto fail_mem;
+			}
+			vsi->base_queue = ret;
+	} else
+		vsi->base_queue = I40E_FDIR_QUEUE_ID;
 
 	/* VF has MSIX interrupt in VF range, don't allocate here */
 	if (type != I40E_VSI_SRIOV) {
@@ -2756,9 +2776,25 @@ i40e_vsi_setup(struct i40e_pf *pf,
 		 * Since VSI is not created yet, only configure parameter,
 		 * will add vsi below.
 		 */
-	}
-	else {
-		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet");
+	} else if (type == I40E_VSI_FDIR) {
+		vsi->uplink_seid = uplink_vsi->uplink_seid;
+		ctxt.pf_num = hw->pf_id;
+		ctxt.vf_num = 0;
+		ctxt.uplink_seid = vsi->uplink_seid;
+		ctxt.connection_type = 0x1;     /* regular data port */
+		ctxt.flags = I40E_AQ_VSI_TYPE_PF;
+		ret = i40e_vsi_config_tc_queue_mapping(vsi, &ctxt.info,
+						I40E_DEFAULT_TCMAP);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to configure "
+					"TC queue mapping\n");
+			goto fail_msix_alloc;
+		}
+		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
+		ctxt.info.valid_sections |=
+			rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
+	} else {
+		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet\n");
 		goto fail_msix_alloc;
 	}
 
@@ -2943,8 +2979,16 @@ i40e_pf_setup(struct i40e_pf *pf)
 		PMD_DRV_LOG(ERR, "Could not get switch config, err %d", ret);
 		return ret;
 	}
-
-	/* VSI setup */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		/* make queue allocated first, let FDIR use queue pair 0*/
+		ret = i40e_res_pool_alloc(&pf->qp_pool, I40E_DEFAULT_QP_NUM_FDIR);
+		if (ret != I40E_FDIR_QUEUE_ID) {
+			PMD_DRV_LOG(ERR, "queue allocation fails for FDIR :"
+				    " ret =%d", ret);
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+	/*  main VSI setup */
 	vsi = i40e_vsi_setup(pf, I40E_VSI_MAIN, NULL, 0);
 	if (!vsi) {
 		PMD_DRV_LOG(ERR, "Setup of main vsi failed");
@@ -2954,9 +2998,20 @@ i40e_pf_setup(struct i40e_pf *pf)
 	dev_data->nb_rx_queues = vsi->nb_qps;
 	dev_data->nb_tx_queues = vsi->nb_qps;
 
+	/* setup FDIR after main vsi created.*/
+	if (pf->flags & I40E_FLAG_FDIR) {
+		ret = i40e_fdir_setup(pf);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to setup flow director\n");
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+
 	/* Configure filter control */
 	memset(&settings, 0, sizeof(settings));
 	settings.hash_lut_size = I40E_HASH_LUT_SIZE_128;
+	if (pf->flags & I40E_FLAG_FDIR)
+		settings.enable_fdir = TRUE;
 	/* Enable ethtype and macvlan filters */
 	settings.enable_ethtype = TRUE;
 	settings.enable_macvlan = TRUE;
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index a315adf..6d30f75 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -46,11 +46,12 @@
 /* number of VSIs and queue default setting */
 #define I40E_MAX_QP_NUM_PER_VF    16
 #define I40E_DEFAULT_QP_NUM_VMDQ  64
-#define I40E_DEFAULT_QP_NUM_FDIR  64
+#define I40E_DEFAULT_QP_NUM_FDIR  1
 #define I40E_UINT32_BIT_SIZE      (CHAR_BIT * sizeof(uint32_t))
 #define I40E_VFTA_SIZE            (4096 / I40E_UINT32_BIT_SIZE)
 /* Default TC traffic in case DCB is not enabled */
 #define I40E_DEFAULT_TCMAP        0x1
+#define I40E_FDIR_QUEUE_ID        0
 
 /* i40e flags */
 #define I40E_FLAG_RSS                   (1ULL << 0)
@@ -221,6 +222,27 @@ struct i40e_pf_vf {
 };
 
 /*
+ *  A structure used to define fields of a FDIR related info.
+ */
+struct i40e_fdir_info {
+	struct i40e_vsi *fdir_vsi;     /* pointer to fdir VSI structure */
+	uint16_t match_counter_index;  /* Statistic counter index used for fdir*/
+	struct i40e_tx_queue *txq;
+	struct i40e_rx_queue *rxq;
+	void *prg_pkt;                 /* memory for fdir program packet */
+	uint64_t dma_addr;             /* physic address of packet memory*/
+	/*
+	 * the rule how bytes stream is extracted as flexible payload
+	 * for each payload layer, the setting can up to three elements
+	 */
+	struct {
+		uint8_t offset;        /* offset in words from the beginning of payload */
+		uint8_t size;          /* size in words */
+	} flex_set[3][3];
+
+};
+
+/*
  * Structure to store private data specific for PF instance.
  */
 struct i40e_pf {
@@ -248,10 +270,10 @@ struct i40e_pf {
 	uint16_t vmdq_nb_qps; /* The number of queue pairs of VMDq */
 	uint16_t vf_nb_qps; /* The number of queue pairs of VF */
 	uint16_t fdir_nb_qps; /* The number of queue pairs of Flow Director */
-
 	/* store VXLAN UDP ports */
 	uint16_t vxlan_ports[I40E_MAX_PF_UDP_OFFLOAD_PORTS];
 	uint16_t vxlan_bitmap; /* Vxlan bit mask */
+	struct i40e_fdir_info fdir; /* flow director info */
 };
 
 enum pending_msg {
@@ -352,6 +374,11 @@ int i40e_vsi_vlan_pvid_set(struct i40e_vsi *vsi,
 int i40e_vsi_config_vlan_stripping(struct i40e_vsi *vsi, bool on);
 uint64_t i40e_config_hena(uint64_t flags);
 uint64_t i40e_parse_hena(uint64_t flags);
+enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+int i40e_fdir_setup(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
new file mode 100644
index 0000000..a44bb73
--- /dev/null
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -0,0 +1,222 @@
+/*-
+ *   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 <sys/queue.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdint.h>
+#include <string.h>
+#include <unistd.h>
+#include <stdarg.h>
+
+#include <rte_ether.h>
+#include <rte_ethdev.h>
+#include <rte_log.h>
+#include <rte_memzone.h>
+#include <rte_malloc.h>
+
+#include "i40e_logs.h"
+#include "i40e/i40e_type.h"
+#include "i40e_ethdev.h"
+#include "i40e_rxtx.h"
+
+#define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#define I40E_FDIR_PKT_LEN                   512
+
+#define I40E_COUNTER_PF           2
+/* Statistic counter index for one pf */
+#define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+#define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
+
+static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+
+static int
+i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
+{
+	struct i40e_hw *hw = I40E_VSI_TO_HW(rxq->vsi);
+	struct i40e_hmc_obj_rxq rx_ctx;
+	int err = I40E_SUCCESS;
+
+	memset(&rx_ctx, 0, sizeof(struct i40e_hmc_obj_rxq));
+	/* Init the RX queue in hardware */
+	rx_ctx.dbuff = I40E_RXBUF_SZ_1024 >> I40E_RXQ_CTX_DBUFF_SHIFT;
+	rx_ctx.hbuff = 0;
+	rx_ctx.base = rxq->rx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
+	rx_ctx.qlen = rxq->nb_rx_desc;
+#ifndef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+	rx_ctx.dsize = 1;
+#endif
+	rx_ctx.dtype = i40e_header_split_none;
+	rx_ctx.hsplit_0 = I40E_HEADER_SPLIT_NONE;
+	rx_ctx.rxmax = ETHER_MAX_LEN;
+	rx_ctx.tphrdesc_ena = 1;
+	rx_ctx.tphwdesc_ena = 1;
+	rx_ctx.tphdata_ena = 1;
+	rx_ctx.tphhead_ena = 1;
+	rx_ctx.lrxqthresh = 2;
+	rx_ctx.crcstrip = 0;
+	rx_ctx.l2tsel = 1;
+	rx_ctx.showiv = 1;
+	rx_ctx.prefena = 1;
+
+	err = i40e_clear_lan_rx_queue_context(hw, rxq->reg_idx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to clear FDIR RX queue context.");
+		return err;
+	}
+	err = i40e_set_lan_rx_queue_context(hw, rxq->reg_idx, &rx_ctx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to set FDIR RX queue context.");
+		return err;
+	}
+	rxq->qrx_tail = hw->hw_addr +
+		I40E_QRX_TAIL(rxq->vsi->base_queue);
+
+	rte_wmb();
+	/* Init the RX tail regieter. */
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, 0);
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, rxq->nb_rx_desc - 1);
+
+	return err;
+}
+
+/*
+ * i40e_fdir_setup - reserve and initialize the Flow Director resources
+ * @pf: board private structure
+ */
+int
+i40e_fdir_setup(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_vsi *vsi;
+	int err = I40E_SUCCESS;
+	char z_name[RTE_MEMZONE_NAMESIZE];
+	const struct rte_memzone *mz = NULL;
+	struct rte_eth_dev *eth_dev = pf->adapter->eth_dev;
+
+	PMD_DRV_LOG(INFO, "FDIR HW Capabilities: num_filters_guaranteed = %u,"
+			" num_filters_best_effort = %u.",
+			hw->func_caps.fd_filters_guaranteed,
+			hw->func_caps.fd_filters_best_effort);
+
+	vsi = pf->fdir.fdir_vsi;
+	if (vsi) {
+		PMD_DRV_LOG(ERR, "FDIR vsi pointer needs"
+				 "to be null before creation.");
+		return I40E_ERR_BAD_PTR;
+	}
+	/* make new FDIR VSI */
+	vsi = i40e_vsi_setup(pf, I40E_VSI_FDIR, pf->main_vsi, 0);
+	if (!vsi) {
+		PMD_DRV_LOG(ERR, "Couldn't create FDIR VSI.");
+		return I40E_ERR_NO_AVAILABLE_VSI;
+	}
+	pf->fdir.fdir_vsi = vsi;
+
+	/*Fdir tx queue setup*/
+	err = i40e_fdir_setup_tx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR TX resources.");
+		goto fail_setup_tx;
+	}
+
+	/*Fdir rx queue setup*/
+	err = i40e_fdir_setup_rx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR RX resources.");
+		goto fail_setup_rx;
+	}
+
+	err = i40e_tx_queue_init(pf->fdir.txq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR TX initialization.");
+		goto fail_mem;
+	}
+
+	/* need switch on before dev start*/
+	err = i40e_switch_tx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do fdir TX switch on.");
+		goto fail_mem;
+	}
+
+	/* Init the rx queue in hardware */
+	err = i40e_fdir_rx_queue_init(pf->fdir.rxq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX initialization.");
+		goto fail_mem;
+	}
+
+	/* switch on rx queue */
+	err = i40e_switch_rx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX switch on.");
+		goto fail_mem;
+	}
+
+	/* reserve memory for the fdir programming packet */
+	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
+			eth_dev->driver->pci_drv.name,
+			I40E_FDIR_MZ_NAME,
+			eth_dev->data->port_id);
+	mz = rte_memzone_lookup(z_name);
+	if (!mz) {
+		mz = rte_memzone_reserve(z_name,
+				I40E_FDIR_PKT_LEN,
+				rte_socket_id(),
+				0);
+		if (!mz) {
+			PMD_DRV_LOG(ERR, "Cannot init memzone for"
+				"flow director program packet.");
+			err = I40E_ERR_NO_MEMORY;
+			goto fail_mem;
+		}
+	}
+	pf->fdir.prg_pkt = mz->addr;
+	pf->fdir.dma_addr = (uint64_t)mz->phys_addr;
+	pf->fdir.match_counter_index = I40E_COUNTER_INDEX_FDIR(hw->pf_id);
+	PMD_DRV_LOG(INFO, "FDIR setup successfully, with programming queue %u.",
+		    vsi->base_queue);
+	return I40E_SUCCESS;
+
+fail_mem:
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+fail_setup_rx:
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+fail_setup_tx:
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return err;
+}
\ No newline at end of file
diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 315a9c0..f2334de 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -2150,6 +2150,8 @@ i40e_tx_queue_init(struct i40e_tx_queue *txq)
 	tx_ctx.base = txq->tx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
 	tx_ctx.qlen = txq->nb_tx_desc;
 	tx_ctx.rdylist = rte_le_to_cpu_16(vsi->info.qs_handle[0]);
+	if (vsi->type == I40E_VSI_FDIR)
+		tx_ctx.fd_ena = TRUE;
 
 	err = i40e_clear_lan_tx_queue_context(hw, pf_q);
 	if (err != I40E_SUCCESS) {
@@ -2366,3 +2368,128 @@ i40e_dev_clear_queues(struct rte_eth_dev *dev)
 		i40e_reset_rx_queue(dev->data->rx_queues[i]);
 	}
 }
+
+enum i40e_status_code
+i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_tx_queue *txq;
+	const struct rte_memzone *tz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_TX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	txq = rte_zmalloc_socket("i40e fdir tx queue",
+				  sizeof(struct i40e_tx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!txq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"tx queue structure\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(struct i40e_tx_desc) * I40E_FDIR_NUM_TX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	tz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_tx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!tz) {
+		i40e_dev_tx_queue_release(txq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for TX\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	txq->nb_tx_desc = I40E_FDIR_NUM_TX_DESC;
+	txq->queue_id = I40E_FDIR_QUEUE_ID;
+	txq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	txq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	txq->tx_ring_phys_addr = rte_mem_phy2mch(tz->memseg_id, tz->phys_addr);
+#else
+	txq->tx_ring_phys_addr = (uint64_t)tz->phys_addr;
+#endif
+	txq->tx_ring = (struct i40e_tx_desc *)tz->addr;
+	/*
+	 * don't need to allocate software ring and reset for the fdir
+	 * program queue just set the queue has been configured.
+	 */
+	txq->q_set = TRUE;
+	pf->fdir.txq = txq;
+
+	return I40E_SUCCESS;
+}
+
+enum i40e_status_code
+i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_rx_queue *rxq;
+	const struct rte_memzone *rz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_RX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	rxq = rte_zmalloc_socket("i40e fdir rx queue",
+				  sizeof(struct i40e_rx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!rxq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"rx queue structure\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(union i40e_rx_desc) * I40E_FDIR_NUM_RX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	rz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_rx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!rz) {
+		i40e_dev_rx_queue_release(rxq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for RX\n");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	rxq->nb_rx_desc = I40E_FDIR_NUM_RX_DESC;
+	rxq->queue_id = I40E_FDIR_QUEUE_ID;
+	rxq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	rxq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	rxq->rx_ring_phys_addr = rte_mem_phy2mch(rz->memseg_id, rz->phys_addr);
+#else
+	rxq->rx_ring_phys_addr = (uint64_t)rz->phys_addr;
+#endif
+	rxq->rx_ring = (union i40e_rx_desc *)rz->addr;
+
+	/*
+	 * Don't need to allocate software ring and reset for the fdir
+	 * rx queue, just set the queue has been configured.
+	 */
+	rxq->q_set = TRUE;
+	pf->fdir.rxq = rxq;
+
+	return I40E_SUCCESS;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 02/21] i40e: tear down flow director
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-11-19  7:53       ` Cao, Min
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 03/21] i40e: initialize flexible payload setting Jingjing Wu
                       ` (20 subsequent siblings)
  22 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

To support flow director tear down, this patch includes
 - queue 0 pair release
 - release vsi

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  4 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |  1 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 19 +++++++++++++++++++
 3 files changed, 23 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index cea7725..812c91d 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -514,7 +514,8 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 	return 0;
 
 err_setup_pf_switch:
-	rte_free(pf->main_vsi);
+	i40e_fdir_teardown(pf);
+	i40e_vsi_release(pf->main_vsi);
 err_get_mac_addr:
 err_configure_lan_hmc:
 	(void)i40e_shutdown_lan_hmc(hw);
@@ -849,6 +850,7 @@ i40e_dev_close(struct rte_eth_dev *dev)
 	i40e_shutdown_lan_hmc(hw);
 
 	/* release all the existing VSIs and VEBs */
+	i40e_fdir_teardown(pf);
 	i40e_vsi_release(pf->main_vsi);
 
 	/* shutdown the adminq */
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 6d30f75..35fcc46 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -379,6 +379,7 @@ enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
 enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
+void i40e_fdir_teardown(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index a44bb73..bb474d2 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -219,4 +219,23 @@ fail_setup_tx:
 	i40e_vsi_release(vsi);
 	pf->fdir.fdir_vsi = NULL;
 	return err;
+}
+
+/*
+ * i40e_fdir_teardown - release the Flow Director resources
+ * @pf: board private structure
+ */
+void
+i40e_fdir_teardown(struct i40e_pf *pf)
+{
+	struct i40e_vsi *vsi;
+
+	vsi = pf->fdir.fdir_vsi;
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return;
 }
\ No newline at end of file
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 03/21] i40e: initialize flexible payload setting
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 02/21] i40e: tear down " Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
                       ` (19 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Set flexible payload related registers to default value at initialization time.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 37 ++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_fdir.c   | 51 ++++++++++++++++++++++++++++++++++++++-
 2 files changed, 87 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 812c91d..8195e8a 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -328,6 +328,36 @@ static struct rte_driver rte_i40e_driver = {
 
 PMD_REGISTER_DRIVER(rte_i40e_driver);
 
+/*
+ * Initialize registers for flexible payload, which should be set by NVM.
+ * This should be removed from code once it is fixed in NVM.
+ */
+static inline void i40e_flex_payload_reg_init(struct i40e_hw *hw)
+{
+#ifndef I40E_GLQF_ORT
+#define I40E_GLQF_ORT(_i)    (0x00268900 + ((_i) * 4))
+#endif
+	/* GLQF_ORT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(18), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(19), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(26), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(30), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(33), 0x000000E0);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(34), 0x000000E3);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(35), 0x000000E6);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(20), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(23), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(63), 0x0000002D);
+
+#ifndef I40E_GLQF_PIT
+#define I40E_GLQF_PIT(_i)    (0x00268C80 + ((_i) * 4))
+#endif
+	/* GLQF_PIT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(16), 0x00007480);
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(17), 0x00007440);
+
+}
+
 static int
 eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
                   struct rte_eth_dev *dev)
@@ -391,6 +421,13 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 		return ret;
 	}
 
+	/*
+	 * To work around the NVM issue,initialize registers
+	 * for flexible payload by software.
+	 * It should be removed once issues are fixed in NVM.
+	 */
+	i40e_flex_payload_reg_init(hw);
+
 	/* Initialize the parameters for adminq */
 	i40e_init_adminq_parameter(hw);
 	ret = i40e_init_adminq(hw);
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index bb474d2..848fb92 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -111,6 +111,53 @@ i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
 }
 
 /*
+ * Initialize the configuration about bytes stream extracted as flexible payload
+ * and mask setting
+ */
+static inline void
+i40e_init_flx_pld(struct i40e_pf *pf)
+{
+	uint8_t pctype;
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+
+	/*
+	 * Define the bytes stream extracted as flexible payload in
+	 * field vector. By default, select 8 words from the beginning
+	 * of payload as flexible payload.
+	 */
+	memset(pf->fdir.flex_set, 0, sizeof(pf->fdir.flex_set));
+
+	/* initialize the flexible payload for L2 payload*/
+	pf->fdir.flex_set[0][0].offset = 0;
+	pf->fdir.flex_set[0][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(0), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(1), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(2), 0x0000FC2A);/*non-used*/
+
+	/* initialize the flexible payload for L3 payload*/
+	pf->fdir.flex_set[1][0].offset = 0;
+	pf->fdir.flex_set[1][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(3), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(4), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(5), 0x0000FC2A);/*non-used*/
+
+	/* initialize the flexible payload for L4 payload*/
+	pf->fdir.flex_set[2][0].offset = 0;
+	pf->fdir.flex_set[2][0].size = 8;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(6), 0x0000C900);
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(7), 0x0000FC29);/*non-used*/
+	I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(8), 0x0000FC2A);/*non-used*/
+
+	/* initialize the masks */
+	for (pctype = I40E_FILTER_PCTYPE_NONF_IPV4_UDP;
+	     pctype <= I40E_FILTER_PCTYPE_FRAG_IPV6; pctype++) {
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), 0);
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, 0), 0);
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, 1), 0);
+	}
+}
+
+/*
  * i40e_fdir_setup - reserve and initialize the Flow Director resources
  * @pf: board private structure
  */
@@ -184,6 +231,8 @@ i40e_fdir_setup(struct i40e_pf *pf)
 		goto fail_mem;
 	}
 
+	i40e_init_flx_pld(pf);
+
 	/* reserve memory for the fdir programming packet */
 	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
 			eth_dev->driver->pci_drv.name,
@@ -238,4 +287,4 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 	i40e_vsi_release(vsi);
 	pf->fdir.fdir_vsi = NULL;
 	return;
-}
\ No newline at end of file
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 04/21] ethdev: define structures for adding/deleting flow director
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (2 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 03/21] i40e: initialize flexible payload setting Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete " Jingjing Wu
                       ` (18 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

New structures are defined to add or delete flow director filter

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 171 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 171 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index b4ab731..77b784e 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -52,6 +52,7 @@ extern "C" {
 enum rte_filter_type {
 	RTE_ETH_FILTER_NONE = 0,
 	RTE_ETH_FILTER_TUNNEL,
+	RTE_ETH_FILTER_FDIR,
 	RTE_ETH_FILTER_MAX
 };
 
@@ -132,6 +133,176 @@ struct rte_eth_tunnel_filter_conf {
 	uint16_t queue_id;      /** < queue number. */
 };
 
+/**
+ * Define all structures for Flow Director Filter type corresponding with specific operations.
+ */
+
+/**
+ * Flow type
+ */
+enum rte_eth_flow_type {
+	RTE_ETH_FLOW_TYPE_NONE = 0x0,
+	RTE_ETH_FLOW_TYPE_UDPV4,
+	RTE_ETH_FLOW_TYPE_TCPV4,
+	RTE_ETH_FLOW_TYPE_SCTPV4,
+	RTE_ETH_FLOW_TYPE_IPV4_OTHER,
+	RTE_ETH_FLOW_TYPE_UDPV6,
+	RTE_ETH_FLOW_TYPE_TCPV6,
+	RTE_ETH_FLOW_TYPE_SCTPV6,
+	RTE_ETH_FLOW_TYPE_IPV6_OTHER,
+};
+
+/**
+ * A structure used to define the input for IPV4 UDP flow
+ */
+struct rte_eth_udpv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+	uint16_t src_port;    /**< UDP source port to match. */
+	uint16_t dst_port;    /**< UDP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 TCP flow
+ */
+struct rte_eth_tcpv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+	uint16_t src_port;    /**< TCP source port to match. */
+	uint16_t dst_port;    /**< TCP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 SCTP flow
+ */
+struct rte_eth_sctpv4_flow {
+	uint32_t src_ip;          /**< IPv4 source address to match. */
+	uint32_t dst_ip;          /**< IPv4 destination address to match. */
+	uint32_t verify_tag;      /**< Verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV4 flow
+ */
+struct rte_eth_ipv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 UDP flow
+ */
+struct rte_eth_udpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint16_t src_port;       /**< UDP source port to match. */
+	uint16_t dst_port;       /**< UDP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 TCP flow
+ */
+struct rte_eth_tcpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint16_t src_port;       /**< TCP source port to match. */
+	uint16_t dst_port;       /**< TCP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 SCTP flow
+ */
+struct rte_eth_sctpv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+	uint32_t verify_tag;     /**< Verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV6 flow
+ */
+struct rte_eth_ipv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+};
+
+/**
+ * An union contains the inputs for all types of flow
+ */
+union rte_eth_fdir_flow {
+	struct rte_eth_udpv4_flow  udp4_flow;
+	struct rte_eth_tcpv4_flow  tcp4_flow;
+	struct rte_eth_sctpv4_flow sctp4_flow;
+	struct rte_eth_ipv4_flow   ip4_flow;
+	struct rte_eth_udpv6_flow  udp6_flow;
+	struct rte_eth_tcpv6_flow  tcp6_flow;
+	struct rte_eth_sctpv6_flow sctp6_flow;
+	struct rte_eth_ipv6_flow   ip6_flow;
+};
+
+#define RTE_ETH_FDIR_MAX_FLEXWORD_LEN  8
+/**
+ * A structure used to contain extend input of flow
+ */
+struct rte_eth_fdir_flow_ext {
+	uint16_t vlan_tci;
+	uint8_t num_flexwords;         /**< Number of flexwords */
+	uint16_t flexwords[RTE_ETH_FDIR_MAX_FLEXWORD_LEN];
+	/**< It is filled by the flexible payload to match. Each word is in little endian. */
+	uint16_t dest_id;
+	/**< Destination vsi or pool id. 0 indicates PF by default.*/
+};
+
+/**
+ * A structure used to define the input for a flow director filter entry
+ */
+struct rte_eth_fdir_input {
+	enum rte_eth_flow_type flow_type;      /**< Type of flow */
+	union rte_eth_fdir_flow flow;
+	/**< Flow fields to match, dependent on flow_type */
+	struct rte_eth_fdir_flow_ext flow_ext;
+	/**< Additional fields to match */
+};
+
+/**
+ * Flow director report status
+ * It defines what will be reported if fdir entry is matched.
+ */
+enum rte_eth_fdir_status {
+	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< Report nothing. */
+	RTE_ETH_FDIR_REPORT_ID,            /**< Only report FD ID. */
+	RTE_ETH_FDIR_REPORT_ID_FLEX_4,     /**< Report FD ID and 4 flex bytes. */
+	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< Report 8 flex bytes. */
+};
+
+/**
+ * A structure used to define an action when match FDIR packet filter.
+ */
+struct rte_eth_fdir_action {
+	uint16_t rx_queue;        /**< Queue assigned to if fdir match. */
+	uint16_t cnt_idx;
+	/**< Statistic counter index in hardware. If set to 0, default counter will
+	     be used for all flow director entries on each device. */
+	uint8_t  drop;            /**< Accept or reject */
+	enum rte_eth_fdir_status report_status;  /**< Status report option */
+	uint8_t flex_off;
+	/**< If report_status is RTE_ETH_FDIR_REPORT_ID_FLEX_4 or
+	     RTE_ETH_FDIR_REPORT_FLEX_8, flex_off specifies where the reported
+	     flex bytes start from in flexible payload. */
+};
+
+/**
+ * A structure used to define the flow director filter entry by filter_ctrl API
+ * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
+ * RTE_ETH_FILTER_DELETE operations.
+ */
+struct rte_eth_fdir_filter {
+	uint32_t soft_id;
+	/**< ID, an unique value is required when deal with fdir entry */
+	struct rte_eth_fdir_input input;    /**< Input set */
+	struct rte_eth_fdir_action action;  /**< Action taken when match */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete flow director
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (3 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-11-05 21:18       ` De Lara Guarch, Pablo
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
                       ` (17 subsequent siblings)
  22 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Deal with two operations for flow director
 - RTE_ETH_FILTER_ADD
 - RTE_ETH_FILTER_DELETE
Encode the flow inputs to programming packet.
Sent the packet to filter programming queue and check status
on the status report queue.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |   3 +
 lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 622 ++++++++++++++++++++++++++++++++++++++
 3 files changed, 628 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 8195e8a..fb43efb 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -4577,6 +4577,7 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 		     enum rte_filter_op filter_op,
 		     void *arg)
 {
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
 	int ret = 0;
 
 	if (dev == NULL)
@@ -4585,6 +4586,8 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 	switch (filter_type) {
 	case RTE_ETH_FILTER_TUNNEL:
 		ret = i40e_tunnel_filter_handle(dev, filter_op, arg);
+	case RTE_ETH_FILTER_FDIR:
+		ret = i40e_fdir_ctrl_func(pf, filter_op, arg);
 		break;
 	default:
 		PMD_DRV_LOG(WARNING, "Filter type (%d) not supported",
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 35fcc46..562ccbd 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -380,6 +380,9 @@ enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
 void i40e_fdir_teardown(struct i40e_pf *pf);
+int i40e_fdir_ctrl_func(struct i40e_pf *pf,
+			  enum rte_filter_op filter_op,
+			  void *arg);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 848fb92..afc9702 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -44,6 +44,10 @@
 #include <rte_log.h>
 #include <rte_memzone.h>
 #include <rte_malloc.h>
+#include <rte_ip.h>
+#include <rte_udp.h>
+#include <rte_tcp.h>
+#include <rte_sctp.h>
 
 #include "i40e_logs.h"
 #include "i40e/i40e_type.h"
@@ -51,7 +55,23 @@
 #include "i40e_rxtx.h"
 
 #define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#ifndef IPV6_ADDR_LEN
+#define IPV6_ADDR_LEN              16
+#endif
+
 #define I40E_FDIR_PKT_LEN                   512
+#define I40E_FDIR_IP_DEFAULT_LEN            420
+#define I40E_FDIR_IP_DEFAULT_TTL            0x40
+#define I40E_FDIR_IP_DEFAULT_VERSION_IHL    0x45
+#define I40E_FDIR_TCP_DEFAULT_DATAOFF       0x50
+#define I40E_FDIR_IPv6_DEFAULT_VTC_FLOW     0x60300000
+#define I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS   0xFF
+#define I40E_FDIR_IPv6_PAYLOAD_LEN          380
+#define I40E_FDIR_UDP_DEFAULT_LEN           400
+
+/* Wait count and interval for fdir filter programming */
+#define I40E_FDIR_WAIT_COUNT       10
+#define I40E_FDIR_WAIT_INTERVAL_US 1000
 
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
@@ -59,6 +79,16 @@
 #define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
+				     struct rte_eth_fdir_input *fdir_input,
+				     unsigned char *raw_pkt);
+static int i40e_add_del_fdir_filter(struct i40e_pf *pf,
+			    struct rte_eth_fdir_filter *filter,
+			    bool add);
+static int i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			struct rte_eth_fdir_filter *filter,
+			bool add);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -288,3 +318,595 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 	pf->fdir.fdir_vsi = NULL;
 	return;
 }
+
+/*
+ * i40e_fdir_construct_pkt - construct packet based on fields in input
+ * @pf: board private structure
+ * @fdir_input: input set of the flow director entry
+ * @raw_pkt: a packet to be constructed
+ */
+static int
+i40e_fdir_construct_pkt(struct i40e_pf *pf,
+			     struct rte_eth_fdir_input *fdir_input,
+			     unsigned char *raw_pkt)
+{
+	struct ether_hdr *ether;
+	unsigned char *payload;
+	struct ipv4_hdr *ip;
+	struct ipv6_hdr *ip6;
+	struct udp_hdr *udp;
+	struct tcp_hdr *tcp;
+	struct sctp_hdr *sctp;
+	uint8_t size = 0;
+	int i, set_idx = 2; /* set_idx = 2 means using l4 payload by default*/
+
+	switch (fdir_input->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct udp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		/* set len to by default */
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.udp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.udp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_UDP;
+		udp->src_port = fdir_input->flow.udp4_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp4_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_UDP_DEFAULT_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct tcp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.tcp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.tcp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_TCP;
+		tcp->src_port = fdir_input->flow.tcp4_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.tcp4_flow.src_port;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv4_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr) + sizeof(struct sctp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.sctp4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.sctp4_flow.src_ip;
+		ip->next_proto_id = IPPROTO_SCTP;
+		sctp->tag = fdir_input->flow.sctp4_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+		ip->next_proto_id = IPPROTO_IP;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.ip4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.ip4_flow.src_ip;
+		set_idx = 1; /* l3 payload */
+		break;
+
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr) + sizeof(struct udp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.udp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.udp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_UDP;
+		udp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv6_hdr) + sizeof(struct tcp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.tcp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.tcp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_TCP;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		tcp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv6_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr) + sizeof(struct sctp_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.sctp6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.sctp6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		ip6->proto = IPPROTO_SCTP;
+		sctp->tag = fdir_input->flow.sctp6_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		ether = (struct ether_hdr *)raw_pkt;
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+		payload = raw_pkt + sizeof(struct ether_hdr) + sizeof(struct ipv6_hdr);
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow = rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->proto = IPPROTO_NONE;
+		ip6->payload_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr), &(fdir_input->flow.ip6_flow.dst_ip),
+			IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr), &(fdir_input->flow.ip6_flow.src_ip),
+			IPV6_ADDR_LEN);
+		set_idx = 1; /* l3 payload */
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown flow type %u.", fdir_input->flow_type);
+		return -EINVAL;
+	}
+
+	for (i = 0; i < 3; i++) {
+		if (pf->fdir.flex_set[set_idx][i].size == 0)
+			break;
+		(void)rte_memcpy(payload + 2 * pf->fdir.flex_set[set_idx][i].offset,
+				 fdir_input->flow_ext.flexwords + size,
+				 2 * pf->fdir.flex_set[set_idx][i].size);
+		size = pf->fdir.flex_set[set_idx][i].size;
+	}
+	return 0;
+}
+
+/* Construct the tx flags */
+static inline uint64_t
+i40e_build_ctob(uint32_t td_cmd,
+		uint32_t td_offset,
+		unsigned int size,
+		uint32_t td_tag)
+{
+	return rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DATA |
+			((uint64_t)td_cmd  << I40E_TXD_QW1_CMD_SHIFT) |
+			((uint64_t)td_offset << I40E_TXD_QW1_OFFSET_SHIFT) |
+			((uint64_t)size  << I40E_TXD_QW1_TX_BUF_SZ_SHIFT) |
+			((uint64_t)td_tag  << I40E_TXD_QW1_L2TAG1_SHIFT));
+}
+
+/*
+ * check the programming status descriptor in rx queue.
+ * done after Programming Flow Director is programmed on
+ * tx queue
+ */
+static inline int
+i40e_check_fdir_programming_status(struct i40e_rx_queue *rxq)
+{
+	volatile union i40e_rx_desc *rxdp;
+	uint64_t qword1;
+	uint32_t rx_status;
+	uint32_t len, id;
+	uint32_t error;
+	int ret = 0;
+
+	rxdp = &rxq->rx_ring[rxq->rx_tail];
+	qword1 = rte_le_to_cpu_64(rxdp->wb.qword1.status_error_len);
+	rx_status = (qword1 & I40E_RXD_QW1_STATUS_MASK)
+			>> I40E_RXD_QW1_STATUS_SHIFT;
+
+	if (rx_status & (1 << I40E_RX_DESC_STATUS_DD_SHIFT)) {
+		len = qword1 >> I40E_RX_PROG_STATUS_DESC_LENGTH_SHIFT;
+		id = (qword1 & I40E_RX_PROG_STATUS_DESC_QW1_PROGID_MASK) >>
+			    I40E_RX_PROG_STATUS_DESC_QW1_PROGID_SHIFT;
+
+		if (len  == I40E_RX_PROG_STATUS_DESC_LENGTH &&
+		    id == I40E_RX_PROG_STATUS_DESC_FD_FILTER_STATUS) {
+			error = (qword1 &
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_MASK) >>
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_SHIFT;
+			if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_FD_TBL_FULL_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to add FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_NO_FD_ENTRY_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to delete FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else
+				PMD_DRV_LOG(ERR, "invalid programming status"
+					    " reported, error = %u.", error);
+		} else
+			PMD_DRV_LOG(ERR, "unknown programming status"
+				    " reported, len = %d, id = %u.", len, id);
+		rxdp->wb.qword1.status_error_len = 0;
+		rxq->rx_tail++;
+		if (unlikely(rxq->rx_tail == rxq->nb_rx_desc))
+			rxq->rx_tail = 0;
+	}
+	return ret;
+}
+
+/*
+ * i40e_add_del_fdir_filter - add or remove a flow director filter.
+ * @pf: board private structure
+ * @filter: fdir filter entry
+ * @add: 0 - delete, 1 - add
+ */
+static int
+i40e_add_del_fdir_filter(struct i40e_pf *pf,
+			    struct rte_eth_fdir_filter *filter,
+			    bool add)
+{
+	int ret = 0;
+	unsigned char *pkt = (unsigned char *)pf->fdir.prg_pkt;
+
+	if (!(pf->flags & I40E_FLAG_FDIR)) {
+		PMD_DRV_LOG(ERR, "FDIR is not enabled.");
+		return -ENOTSUP;
+	}
+
+	memset(pkt, 0, I40E_FDIR_PKT_LEN);
+
+	ret = i40e_fdir_construct_pkt(pf, &filter->input, pkt);
+	if (ret < 0) {
+		PMD_DRV_LOG(ERR, "construct packet for fdir fails.");
+		return ret;
+	}
+
+	switch (filter->input.flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_UDP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_TCP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_SCTP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		/* program on both NONF_IPV4 and FRAG_IPV4 PCTYPE*/
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV4_OTHER fdir programming fails.");
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_FRAG_IPV4,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_FRAG_IPV4 fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_UDP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_TCP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_SCTP fdir programming fails.");
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		/* program on both NONF_IPV6 and FRAG_IPV6 PCTYPE*/
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_IPV6_OTHER fdir programming fails.");
+		ret = i40e_fdir_filter_programming(pf,
+			I40E_FILTER_PCTYPE_FRAG_IPV6,
+			filter, add);
+		if (ret < 0)
+			PMD_DRV_LOG(ERR, "NONF_FRAG_IPV6 fdir programming fails.");
+		break;
+	default:
+		PMD_DRV_LOG(ERR, " invalid flow_type input.");
+		ret = -EINVAL;
+	}
+	return ret;
+}
+
+/*
+ * i40e_fdir_filter_programming - Program a flow director filter rule.
+ * Is done by Flow Director Programming Descriptor followed by packet
+ * structure that contains the filter fields need to match.
+ * @pf: board private structure
+ * @pctype: pctype
+ * @filter: fdir filter entry
+ * @add: 0 - delelet, 1 - add
+ */
+static int
+i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			struct rte_eth_fdir_filter *filter,
+			bool add)
+{
+	struct i40e_tx_queue *txq = pf->fdir.txq;
+	struct i40e_rx_queue *rxq = pf->fdir.rxq;
+	struct rte_eth_fdir_input *fdir_input = &filter->input;
+	struct rte_eth_fdir_action *fdir_action = &filter->action;
+	volatile struct i40e_tx_desc *txdp;
+	volatile struct i40e_filter_program_desc *fdirdp;
+	uint32_t td_cmd;
+	uint16_t i;
+	uint8_t dest;
+
+	PMD_DRV_LOG(INFO, "filling filter programming descriptor.");
+	fdirdp = (volatile struct i40e_filter_program_desc *)
+			(&(txq->tx_ring[txq->tx_tail]));
+
+	fdirdp->qindex_flex_ptype_vsi =
+			rte_cpu_to_le_32((fdir_action->rx_queue <<
+					  I40E_TXD_FLTR_QW0_QINDEX_SHIFT) &
+					  I40E_TXD_FLTR_QW0_QINDEX_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_action->flex_off <<
+					  I40E_TXD_FLTR_QW0_FLEXOFF_SHIFT) &
+					  I40E_TXD_FLTR_QW0_FLEXOFF_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pctype <<
+					  I40E_TXD_FLTR_QW0_PCTYPE_SHIFT) &
+					  I40E_TXD_FLTR_QW0_PCTYPE_MASK);
+
+	/* Use LAN VSI Id if not programmed by user */
+	if (fdir_input->flow_ext.dest_id == 0)
+		fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pf->main_vsi->vsi_id <<
+					  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+					  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+	else
+		fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_input->flow_ext.dest_id <<
+					  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+					  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+
+	fdirdp->dtype_cmd_cntindex =
+			rte_cpu_to_le_32(I40E_TX_DESC_DTYPE_FILTER_PROG);
+
+	if (add)
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_ADD_UPDATE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+	else
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_REMOVE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+
+	if (fdir_action->drop)
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DROP_PACKET;
+	else
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DIRECT_PACKET_QINDEX;
+	fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32((dest <<
+				I40E_TXD_FLTR_QW1_DEST_SHIFT) &
+				I40E_TXD_FLTR_QW1_DEST_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+		rte_cpu_to_le_32((fdir_action->report_status<<
+				I40E_TXD_FLTR_QW1_FD_STATUS_SHIFT) &
+				I40E_TXD_FLTR_QW1_FD_STATUS_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+			rte_cpu_to_le_32(I40E_TXD_FLTR_QW1_CNT_ENA_MASK);
+	if (fdir_action->cnt_idx != 0)
+		fdirdp->dtype_cmd_cntindex |=
+				rte_cpu_to_le_32((fdir_action->cnt_idx <<
+				I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+				I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+	else
+		fdirdp->dtype_cmd_cntindex |=
+				rte_cpu_to_le_32((pf->fdir.match_counter_index <<
+				I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+				I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+
+	fdirdp->fd_id = rte_cpu_to_le_32(filter->soft_id);
+	txq->tx_tail++;
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+
+	PMD_DRV_LOG(INFO, "filling transmit descriptor.");
+	txdp = &(txq->tx_ring[txq->tx_tail]);
+	txdp->buffer_addr = rte_cpu_to_le_64(pf->fdir.dma_addr);
+	td_cmd = I40E_TX_DESC_CMD_EOP |
+		 I40E_TX_DESC_CMD_RS  |
+		 I40E_TX_DESC_CMD_DUMMY;
+
+	txdp->cmd_type_offset_bsz =
+		i40e_build_ctob(td_cmd, 0, I40E_FDIR_PKT_LEN, 0);
+
+	txq->tx_tail++;
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+	/* Update the tx tail register */
+	rte_wmb();
+	I40E_PCI_REG_WRITE(txq->qtx_tail, txq->tx_tail);
+
+	for (i = 0; i < I40E_FDIR_WAIT_COUNT; i++) {
+		rte_delay_us(I40E_FDIR_WAIT_INTERVAL_US);
+		if (txdp->cmd_type_offset_bsz &
+				rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DESC_DONE))
+			break;
+	}
+	if (i >= I40E_FDIR_WAIT_COUNT) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " time out to get DD on tx queue.");
+		return -ETIMEDOUT;
+	}
+	/* totally delay 10 ms to check programming status*/
+	rte_delay_us((I40E_FDIR_WAIT_COUNT - i) * I40E_FDIR_WAIT_INTERVAL_US);
+	if (i40e_check_fdir_programming_status(rxq) < 0) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " programming status reported.");
+		return -ENOSYS;
+	}
+
+	return 0;
+}
+
+/*
+ * i40e_fdir_ctrl_func - deal with all operations on flow director.
+ * @pf: board private structure
+ * @filter_op:operation will be taken.
+ * @arg: a pointer to specific structure corresponding to the filter_op
+ */
+int
+i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
+{
+	int ret = 0;
+
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_NOP &&
+	    filter_op != RTE_ETH_FILTER_FLUSH)
+		return -EINVAL;
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_NOP:
+		if (!(pf->flags & I40E_FLAG_FDIR))
+			ret = -ENOTSUP;
+		break;
+	case RTE_ETH_FILTER_ADD:
+		ret = i40e_add_del_fdir_filter(pf,
+			(struct rte_eth_fdir_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_DELETE:
+		ret = i40e_add_del_fdir_filter(pf,
+			(struct rte_eth_fdir_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
+		ret = -EINVAL;
+		break;
+	}
+	return ret;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 06/21] testpmd: add test commands to add/delete flow director filter
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (4 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete " Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 07/21] i40e: match counter for flow director Jingjing Wu
                       ` (16 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Commands are added which can be used to test adding or deleting 8 flow
types of the flow director filters: ipv4, tcpv4, udpv4, sctpv4,
ipv6, tcpv6, udpv6, sctpv6.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 447 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 447 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 47162e9..bfa7656 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -678,6 +678,28 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"get_flex_filter (port_id) index (idx)\n"
 			"    get info of a flex filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del|update)"
+			" flow (ip4|ip6) src (src_ip_address) dst (dst_ip_address)"
+			" flexwords (flexwords_value)"
+			" (drop|fwd) queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del an IP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del|update)"
+			" flow (udp4|tcp4|udp6|tcp6)"
+			" src (src_ip_address) (src_port)"
+			" dst (dst_ip_address) (dst_port)"
+			" flexwords (flexwords_value)"
+			" (drop|fwd) queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del an UDP/TCP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del|update)"
+			" flow (sctp4|sctp6)"
+			" src (src_ip_address) dst (dst_ip_address)"
+			" tag (verification_tag)"
+			" flexwords (flexwords_value) (drop|fwd)"
+			" queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a SCTP type flow director filter.\n\n"
 		);
 	}
 }
@@ -7633,6 +7655,428 @@ cmdline_parse_inst_t cmd_get_flex_filter = {
 	},
 };
 
+/* *** Filters Control *** */
+
+/* *** deal with flow director filter *** */
+struct cmd_flow_director_result {
+	cmdline_fixed_string_t flow_director_filter;
+	uint8_t port_id;
+	cmdline_fixed_string_t ops;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t src;
+	cmdline_ipaddr_t ip_src;
+	uint16_t port_src;
+	cmdline_fixed_string_t dst;
+	cmdline_ipaddr_t ip_dst;
+	uint16_t port_dst;
+	cmdline_fixed_string_t verify_tag;
+	uint32_t verify_tag_value;
+	cmdline_fixed_string_t flexwords;
+	cmdline_fixed_string_t flexwords_value;
+	cmdline_fixed_string_t drop;
+	cmdline_fixed_string_t queue;
+	uint16_t  queue_id;
+	cmdline_fixed_string_t fd_id;
+	uint32_t  fd_id_value;
+};
+
+static inline int
+parse_flexwords(const char *q_arg, uint16_t *flexwords)
+{
+#define MAX_NUM_WORD 8
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	unsigned long int_fld[MAX_NUM_WORD];
+	char *str_fld[MAX_NUM_WORD];
+	int i;
+	unsigned size;
+	int num_words = -1;
+
+	p = strchr(p0, '(');
+	if (p == NULL)
+		return -1;
+	++p;
+	p0 = strchr(p, ')');
+	if (p0 == NULL)
+		return -1;
+
+	size = p0 - p;
+	if (size >= sizeof(s))
+		return -1;
+
+	snprintf(s, sizeof(s), "%.*s", size, p);
+	num_words = rte_strsplit(s, sizeof(s), str_fld, MAX_NUM_WORD, ',');
+	if (num_words < 0 || num_words > MAX_NUM_WORD)
+		return -1;
+	for (i = 0; i < num_words; i++) {
+		errno = 0;
+		int_fld[i] = strtoul(str_fld[i], &end, 0);
+		if (errno != 0 || end == str_fld[i] || int_fld[i] > UINT16_MAX)
+			return -1;
+		flexwords[i] = rte_cpu_to_be_16((uint16_t)int_fld[i]);
+	}
+	return num_words;
+}
+
+static void
+cmd_flow_director_filter_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	struct rte_eth_fdir_filter entry;
+	uint16_t flexwords[8];
+	int num_flexwords;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+	memset(flexwords, 0, sizeof(flexwords));
+	memset(&entry, 0, sizeof(struct rte_eth_fdir_filter));
+	num_flexwords = parse_flexwords(res->flexwords_value, flexwords);
+	if (num_flexwords < 0) {
+		printf("error: Cannot parse flexwords input.\n");
+		return;
+	}
+
+	if (!strcmp(res->flow_type, "ip4")) {
+		/* no need to convert, already big endian. */
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.ip4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.ip4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_IPV4_OTHER;
+	} else if (!strcmp(res->flow_type, "udp4")) {
+		/* no need to convert, already big endian. */
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.udp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.udp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.udp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
+	} else if (!strcmp(res->flow_type, "tcp4")) {
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.tcp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.tcp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.tcp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.tcp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
+	} else if (!strcmp(res->flow_type, "sctp4")) {
+		if (res->ip_dst.family == AF_INET)
+			entry.input.flow.sctp4_flow.dst_ip =
+				res->ip_dst.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_src.family == AF_INET)
+			entry.input.flow.sctp4_flow.src_ip =
+				res->ip_src.addr.ipv4.s_addr;
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		/* need convert to big endian. */
+		entry.input.flow.sctp4_flow.verify_tag =
+				rte_cpu_to_be_32(res->verify_tag_value);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
+	} else if (!strcmp(res->flow_type, "ip6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.ip6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.ip6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_IPV6_OTHER;
+	} else if (!strcmp(res->flow_type, "udp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.udp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.udp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		entry.input.flow.udp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
+	} else if (!strcmp(res->flow_type, "tcp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.tcp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.tcp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		entry.input.flow.tcp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.tcp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
+	} else if (!strcmp(res->flow_type, "sctp6")) {
+		if (res->ip_src.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.sctp6_flow.src_ip),
+					 &(res->ip_src.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		if (res->ip_dst.family == AF_INET6)
+			(void)rte_memcpy(&(entry.input.flow.sctp6_flow.dst_ip),
+					 &(res->ip_dst.addr.ipv6),
+					 sizeof(struct in6_addr));
+		else {
+			printf("error parameters.\n");
+			return;
+		}
+		entry.input.flow.sctp6_flow.verify_tag =
+			rte_cpu_to_be_32(res->verify_tag_value);
+		entry.input.flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
+	}
+
+	entry.input.flow_ext.num_flexwords = num_flexwords;
+	rte_memcpy(entry.input.flow_ext.flexwords,
+		   flexwords,
+		   sizeof(flexwords[0]) * num_flexwords);
+
+	entry.input.flow_ext.dest_id = 0;
+	entry.action.flex_off = 0;  /*use 0 by default */
+	if (!strcmp(res->drop, "drop"))
+		entry.action.drop = 1;
+	else
+		entry.action.drop = 0;
+	/* set to report FD ID by default */
+	entry.action.report_status = RTE_ETH_FDIR_REPORT_ID;
+	entry.action.rx_queue = res->queue_id;
+	/* use 0 by default, will set it to fdir counter per dev */
+	entry.action.cnt_idx = 0;
+	entry.soft_id = res->fd_id_value;
+	if (!strcmp(res->ops, "add"))
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_ADD, &entry);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_DELETE, &entry);
+	if (ret < 0)
+		printf("flow director programming error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_token_string_t cmd_flow_director_filter =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_director_filter, "flow_director_filter");
+cmdline_parse_token_num_t cmd_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_ops =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 ops, "add#del#update");
+cmdline_parse_token_string_t cmd_flow_director_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_type,
+				 "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_src =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 src, "src");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_src =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_src);
+cmdline_parse_token_num_t cmd_flow_director_port_src =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_src, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_dst =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 dst, "dst");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_dst =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_dst);
+cmdline_parse_token_num_t cmd_flow_director_port_dst =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_dst, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_verify_tag =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				  verify_tag, "verify_tag");
+cmdline_parse_token_num_t cmd_flow_director_verify_tag_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      verify_tag_value, UINT32);
+cmdline_parse_token_string_t cmd_flow_director_flexwords =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flexwords, "flexwords");
+cmdline_parse_token_string_t cmd_flow_director_flexwords_value =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+			      flexwords_value, NULL);
+cmdline_parse_token_string_t cmd_flow_director_drop =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 drop, "drop#fwd");
+cmdline_parse_token_string_t cmd_flow_director_queue =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 queue, "queue");
+cmdline_parse_token_num_t cmd_flow_director_queue_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      queue_id, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_fd_id =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 fd_id, "fd_id");
+cmdline_parse_token_num_t cmd_flow_director_fd_id_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      fd_id_value, UINT32);
+
+cmdline_parse_inst_t cmd_add_del_ip_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete an ip flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_udp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete an udp/tcp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_port_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_port_dst,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a sctp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_verify_tag,
+		(void *)&cmd_flow_director_verify_tag_value,
+		(void *)&cmd_flow_director_flexwords,
+		(void *)&cmd_flow_director_flexwords_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7761,6 +8205,9 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_remove_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_get_flex_filter,
+	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 07/21] i40e: match counter for flow director
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (5 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 08/21] mbuf: extend fdir field Jingjing Wu
                       ` (15 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Support to get the fdir_match counter

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index fb43efb..bd5d261 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1302,6 +1302,9 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			    I40E_GLPRT_PTC9522L(hw->port),
 			    pf->offset_loaded, &os->tx_size_big,
 			    &ns->tx_size_big);
+	i40e_stat_update_32(hw, I40E_GLQF_PCNT(pf->fdir.match_counter_index),
+			   pf->offset_loaded,
+			   &os->fd_sb_match, &ns->fd_sb_match);
 	/* GLPRT_MSPDC not supported */
 	/* GLPRT_XEC not supported */
 
@@ -1318,6 +1321,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 	stats->obytes   = ns->eth.tx_bytes;
 	stats->oerrors  = ns->eth.tx_errors;
 	stats->imcasts  = ns->eth.rx_multicast;
+	stats->fdirmatch = ns->fd_sb_match;
 
 	/* Rx Errors */
 	stats->ibadcrc  = ns->crc_errors;
@@ -1393,6 +1397,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			ns->mac_short_packet_dropped);
 	PMD_DRV_LOG(DEBUG, "checksum_error:           %lu",
 		    ns->checksum_error);
+	PMD_DRV_LOG(DEBUG, "fdir_match:               %lu", ns->fd_sb_match);
 	PMD_DRV_LOG(DEBUG, "***************** PF stats end ********************");
 }
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 08/21] mbuf: extend fdir field
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (6 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 07/21] i40e: match counter for flow director Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 09/21] i40e: report flow director match info to mbuf Jingjing Wu
                       ` (14 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Fdir field is extened to support flex bytes reported when fdir match.
8 flex bytes can be reported in maximum.
The reported flex bytes are part of flexible payload.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_mbuf/rte_mbuf.h | 14 ++++++++++++--
 1 file changed, 12 insertions(+), 2 deletions(-)

diff --git a/lib/librte_mbuf/rte_mbuf.h b/lib/librte_mbuf/rte_mbuf.h
index e8f9bfc..e4b6e98 100644
--- a/lib/librte_mbuf/rte_mbuf.h
+++ b/lib/librte_mbuf/rte_mbuf.h
@@ -93,6 +93,8 @@ extern "C" {
 #define PKT_RX_IEEE1588_TMST (1ULL << 10) /**< RX IEEE1588 L2/L4 timestamped packet.*/
 #define PKT_RX_TUNNEL_IPV4_HDR (1ULL << 11) /**< RX tunnel packet with IPv4 header.*/
 #define PKT_RX_TUNNEL_IPV6_HDR (1ULL << 12) /**< RX tunnel packet with IPv6 header. */
+#define PKT_RX_FDIR_ID       (1ULL << 13) /**< FD id reported if FDIR match. */
+#define PKT_RX_FDIR_FLX      (1ULL << 14) /**< Flexible bytes reported if FDIR match. */
 
 #define PKT_TX_VLAN_PKT      (1ULL << 55) /**< TX packet is a 802.1q VLAN packet. */
 #define PKT_TX_IP_CKSUM      (1ULL << 54) /**< IP cksum of TX pkt. computed by NIC. */
@@ -181,8 +183,16 @@ struct rte_mbuf {
 	union {
 		uint32_t rss;     /**< RSS hash result if RSS enabled */
 		struct {
-			uint16_t hash;
-			uint16_t id;
+			union {
+				struct {
+					uint16_t hash;
+					uint16_t id;
+				};
+				uint32_t lo;
+				/**< Second 4 flexible bytes in little endian */
+			};
+			uint32_t hi;
+			/**< First 4 flexible bytes in little endian */
 		} fdir;           /**< Filter identifier if FDIR enabled */
 		uint32_t sched;   /**< Hierarchical scheduler */
 	} hash;                   /**< hash information */
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 09/21] i40e: report flow director match info to mbuf
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (7 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 08/21] mbuf: extend fdir field Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 10/21] testpmd: print extended fdir info in mbuf Jingjing Wu
                       ` (13 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Set the FDIR information in mbuf if match

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_rxtx.c | 99 +++++++++++++++++++++++++++++++++++++++--
 1 file changed, 95 insertions(+), 4 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index f2334de..20e35a4 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -105,6 +105,10 @@ i40e_rxd_status_to_pkt_flags(uint64_t qword)
 					I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
 			I40E_RX_DESC_FLTSTAT_RSS_HASH) ? PKT_RX_RSS_HASH : 0;
 
+	/* Check if FDIR Match */
+	flags |= (uint16_t)(qword & (1 << I40E_RX_DESC_STATUS_FLM_SHIFT) ?
+							PKT_RX_FDIR : 0);
+
 	return flags;
 }
 
@@ -661,14 +665,41 @@ i40e_rx_scan_hw_ring(struct i40e_rx_queue *rxq)
 			pkt_flags = i40e_rxd_status_to_pkt_flags(qword1);
 			pkt_flags |= i40e_rxd_error_to_pkt_flags(qword1);
 			pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
-			mb->ol_flags = pkt_flags;
-
 			mb->packet_type = (uint16_t)((qword1 &
 					I40E_RXD_QW1_PTYPE_MASK) >>
 					I40E_RXD_QW1_PTYPE_SHIFT);
 			if (pkt_flags & PKT_RX_RSS_HASH)
 				mb->hash.rss = rte_le_to_cpu_32(\
 					rxdp->wb.qword0.hi_dword.rss);
+
+			if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				mb->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxdp[j].wb.qword0.hi_dword.fd);
+				pkt_flags |= PKT_RX_FDIR_ID;
+#else
+				if (((rxdp[j].wb.qword2.ext_status >>
+					I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+					0x03) == 0x01) {
+					mb->hash.fdir.hi =
+						rte_le_to_cpu_32(\
+						rxdp[j].wb.qword3.hi_dword.fd_id);
+					pkt_flags |= PKT_RX_FDIR_ID;
+				} else if (((rxdp[j].wb.qword2.ext_status >>
+					I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+					0x03) == 0x02) {
+					mb->hash.fdir.hi =
+						rte_le_to_cpu_32(\
+						rxdp[j].wb.qword3.hi_dword.flex_bytes_hi);
+					pkt_flags |= PKT_RX_FDIR_FLX;
+				}
+				mb->hash.fdir.lo =
+					rte_le_to_cpu_32(\
+					rxdp[j].wb.qword3.lo_dword.flex_bytes_lo);
+#endif
+			}
+			mb->ol_flags = pkt_flags;
 		}
 
 		for (j = 0; j < I40E_LOOK_AHEAD; j++)
@@ -903,10 +934,40 @@ i40e_recv_pkts(void *rx_queue, struct rte_mbuf **rx_pkts, uint16_t nb_pkts)
 		pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
 		rxm->packet_type = (uint16_t)((qword1 & I40E_RXD_QW1_PTYPE_MASK) >>
 				I40E_RXD_QW1_PTYPE_SHIFT);
-		rxm->ol_flags = pkt_flags;
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword0.hi_dword.fd);
+				pkt_flags |= PKT_RX_FDIR_ID;
+#else
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x01) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.fd_id);
+				pkt_flags |= PKT_RX_FDIR_ID;
+			} else if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x02) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.flex_bytes_hi);
+				pkt_flags |= PKT_RX_FDIR_FLX;
+			}
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBL_SHIFT) &
+				0x03) == 0x01)
+				rxm->hash.fdir.lo =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.lo_dword.flex_bytes_lo);
+#endif
+		}
+		rxm->ol_flags = pkt_flags;
 
 		rx_pkts[nb_rx++] = rxm;
 	}
@@ -1060,10 +1121,40 @@ i40e_recv_scattered_pkts(void *rx_queue,
 		first_seg->packet_type = (uint16_t)((qword1 &
 					I40E_RXD_QW1_PTYPE_MASK) >>
 					I40E_RXD_QW1_PTYPE_SHIFT);
-		first_seg->ol_flags = pkt_flags;
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR) {
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword0.hi_dword.fd);
+				pkt_flags |= PKT_RX_FDIR_ID;
+#else
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x01) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.fd_id);
+				pkt_flags |= PKT_RX_FDIR_ID;
+			} else if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+				0x03) == 0x02) {
+				rxm->hash.fdir.hi =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.hi_dword.flex_bytes_hi);
+				pkt_flags |= PKT_RX_FDIR_FLX;
+			}
+			if (((rxd.wb.qword2.ext_status >>
+				I40E_RX_DESC_EXT_STATUS_FLEXBL_SHIFT) &
+				0x03) == 0x01)
+				rxm->hash.fdir.lo =
+					rte_le_to_cpu_32(\
+					rxd.wb.qword3.lo_dword.flex_bytes_lo);
+#endif
+		}
+		first_seg->ol_flags = pkt_flags;
 
 		/* Prefetch data of first segment, if configured to do so. */
 		rte_prefetch0(RTE_PTR_ADD(first_seg->buf_addr,
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 10/21] testpmd: print extended fdir info in mbuf
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (8 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 09/21] i40e: report flow director match info to mbuf Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 11/21] ethdev: define structures for getting flow director information Jingjing Wu
                       ` (12 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Extended fdir info is printed in rxonly fwd engine when fdir match.

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/rxonly.c | 14 +++++++++++---
 1 file changed, 11 insertions(+), 3 deletions(-)

diff --git a/app/test-pmd/rxonly.c b/app/test-pmd/rxonly.c
index 4410c3d..281bee1 100644
--- a/app/test-pmd/rxonly.c
+++ b/app/test-pmd/rxonly.c
@@ -172,10 +172,18 @@ pkt_burst_receive(struct fwd_stream *fs)
 		if (ol_flags & PKT_RX_RSS_HASH) {
 			printf(" - RSS hash=0x%x", (unsigned) mb->hash.rss);
 			printf(" - RSS queue=0x%x",(unsigned) fs->rx_queue);
+		} else if (ol_flags & PKT_RX_FDIR) {
+			printf(" - FDIR matched ");
+			if (ol_flags & PKT_RX_FDIR_ID)
+				printf("ID=0x%x",
+				       mb->hash.fdir.hi);
+			else if (ol_flags & PKT_RX_FDIR_FLX)
+				printf("flex bytes=0x%08x %08x",
+				       mb->hash.fdir.hi, mb->hash.fdir.lo);
+			else
+				printf("hash=0x%x ID=0x%x ",
+				       mb->hash.fdir.hash, mb->hash.fdir.id);
 		}
-		else if (ol_flags & PKT_RX_FDIR)
-			printf(" - FDIR hash=0x%x - FDIR id=0x%x ",
-			       mb->hash.fdir.hash, mb->hash.fdir.id);
 		if (ol_flags & PKT_RX_VLAN_PKT)
 			printf(" - VLAN tci=0x%x", mb->vlan_tci);
 		if (is_encapsulation) {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 11/21] ethdev: define structures for getting flow director information
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (9 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 10/21] testpmd: print extended fdir info in mbuf Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 12/21] i40e: implement operations to get fdir info Jingjing Wu
                       ` (11 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Structure is defined for getting flow director information

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 22 ++++++++++++++++++++++
 1 file changed, 22 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 77b784e..74a9c59 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -303,6 +303,28 @@ struct rte_eth_fdir_filter {
 	struct rte_eth_fdir_action action;  /**< Action taken when match */
 };
 
+/**
+ * A structure used to get the status information of flow director filter.
+ * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_INFO operation.
+ */
+struct rte_eth_fdir_info {
+	int mode;              /**< If 0 disable, if 1 enable */
+	uint16_t collision;    /**< Number of filters with collision. */
+	uint16_t free;         /**< Number of free filters. */
+	uint16_t maxhash;
+	/**< The lookup hash value of the added filter that updated the value
+	   of the maxlen field */
+	uint8_t maxlen;        /**< Longest linked list of filters. */
+	uint64_t add;          /**< Number of added filters. */
+	uint64_t remove;       /**< Number of removed filters. */
+	uint64_t f_add;        /**< Number of failed added filters. */
+	uint64_t f_remove;     /**< Number of failed removed filters. */
+	uint16_t guarant_spc;  /**< Guaranteed spaces.*/
+	uint16_t guarant_cnt;  /**< Number of filters in guaranteed spaces. */
+	uint16_t best_spc;     /**< Best effort spaces.*/
+	uint16_t best_cnt;     /**< Number of filters in best effort spaces. */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 12/21] i40e: implement operations to get fdir info
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (10 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 11/21] ethdev: define structures for getting flow director information Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 13/21] testpmd: display fdir statistics Jingjing Wu
                       ` (10 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Implement operation to get flow director information in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 34 ++++++++++++++++++++++++++++++++++
 1 file changed, 34 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index afc9702..85df220 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -89,6 +89,8 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			enum i40e_filter_pctype pctype,
 			struct rte_eth_fdir_filter *filter,
 			bool add);
+static void i40e_fdir_info_get(struct i40e_pf *pf,
+			   struct rte_eth_fdir_info *fdir);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -874,6 +876,35 @@ i40e_fdir_filter_programming(struct i40e_pf *pf,
 }
 
 /*
+ * i40e_fdir_info_get - get information of Flow Director
+ * @pf: ethernet device to get info from
+ * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
+ *    the flow director information.
+ */
+static void
+i40e_fdir_info_get(struct i40e_pf *pf, struct rte_eth_fdir_info *fdir)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t pfqf_ctl;
+
+	pfqf_ctl = I40E_READ_REG(hw, I40E_PFQF_CTL_0);
+	fdir->mode = pfqf_ctl & I40E_PFQF_CTL_0_FD_ENA_MASK ? 1 : 0;
+	fdir->guarant_spc =
+		(uint16_t)hw->func_caps.fd_filters_guaranteed;
+	fdir->guarant_cnt =
+		(uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	fdir->best_spc =
+		(uint16_t)hw->func_caps.fd_filters_best_effort;
+	fdir->best_cnt =
+		(uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			    I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	return;
+}
+
+/*
  * i40e_fdir_ctrl_func - deal with all operations on flow director.
  * @pf: board private structure
  * @filter_op:operation will be taken.
@@ -903,6 +934,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_INFO:
+		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
+		break;
 	default:
 		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
 		ret = -EINVAL;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 13/21] testpmd: display fdir statistics
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (11 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 12/21] i40e: implement operations to get fdir info Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 14/21] i40e: implement operation to flush flow director table Jingjing Wu
                       ` (9 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Display flow director's statistics information

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/config.c | 42 ++++++++++++++++++++++++++++++++++++++----
 1 file changed, 38 insertions(+), 4 deletions(-)

diff --git a/app/test-pmd/config.c b/app/test-pmd/config.c
index 9bc08f4..c516be0 100644
--- a/app/test-pmd/config.c
+++ b/app/test-pmd/config.c
@@ -1815,18 +1815,46 @@ fdir_remove_signature_filter(portid_t port_id,
 void
 fdir_get_infos(portid_t port_id)
 {
-	struct rte_eth_fdir fdir_infos;
+	struct rte_eth_fdir_info fdir_infos;
+	int ret;
 
 	static const char *fdir_stats_border = "########################";
 
 	if (port_id_is_invalid(port_id))
 		return;
 
-	rte_eth_dev_fdir_get_infos(port_id, &fdir_infos);
-
+	memset(&fdir_infos, 0, sizeof(fdir_infos));
+	ret = rte_eth_dev_filter_ctrl(port_id, RTE_ETH_FILTER_FDIR,
+			       RTE_ETH_FILTER_INFO, &fdir_infos);
+	if (ret < 0) {
+		/* use the old fdir APIs to get info */
+		struct rte_eth_fdir fdir;
+		memset(&fdir, 0, sizeof(fdir));
+		ret = rte_eth_dev_fdir_get_infos(port_id, &fdir);
+		if (ret < 0) {
+			printf("\n getting fdir info fails on port %-2d\n",
+				port_id);
+			return;
+		}
+		printf("\n  %s FDIR infos for port %-2d     %s\n",
+			fdir_stats_border, port_id, fdir_stats_border);
+		printf("  collision: %-10"PRIu64"  free:     %"PRIu64"\n"
+		       "  maxhash:   %-10"PRIu64"  maxlen:   %"PRIu64"\n"
+		       "  add:	     %-10"PRIu64"  remove:   %"PRIu64"\n"
+		       "  f_add:     %-10"PRIu64"  f_remove: %"PRIu64"\n",
+		       (uint64_t)(fdir.collision), (uint64_t)(fdir.free),
+		       (uint64_t)(fdir.maxhash), (uint64_t)(fdir.maxlen),
+		       fdir.add, fdir.remove, fdir.f_add, fdir.f_remove);
+		printf("  %s############################%s\n",
+		       fdir_stats_border, fdir_stats_border);
+		return;
+	}
 	printf("\n  %s FDIR infos for port %-2d     %s\n",
 	       fdir_stats_border, port_id, fdir_stats_border);
-
+	if (fdir_infos.mode)
+			printf("  FDIR is enabled\n");
+	else
+			printf("  FDIR is disabled\n");
 	printf("  collision: %-10"PRIu64"  free:     %"PRIu64"\n"
 	       "  maxhash:   %-10"PRIu64"  maxlen:   %"PRIu64"\n"
 	       "  add:       %-10"PRIu64"  remove:   %"PRIu64"\n"
@@ -1835,6 +1863,12 @@ fdir_get_infos(portid_t port_id)
 	       (uint64_t)(fdir_infos.maxhash), (uint64_t)(fdir_infos.maxlen),
 	       fdir_infos.add, fdir_infos.remove,
 	       fdir_infos.f_add, fdir_infos.f_remove);
+	printf("  guarant_space: %-10"PRIu16
+	       "  best_space:    %-10"PRIu16"\n",
+	       fdir_infos.guarant_spc, fdir_infos.best_spc);
+	printf("  guarant_count: %-10"PRIu16
+	       "  best_count:    %-10"PRIu16"\n",
+	       fdir_infos.guarant_cnt, fdir_infos.best_cnt);
 	printf("  %s############################%s\n",
 	       fdir_stats_border, fdir_stats_border);
 }
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 14/21] i40e: implement operation to flush flow director table
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (12 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 13/21] testpmd: display fdir statistics Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 15/21] testpmd: add test command " Jingjing Wu
                       ` (8 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Implement operation to flush flow director table

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 47 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 47 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 85df220..f59eb24 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -73,6 +73,10 @@
 #define I40E_FDIR_WAIT_COUNT       10
 #define I40E_FDIR_WAIT_INTERVAL_US 1000
 
+/* Wait count and interval for fdir filter flush */
+#define I40E_FDIR_FLUSH_RETRY       50
+#define I40E_FDIR_FLUSH_INTERVAL_MS 5
+
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
 #define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
@@ -89,6 +93,7 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			enum i40e_filter_pctype pctype,
 			struct rte_eth_fdir_filter *filter,
 			bool add);
+static int i40e_fdir_flush(struct i40e_pf *pf);
 static void i40e_fdir_info_get(struct i40e_pf *pf,
 			   struct rte_eth_fdir_info *fdir);
 
@@ -876,6 +881,45 @@ i40e_fdir_filter_programming(struct i40e_pf *pf,
 }
 
 /*
+ * i40e_fdir_flush - clear all filters of Flow Director table
+ * @pf: board private structure
+ */
+static int
+i40e_fdir_flush(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t reg;
+	uint16_t guarant_cnt, best_cnt;
+	int i;
+
+	I40E_WRITE_REG(hw, I40E_PFQF_CTL_1, I40E_PFQF_CTL_1_CLEARFDTABLE_MASK);
+	I40E_WRITE_FLUSH(hw);
+
+	for (i = 0; i < I40E_FDIR_FLUSH_RETRY; i++) {
+		rte_delay_ms(I40E_FDIR_FLUSH_INTERVAL_MS);
+		reg = I40E_READ_REG(hw, I40E_PFQF_CTL_1);
+		if (!(reg & I40E_PFQF_CTL_1_CLEARFDTABLE_MASK))
+			break;
+	}
+	if (i >= I40E_FDIR_FLUSH_RETRY) {
+		PMD_DRV_LOG(ERR, "FD table did not flush, may need more time.");
+		return -ETIMEDOUT;
+	}
+	guarant_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	best_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	if (guarant_cnt != 0 || best_cnt != 0) {
+		PMD_DRV_LOG(ERR, "Failed to flush FD table.");
+		return -ENOSYS;
+	} else
+		PMD_DRV_LOG(INFO, "FD table Flush success.");
+	return 0;
+}
+
+/*
  * i40e_fdir_info_get - get information of Flow Director
  * @pf: ethernet device to get info from
  * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
@@ -934,6 +978,9 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_FLUSH:
+		ret = i40e_fdir_flush(pf);
+		break;
 	case RTE_ETH_FILTER_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
 		break;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 15/21] testpmd: add test command to flush flow director table
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (13 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 14/21] i40e: implement operation to flush flow director table Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
                       ` (7 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Test command is added to flush flow director table

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 49 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 49 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index bfa7656..f8960d8 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -700,6 +700,9 @@ static void cmd_help_long_parsed(void *parsed_result,
 			" flexwords (flexwords_value) (drop|fwd)"
 			" queue (queue_id) fd_id (fd_id_value)\n"
 			"    Add/Del a SCTP type flow director filter.\n\n"
+
+			"flush_flow_director (port_id)\n"
+			"    Flush all flow director entries of a device.\n\n"
 		);
 	}
 }
@@ -8077,6 +8080,51 @@ cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
 	},
 };
 
+struct cmd_flush_flow_director_result {
+	cmdline_fixed_string_t flush_flow_director;
+	uint8_t port_id;
+};
+
+cmdline_parse_token_string_t cmd_flush_flow_director_flush =
+	TOKEN_STRING_INITIALIZER(struct cmd_flush_flow_director_result,
+				 flush_flow_director, "flush_flow_director");
+cmdline_parse_token_num_t cmd_flush_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flush_flow_director_result,
+			      port_id, UINT8);
+
+static void
+cmd_flush_flow_director_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+			RTE_ETH_FILTER_FLUSH, NULL);
+	if (ret < 0)
+		printf("flow director table flushing error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_inst_t cmd_flush_flow_director = {
+	.f = cmd_flush_flow_director_parsed,
+	.data = NULL,
+	.help_str = "flush all flow director entries of a device on NIC",
+	.tokens = {
+		(void *)&cmd_flush_flow_director_flush,
+		(void *)&cmd_flush_flow_director_port_id,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8208,6 +8256,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 16/21] ethdev: define structures for configuring flexible payload
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (14 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 15/21] testpmd: add test command " Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 17/21] i40e: implement operations to configure " Jingjing Wu
                       ` (6 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

New Structures are defined for configuring flexible payload

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 43 +++++++++++++++++++++++++++++++++++++++++
 1 file changed, 43 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 74a9c59..4a51c22 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -138,6 +138,24 @@ struct rte_eth_tunnel_filter_conf {
  */
 
 /**
+ * A structure defined a field vector to specify each field.
+ */
+struct rte_eth_field_vector {
+	uint8_t offset;   /**< Word offset in payload */
+	uint8_t size;     /**< Field size defined in word units */
+};
+
+/**
+ * Payload type
+ */
+enum rte_eth_payload_type {
+	RTE_ETH_PAYLOAD_UNKNOWN = 0,
+	RTE_ETH_L2_PAYLOAD,
+	RTE_ETH_L3_PAYLOAD,
+	RTE_ETH_L4_PAYLOAD,
+};
+
+/**
  * Flow type
  */
 enum rte_eth_flow_type {
@@ -153,6 +171,31 @@ enum rte_eth_flow_type {
 };
 
 /**
+ * A structure used to select fields extracted from the protocol layers to
+ * the Field Vector as flexible payload for filter
+ */
+struct rte_eth_flex_payload_cfg {
+	enum rte_eth_payload_type type;  /**< Payload type */
+	uint8_t nb_field;                /**< The number of following fields */
+	struct rte_eth_field_vector field[0];
+	/**< Field vectors to constitute flexible payload */
+};
+
+#define RTE_ETH_FDIR_CFG_FLX      0x0001
+/**
+ * A structure used to configure FDIR filter global set
+ * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_SET operation.
+ */
+struct rte_eth_fdir_cfg {
+	uint16_t cmd;  /**< Sub command  */
+	/**
+	 * A pointer to structure for the configuration e.g.
+	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
+	*/
+	void *cfg;
+};
+
+/**
  * A structure used to define the input for IPV4 UDP flow
  */
 struct rte_eth_udpv4_flow {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 17/21] i40e: implement operations to configure flexible payload
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (15 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 18/21] testpmd: add test command " Jingjing Wu
                       ` (5 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Implement operation to flexible payload in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 106 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 106 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index f59eb24..e15d94e 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -83,6 +83,8 @@
 #define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 struct rte_eth_flex_payload_cfg *cfg);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -327,6 +329,98 @@ i40e_fdir_teardown(struct i40e_pf *pf)
 }
 
 /*
+ * i40e_set_flx_pld_cfg -configure the rule how bytes stream is extracted as flexible payload
+ * @pf: board private structure
+ * @cfg: the rule how bytes stream is extracted as flexible payload
+ */
+static int
+i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 struct rte_eth_flex_payload_cfg *cfg)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct rte_eth_fdir_info fdir;
+	uint32_t flx_pit;
+	uint16_t min_next_off = 0;
+	uint8_t idx = 0;
+	int i = 0;
+	int num_word = 0;
+	int ret;
+
+	if (cfg == NULL || cfg->nb_field > 3)
+		return -EINVAL;
+
+	if (cfg->type == RTE_ETH_L2_PAYLOAD)
+		idx = 0;
+	else if (cfg->type == RTE_ETH_L3_PAYLOAD)
+		idx = 1;
+	else if (cfg->type == RTE_ETH_L4_PAYLOAD)
+		idx = 2;
+	else {
+		PMD_DRV_LOG(ERR, "unknown payload type.");
+		return -EINVAL;
+	}
+	/*
+	 * flexible payload need to be configured before
+	 * flow director filters are added
+	 * If filters exist, flush them.
+	 */
+	memset(&fdir, 0, sizeof(fdir));
+	i40e_fdir_info_get(pf, &fdir);
+	if (fdir.best_cnt + fdir.guarant_cnt > 0) {
+		ret = i40e_fdir_flush(pf);
+		if (ret) {
+			PMD_DRV_LOG(ERR, " failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	for (i = 0; i < cfg->nb_field; i++) {
+		/*
+		 * check register's constrain
+		 * Current Offset >= previous offset + previous FSIZE.
+		 */
+		if (cfg->field[i].offset < min_next_off) {
+			PMD_DRV_LOG(ERR, "Offset should be larger than"
+				"previous offset + previous FSIZE.");
+			return -EINVAL;
+		}
+		flx_pit = (cfg->field[i].offset <<
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK;
+		flx_pit |= (cfg->field[i].size <<
+				I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) &
+				I40E_PRTQF_FLX_PIT_FSIZE_MASK;
+		flx_pit |= ((num_word + I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+				I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) &
+				I40E_PRTQF_FLX_PIT_DEST_OFF_MASK;
+		/* support no more than 8 words flexible payload*/
+		num_word += cfg->field[i].size;
+		if (num_word > 8)
+			return -EINVAL;
+
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(idx * 3 + i), flx_pit);
+		/* record the info in fdir structure */
+		pf->fdir.flex_set[idx][i].offset = cfg->field[i].offset;
+		pf->fdir.flex_set[idx][i].size = cfg->field[i].size;
+		min_next_off = cfg->field[i].offset + cfg->field[i].size;
+	}
+
+	for (; i < 3; i++) {
+		/* set the non-used register obeying register's constrain */
+		flx_pit = (min_next_off << I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK;
+		flx_pit |= (1 << I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) &
+			I40E_PRTQF_FLX_PIT_FSIZE_MASK;
+		flx_pit |= (63 << I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) &
+			I40E_PRTQF_FLX_PIT_DEST_OFF_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(idx * 3 + i), flx_pit);
+		min_next_off++;
+	}
+
+	return 0;
+}
+
+/*
  * i40e_fdir_construct_pkt - construct packet based on fields in input
  * @pf: board private structure
  * @fdir_input: input set of the flow director entry
@@ -957,6 +1051,7 @@ i40e_fdir_info_get(struct i40e_pf *pf, struct rte_eth_fdir_info *fdir)
 int
 i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 {
+	struct rte_eth_fdir_cfg *fdir_cfg = NULL;
 	int ret = 0;
 
 	if (arg == NULL && filter_op != RTE_ETH_FILTER_NOP &&
@@ -981,6 +1076,17 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 	case RTE_ETH_FILTER_FLUSH:
 		ret = i40e_fdir_flush(pf);
 		break;
+	case RTE_ETH_FILTER_SET:
+		fdir_cfg = (struct rte_eth_fdir_cfg *)arg;
+		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX)
+			ret = i40e_set_flx_pld_cfg(pf,
+				(struct rte_eth_flex_payload_cfg *)fdir_cfg->cfg);
+		else {
+			PMD_DRV_LOG(WARNING, "unsupported configuration command %u.",
+				    fdir_cfg->cmd);
+			return -EINVAL;
+		}
+		break;
 	case RTE_ETH_FILTER_INFO:
 		i40e_fdir_info_get(pf, (struct rte_eth_fdir_info *)arg);
 		break;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 18/21] testpmd: add test command to configure flexible payload
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (16 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 17/21] i40e: implement operations to configure " Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 19/21] ethdev: define structures for configuring flex masks Jingjing Wu
                       ` (4 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Test command is added to configure flexible payload

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 144 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 144 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index f8960d8..5a84a6c 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -58,6 +58,7 @@
 #include <rte_debug.h>
 #include <rte_cycles.h>
 #include <rte_memory.h>
+#include <rte_malloc.h>
 #include <rte_memzone.h>
 #include <rte_launch.h>
 #include <rte_tailq.h>
@@ -703,6 +704,10 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"flush_flow_director (port_id)\n"
 			"    Flush all flow director entries of a device.\n\n"
+
+			"flow_director_flex_payload (port_id)"
+			" (l2|l3|l4) (config)\n"
+			"    Configure flex payload selection.\n\n"
 		);
 	}
 }
@@ -8125,6 +8130,144 @@ cmdline_parse_inst_t cmd_flush_flow_director = {
 	},
 };
 
+/* *** deal with flow director flexible payload configuration *** */
+struct cmd_flow_director_flexpayload_result {
+	cmdline_fixed_string_t flow_director_flexpayload;
+	uint8_t port_id;
+	cmdline_fixed_string_t payload_layer;
+	cmdline_fixed_string_t payload_cfg;
+};
+
+static inline int
+parse_flex_payload_cfg(const char *q_arg,
+			     struct rte_eth_flex_payload_cfg *cfg)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	enum fieldnames {
+		FLD_OFFSET = 0,
+		FLD_SIZE,
+		_NUM_FLD
+	};
+	unsigned long int_fld[_NUM_FLD];
+	char *str_fld[_NUM_FLD];
+	int i;
+	unsigned size;
+
+	cfg->nb_field = 0;
+	p = strchr(p0, '(');
+	while (p != NULL) {
+		++p;
+		p0 = strchr(p, ')');
+		if (p0 == NULL)
+			return -1;
+
+		size = p0 - p;
+		if (size >= sizeof(s))
+			return -1;
+
+		snprintf(s, sizeof(s), "%.*s", size, p);
+		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') != _NUM_FLD)
+			return -1;
+		for (i = 0; i < _NUM_FLD; i++) {
+			errno = 0;
+			int_fld[i] = strtoul(str_fld[i], &end, 0);
+			if (errno != 0 || end == str_fld[i] || int_fld[i] > 255)
+				return -1;
+		}
+		cfg->field[cfg->nb_field].offset = (uint8_t)int_fld[FLD_OFFSET];
+		cfg->field[cfg->nb_field].size = (uint8_t)int_fld[FLD_SIZE];
+		cfg->nb_field++;
+		if (cfg->nb_field > 3) {
+			printf("exceeded max number of fields: %hhu\n",
+				cfg->nb_field);
+			return -1;
+		}
+		p = strchr(p0, '(');
+	}
+	return 0;
+}
+
+static void
+cmd_flow_director_flxpld_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flexpayload_result *res = parsed_result;
+	struct rte_eth_fdir_cfg fdir_cfg;
+	struct rte_eth_flex_payload_cfg *flxpld_cfg;
+	int ret = 0;
+	int cfg_size = 3 * sizeof(struct rte_eth_field_vector) +
+		  offsetof(struct rte_eth_flex_payload_cfg, field);
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
+
+	flxpld_cfg = (struct rte_eth_flex_payload_cfg *)rte_zmalloc_socket("CLI",
+		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
+
+	if (flxpld_cfg == NULL) {
+		printf("fail to malloc memory to configure flex payload\n");
+		return;
+	}
+
+	if (!strcmp(res->payload_layer, "l2"))
+		flxpld_cfg->type = RTE_ETH_L2_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l3"))
+		flxpld_cfg->type = RTE_ETH_L3_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l4"))
+		flxpld_cfg->type = RTE_ETH_L4_PAYLOAD;
+
+	ret = parse_flex_payload_cfg(res->payload_cfg, flxpld_cfg);
+	if (ret < 0) {
+		printf("error: Cannot parse flex payload input.\n");
+		rte_free(flxpld_cfg);
+		return;
+	}
+	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX;
+	fdir_cfg.cfg = flxpld_cfg;
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+				     RTE_ETH_FILTER_SET, &fdir_cfg);
+	if (ret < 0)
+		printf("fdir flex payload setting error: (%s)\n",
+			strerror(-ret));
+	rte_free(flxpld_cfg);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexpayload =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 flow_director_flexpayload,
+				 "flow_director_flex_payload");
+cmdline_parse_token_num_t cmd_flow_director_flexpayload_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_layer =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_layer, "l2#l3#l4");
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_cfg =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_cfg, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_payload = {
+	.f = cmd_flow_director_flxpld_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex payload on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexpayload,
+		(void *)&cmd_flow_director_flexpayload_port_id,
+		(void *)&cmd_flow_director_flexpayload_payload_layer,
+		(void *)&cmd_flow_director_flexpayload_payload_cfg,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8257,6 +8400,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 19/21] ethdev: define structures for configuring flex masks
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (17 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 18/21] testpmd: add test command " Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 20/21] i40e: implement operations to configure flexible masks Jingjing Wu
                       ` (3 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

New structures are defined for configuring flexible masks

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 25 +++++++++++++++++++++++++
 1 file changed, 25 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 4a51c22..e8e47fd 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -181,7 +181,30 @@ struct rte_eth_flex_payload_cfg {
 	/**< Field vectors to constitute flexible payload */
 };
 
+/**
+ * A structure defined to specify each word's bit mask
+ */
+struct rte_eth_flex_mask {
+	uint8_t offset;      /**< Word offset in flexible payload */
+	uint16_t bitmask;
+	/**< Each bit set to 1 disables the matched bit in the selected word
+	     defined by offset field. */
+};
+
+/**
+ * A structure used to configure FDIR masks for flexible payload
+ * for each flow type
+ */
+struct rte_eth_fdir_flex_masks {
+	enum rte_eth_flow_type flow_type;  /**< Flow type */
+	uint8_t words_mask;  /**< Bit i enables word i of flexible payload */
+	uint8_t nb_field;    /**< The number of following fields */
+	struct rte_eth_flex_mask field[0]; /**< Bitmask array */
+};
+
 #define RTE_ETH_FDIR_CFG_FLX      0x0001
+#define RTE_ETH_FDIR_CFG_MASK     0x0002
+#define RTE_ETH_FDIR_CFG_FLX_MASK 0x0003
 /**
  * A structure used to configure FDIR filter global set
  * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_SET operation.
@@ -191,6 +214,8 @@ struct rte_eth_fdir_cfg {
 	/**
 	 * A pointer to structure for the configuration e.g.
 	 * struct rte_eth_flex_payload_cfg for FDIR_CFG_FLX
+	 * struct rte_fdir_masks for FDIR_MASK
+	 * struct rte_eth_fdir_flex_masks for FDIR_FLX_MASK
 	*/
 	void *cfg;
 };
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 20/21] i40e: implement operations to configure flexible masks
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (18 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 19/21] ethdev: define structures for configuring flex masks Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 21/21] testpmd: add test command " Jingjing Wu
                       ` (2 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Implement operation to flexible masks for each flow type in i40e pmd driver

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 124 +++++++++++++++++++++++++++++++++++++++-
 1 file changed, 123 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index e15d94e..981b6eb 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -85,6 +85,8 @@
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
 static int i40e_set_flx_pld_cfg(struct i40e_pf *pf,
 			 struct rte_eth_flex_payload_cfg *cfg);
+static int i40e_set_fdir_flx_mask(struct i40e_pf *pf,
+			struct rte_eth_fdir_flex_masks *flex_masks);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -420,6 +422,123 @@ i40e_set_flx_pld_cfg(struct i40e_pf *pf,
 	return 0;
 }
 
+static inline void
+i40e_set_flex_mask_on_pctype(
+		struct i40e_hw *hw,
+		enum i40e_filter_pctype pctype,
+		struct rte_eth_fdir_flex_masks *flex_masks)
+{
+	uint32_t flxinset, mask;
+	int i;
+
+	flxinset = (flex_masks->words_mask <<
+		I40E_PRTQF_FD_FLXINSET_INSET_SHIFT) &
+		I40E_PRTQF_FD_FLXINSET_INSET_MASK;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), flxinset);
+
+	for (i = 0; i < flex_masks->nb_field; i++) {
+		mask = (flex_masks->field[i].bitmask <<
+			I40E_PRTQF_FD_MSK_MASK_SHIFT) &
+			I40E_PRTQF_FD_MSK_MASK_MASK;
+		mask |= ((flex_masks->field[i].offset +
+			I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+			I40E_PRTQF_FD_MSK_OFFSET_SHIFT) &
+			I40E_PRTQF_FD_MSK_OFFSET_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, i), mask);
+	}
+}
+
+/*
+ * i40e_set_fdir_flx_mask - configure the mask on flexible payload
+ * @pf: board private structure
+ * @flex_masks: mask for flexible payload
+ */
+static int
+i40e_set_fdir_flx_mask(struct i40e_pf *pf,
+		struct rte_eth_fdir_flex_masks *flex_masks)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct rte_eth_fdir_info fdir;
+	int ret = 0;
+
+	if (flex_masks == NULL)
+		return -EINVAL;
+
+	if (flex_masks->nb_field > 2) {
+		PMD_DRV_LOG(ERR, "bit masks cannot support more than 2 words.");
+		return -EINVAL;
+	}
+	/*
+	 * flexible payload masks need to be configured before
+	 * flow director filters are added
+	 * If filters exist, flush them.
+	 */
+	memset(&fdir, 0, sizeof(fdir));
+	i40e_fdir_info_get(pf, &fdir);
+	if (fdir.best_cnt + fdir.guarant_cnt > 0) {
+		ret = i40e_fdir_flush(pf);
+		if (ret) {
+			PMD_DRV_LOG(ERR, "failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	switch (flex_masks->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+		/* set mask for both NONF_IPV4 and FRAG_IPV4 PCTYPE*/
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+			flex_masks);
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_FRAG_IPV4,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+			flex_masks);
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+			flex_masks);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+		/* set mask for both NONF_IPV6 and FRAG_IPV6 PCTYPE*/
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+			flex_masks);
+		i40e_set_flex_mask_on_pctype(hw,
+			I40E_FILTER_PCTYPE_FRAG_IPV6,
+			flex_masks);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "invalid flow_type input.");
+		return -EINVAL;
+	}
+
+	return ret;
+}
+
 /*
  * i40e_fdir_construct_pkt - construct packet based on fields in input
  * @pf: board private structure
@@ -1081,8 +1200,11 @@ i40e_fdir_ctrl_func(struct i40e_pf *pf, enum rte_filter_op filter_op, void *arg)
 		if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX)
 			ret = i40e_set_flx_pld_cfg(pf,
 				(struct rte_eth_flex_payload_cfg *)fdir_cfg->cfg);
+		else if (fdir_cfg->cmd == RTE_ETH_FDIR_CFG_FLX_MASK)
+			ret = i40e_set_fdir_flx_mask(pf,
+				(struct rte_eth_fdir_flex_masks *)fdir_cfg->cfg);
 		else {
-			PMD_DRV_LOG(WARNING, "unsupported configuration command %u.",
+			PMD_DRV_LOG(ERR, "unsupported configuration command %u.",
 				    fdir_cfg->cmd);
 			return -EINVAL;
 		}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 21/21] testpmd: add test command to configure flexible masks
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (19 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 20/21] i40e: implement operations to configure flexible masks Jingjing Wu
@ 2014-10-30  7:26     ` Jingjing Wu
  2014-10-30  8:07     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  7:26 UTC (permalink / raw)
  To: dev

Test command is added to configure flexible masks for each flow type

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 173 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 173 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 5a84a6c..45b5481 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -705,6 +705,11 @@ static void cmd_help_long_parsed(void *parsed_result,
 			"flush_flow_director (port_id)\n"
 			"    Flush all flow director entries of a device.\n\n"
 
+			"flow_director_flex_mask (port_id)"
+			" flow (ip4|tcp4|udp4|sctp4|ip6|tcp6|udp6|sctp6)"
+			" words_mask (words) (word_mask_list)\n"
+			"    Configure mask of flex payload.\n\n"
+
 			"flow_director_flex_payload (port_id)"
 			" (l2|l3|l4) (config)\n"
 			"    Configure flex payload selection.\n\n"
@@ -8130,6 +8135,173 @@ cmdline_parse_inst_t cmd_flush_flow_director = {
 	},
 };
 
+/* *** deal with flow director mask on flexible payload *** */
+struct cmd_flow_director_flex_mask_result {
+	cmdline_fixed_string_t flow_director_flexmask;
+	uint8_t port_id;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t words_mask;
+	uint8_t words;
+	cmdline_fixed_string_t word_mask_list;
+};
+
+static inline int
+parse_word_masks_cfg(const char *q_arg,
+			     struct rte_eth_fdir_flex_masks *masks)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	enum fieldnames {
+		FLD_OFFSET = 0,
+		FLD_MASK,
+		_NUM_FLD
+	};
+	unsigned long int_fld[_NUM_FLD];
+	char *str_fld[_NUM_FLD];
+	int i;
+	unsigned size;
+
+	masks->nb_field = 0;
+	p = strchr(p0, '(');
+	while (p != NULL) {
+		++p;
+		p0 = strchr(p, ')');
+		if (p0 == NULL)
+			return -1;
+
+		size = p0 - p;
+		if (size >= sizeof(s))
+			return -1;
+
+		snprintf(s, sizeof(s), "%.*s", size, p);
+		if (rte_strsplit(s, sizeof(s), str_fld, _NUM_FLD, ',') != _NUM_FLD)
+			return -1;
+		for (i = 0; i < _NUM_FLD; i++) {
+			errno = 0;
+			int_fld[i] = strtoul(str_fld[i], &end, 0);
+			if (errno != 0 || end == str_fld[i] || int_fld[i] > UINT16_MAX)
+				return -1;
+		}
+		masks->field[masks->nb_field].offset =
+			(uint16_t)int_fld[FLD_OFFSET];
+		masks->field[masks->nb_field].bitmask =
+			~(uint16_t)int_fld[FLD_MASK];
+		masks->nb_field++;
+		if (masks->nb_field > 2) {
+			printf("exceeded max number of fields: %hhu\n",
+				masks->nb_field);
+			return -1;
+		}
+		p = strchr(p0, '(');
+	}
+	return 0;
+}
+
+static void
+cmd_flow_director_flex_mask_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flex_mask_result *res = parsed_result;
+	struct rte_eth_fdir_flex_masks *flex_masks;
+	struct rte_eth_fdir_cfg fdir_cfg;
+	int ret = 0;
+	int cfg_size = 2 * sizeof(struct rte_eth_flex_mask) +
+		  offsetof(struct rte_eth_fdir_flex_masks, field);
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&fdir_cfg, 0, sizeof(struct rte_eth_fdir_cfg));
+
+	flex_masks = (struct rte_eth_fdir_flex_masks *)rte_zmalloc_socket("CLI",
+		cfg_size, CACHE_LINE_SIZE, rte_socket_id());
+
+	if (flex_masks == NULL) {
+		printf("fail to malloc memory to configure flex mask.\n");
+		return;
+	}
+
+	if (!strcmp(res->flow_type, "ip4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_IPV4_OTHER;
+	else if (!strcmp(res->flow_type, "udp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV4;
+	else if (!strcmp(res->flow_type, "tcp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV4;
+	else if (!strcmp(res->flow_type, "sctp4"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV4;
+	else if (!strcmp(res->flow_type, "ip6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_IPV6_OTHER;
+	else if (!strcmp(res->flow_type, "udp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_UDPV6;
+	else if (!strcmp(res->flow_type, "tcp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_TCPV6;
+	else if (!strcmp(res->flow_type, "sctp6"))
+		flex_masks->flow_type = RTE_ETH_FLOW_TYPE_SCTPV6;
+
+	flex_masks->words_mask = res->words;
+	ret = parse_word_masks_cfg(res->word_mask_list, flex_masks);
+	if (ret < 0) {
+		printf("error: Cannot parse words masks input.\n");
+		rte_free(flex_masks);
+		return;
+	}
+
+	fdir_cfg.cmd = RTE_ETH_FDIR_CFG_FLX_MASK;
+	fdir_cfg.cfg = flex_masks;
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+				     RTE_ETH_FILTER_SET, &fdir_cfg);
+	if (ret < 0)
+		printf("fdir flex mask setting error: (%s)\n", strerror(-ret));
+	rte_free(flex_masks);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexmask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_director_flexmask,
+				 "flow_director_flex_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_type,
+				 "ip4#tcp4#udp4#sctp4#ip6#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_words_mask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 words_mask, "words_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_words =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      words, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_word_mask_list =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 word_mask_list, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_mask = {
+	.f = cmd_flow_director_flex_mask_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex mask on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexmask,
+		(void *)&cmd_flow_director_flexmask_port_id,
+		(void *)&cmd_flow_director_flexmask_flow,
+		(void *)&cmd_flow_director_flexmask_flow_type,
+		(void *)&cmd_flow_director_flexmask_words_mask,
+		(void *)&cmd_flow_director_flexmask_words,
+		(void *)&cmd_flow_director_flexmask_word_mask_list,
+		NULL,
+	},
+};
+
 /* *** deal with flow director flexible payload configuration *** */
 struct cmd_flow_director_flexpayload_result {
 	cmdline_fixed_string_t flow_director_flexpayload;
@@ -8400,6 +8572,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_mask,
 	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
 	NULL,
 };
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (23 preceding siblings ...)
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
@ 2014-10-30  7:34   ` Cao, Min
  2014-11-19  7:53   ` Cao, Min
  25 siblings, 0 replies; 123+ messages in thread
From: Cao, Min @ 2014-10-30  7:34 UTC (permalink / raw)
  To: Wu, Jingjing, dev

Tested-by: Min Cao <min.cao@intel.com>

Patch name: 		Support flow director programming on Fortville
Brief description: 	add flexible payload
Test Flag: 			Tested-by
Tester name: 		min.cao@intel.com
Result summary:		total 3 cases, 3 passed, 0 failed

Test Case 1:		
Name:				Fortville flow director with no flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 2:		
Name:				Fortville flow director with flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 3:		
Name:				Fortville flow director flush
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED



-----Original Message-----
From: Wu, Jingjing 
Sent: Wednesday, October 22, 2014 9:01 AM
To: dev@dpdk.org
Cc: Wu, Jingjing; Cao, Min
Subject: [PATCH v4 00/21] Support flow director programming on Fortville

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics, FD_ID report.
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison and flex bytes report.

v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 changes:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison 
 
v4 changes:
 - strip the filter APIs definitions from this patch set
 - extend mbuf field to support flex bytes report
 - fix typos

Jingjing Wu (21):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  ethdev: define structures for adding/deleting flow director
  i40e: implement operations to add/delete flow director
  testpmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  mbuf: extend fdir field
  i40e: report flow director match info to mbuf
  testpmd: print extended fdir info in mbuf
  ethdev: define structures for getting flow director information
  i40e: implement operations to get fdir info
  testpmd: display fdir statistics
  i40e: implement operation to flush flow director table
  testpmd: add test command to flush flow director table
  ethdev: define structures for configuring flexible payload
  i40e: implement operations to configure flexible payload
  testpmd: add test command to configure flexible payload
  ethdev:  define structures for configuring flex masks
  i40e: implement operations to configure flexible masks
  testpmd: add test command to configure flexible masks

 app/test-pmd/cmdline.c            |  812 ++++++++++++++++++++++++
 app/test-pmd/config.c             |   38 +-
 app/test-pmd/rxonly.c             |   14 +-
 app/test-pmd/testpmd.h            |    3 +
 lib/librte_ether/rte_eth_ctrl.h   |  266 ++++++++
 lib/librte_ether/rte_ethdev.h     |   23 -
 lib/librte_mbuf/rte_mbuf.h        |   12 +-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  127 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   34 +-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1222 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  225 ++++++-
 12 files changed, 2723 insertions(+), 55 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (20 preceding siblings ...)
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 21/21] testpmd: add test command " Jingjing Wu
@ 2014-10-30  8:07     ` Jingjing Wu
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-10-30  8:07 UTC (permalink / raw)
  To: dev

To support flow director, this patch sets up fortville resources. It  includes
 - Queue 0 pair allocated and set up for flow director
 - Create vsi
 - Reserve memzone for flow director programming packet

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/Makefile      |   2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  79 +++++++++++---
 lib/librte_pmd_i40e/i40e_ethdev.h |  31 +++++-
 lib/librte_pmd_i40e/i40e_fdir.c   | 222 ++++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   | 127 ++++++++++++++++++++++
 5 files changed, 447 insertions(+), 14 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

diff --git a/lib/librte_pmd_i40e/Makefile b/lib/librte_pmd_i40e/Makefile
index bd3428f..98e4bdf 100644
--- a/lib/librte_pmd_i40e/Makefile
+++ b/lib/librte_pmd_i40e/Makefile
@@ -91,6 +91,8 @@ SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_rxtx.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev_vf.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_pf.c
+SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_fdir.c
+
 # this lib depends upon:
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_eal lib/librte_ether
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_mempool lib/librte_mbuf
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index c39eedc..cea7725 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -778,6 +778,12 @@ i40e_dev_start(struct rte_eth_dev *dev)
 	i40e_vsi_queues_bind_intr(vsi);
 	i40e_vsi_enable_queues_intr(vsi);
 
+	/* enable FDIR MSIX interrupt */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
+		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
+	}
+
 	/* Enable all queues which have been configured */
 	ret = i40e_vsi_switch_queues(vsi, TRUE);
 	if (ret != I40E_SUCCESS) {
@@ -2615,16 +2621,30 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	case I40E_VSI_SRIOV :
 		vsi->nb_qps = pf->vf_nb_qps;
 		break;
+	case I40E_VSI_FDIR:
+		vsi->nb_qps = pf->fdir_nb_qps;
+		break;
 	default:
 		goto fail_mem;
 	}
-	ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
-	if (ret < 0) {
-		PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
-				vsi->seid, ret);
-		goto fail_mem;
-	}
-	vsi->base_queue = ret;
+	/*
+	 * The filter status descriptor is reported in rx queue 0,
+	 * while the tx queue for fdir filter programming has no
+	 * such constraints, can be non-zero queues.
+	 * To simplify it, choose FDIR vsi use queue 0 pair.
+	 * To make sure it will use queue 0 pair, queue allocation
+	 * need be done before this function is called
+	 */
+	if (type != I40E_VSI_FDIR) {
+		ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
+			if (ret < 0) {
+				PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
+						vsi->seid, ret);
+				goto fail_mem;
+			}
+			vsi->base_queue = ret;
+	} else
+		vsi->base_queue = I40E_FDIR_QUEUE_ID;
 
 	/* VF has MSIX interrupt in VF range, don't allocate here */
 	if (type != I40E_VSI_SRIOV) {
@@ -2756,9 +2776,25 @@ i40e_vsi_setup(struct i40e_pf *pf,
 		 * Since VSI is not created yet, only configure parameter,
 		 * will add vsi below.
 		 */
-	}
-	else {
-		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet");
+	} else if (type == I40E_VSI_FDIR) {
+		vsi->uplink_seid = uplink_vsi->uplink_seid;
+		ctxt.pf_num = hw->pf_id;
+		ctxt.vf_num = 0;
+		ctxt.uplink_seid = vsi->uplink_seid;
+		ctxt.connection_type = 0x1;     /* regular data port */
+		ctxt.flags = I40E_AQ_VSI_TYPE_PF;
+		ret = i40e_vsi_config_tc_queue_mapping(vsi, &ctxt.info,
+						I40E_DEFAULT_TCMAP);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to configure "
+					"TC queue mapping.");
+			goto fail_msix_alloc;
+		}
+		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
+		ctxt.info.valid_sections |=
+			rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
+	} else {
+		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet.");
 		goto fail_msix_alloc;
 	}
 
@@ -2943,8 +2979,16 @@ i40e_pf_setup(struct i40e_pf *pf)
 		PMD_DRV_LOG(ERR, "Could not get switch config, err %d", ret);
 		return ret;
 	}
-
-	/* VSI setup */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		/* make queue allocated first, let FDIR use queue pair 0*/
+		ret = i40e_res_pool_alloc(&pf->qp_pool, I40E_DEFAULT_QP_NUM_FDIR);
+		if (ret != I40E_FDIR_QUEUE_ID) {
+			PMD_DRV_LOG(ERR, "queue allocation fails for FDIR :"
+				    " ret =%d", ret);
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+	/*  main VSI setup */
 	vsi = i40e_vsi_setup(pf, I40E_VSI_MAIN, NULL, 0);
 	if (!vsi) {
 		PMD_DRV_LOG(ERR, "Setup of main vsi failed");
@@ -2954,9 +2998,20 @@ i40e_pf_setup(struct i40e_pf *pf)
 	dev_data->nb_rx_queues = vsi->nb_qps;
 	dev_data->nb_tx_queues = vsi->nb_qps;
 
+	/* setup FDIR after main vsi created.*/
+	if (pf->flags & I40E_FLAG_FDIR) {
+		ret = i40e_fdir_setup(pf);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to setup flow director.");
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+
 	/* Configure filter control */
 	memset(&settings, 0, sizeof(settings));
 	settings.hash_lut_size = I40E_HASH_LUT_SIZE_128;
+	if (pf->flags & I40E_FLAG_FDIR)
+		settings.enable_fdir = TRUE;
 	/* Enable ethtype and macvlan filters */
 	settings.enable_ethtype = TRUE;
 	settings.enable_macvlan = TRUE;
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index a315adf..6d30f75 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -46,11 +46,12 @@
 /* number of VSIs and queue default setting */
 #define I40E_MAX_QP_NUM_PER_VF    16
 #define I40E_DEFAULT_QP_NUM_VMDQ  64
-#define I40E_DEFAULT_QP_NUM_FDIR  64
+#define I40E_DEFAULT_QP_NUM_FDIR  1
 #define I40E_UINT32_BIT_SIZE      (CHAR_BIT * sizeof(uint32_t))
 #define I40E_VFTA_SIZE            (4096 / I40E_UINT32_BIT_SIZE)
 /* Default TC traffic in case DCB is not enabled */
 #define I40E_DEFAULT_TCMAP        0x1
+#define I40E_FDIR_QUEUE_ID        0
 
 /* i40e flags */
 #define I40E_FLAG_RSS                   (1ULL << 0)
@@ -221,6 +222,27 @@ struct i40e_pf_vf {
 };
 
 /*
+ *  A structure used to define fields of a FDIR related info.
+ */
+struct i40e_fdir_info {
+	struct i40e_vsi *fdir_vsi;     /* pointer to fdir VSI structure */
+	uint16_t match_counter_index;  /* Statistic counter index used for fdir*/
+	struct i40e_tx_queue *txq;
+	struct i40e_rx_queue *rxq;
+	void *prg_pkt;                 /* memory for fdir program packet */
+	uint64_t dma_addr;             /* physic address of packet memory*/
+	/*
+	 * the rule how bytes stream is extracted as flexible payload
+	 * for each payload layer, the setting can up to three elements
+	 */
+	struct {
+		uint8_t offset;        /* offset in words from the beginning of payload */
+		uint8_t size;          /* size in words */
+	} flex_set[3][3];
+
+};
+
+/*
  * Structure to store private data specific for PF instance.
  */
 struct i40e_pf {
@@ -248,10 +270,10 @@ struct i40e_pf {
 	uint16_t vmdq_nb_qps; /* The number of queue pairs of VMDq */
 	uint16_t vf_nb_qps; /* The number of queue pairs of VF */
 	uint16_t fdir_nb_qps; /* The number of queue pairs of Flow Director */
-
 	/* store VXLAN UDP ports */
 	uint16_t vxlan_ports[I40E_MAX_PF_UDP_OFFLOAD_PORTS];
 	uint16_t vxlan_bitmap; /* Vxlan bit mask */
+	struct i40e_fdir_info fdir; /* flow director info */
 };
 
 enum pending_msg {
@@ -352,6 +374,11 @@ int i40e_vsi_vlan_pvid_set(struct i40e_vsi *vsi,
 int i40e_vsi_config_vlan_stripping(struct i40e_vsi *vsi, bool on);
 uint64_t i40e_config_hena(uint64_t flags);
 uint64_t i40e_parse_hena(uint64_t flags);
+enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id);
+int i40e_fdir_setup(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
new file mode 100644
index 0000000..a44bb73
--- /dev/null
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -0,0 +1,222 @@
+/*-
+ *   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 <sys/queue.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdint.h>
+#include <string.h>
+#include <unistd.h>
+#include <stdarg.h>
+
+#include <rte_ether.h>
+#include <rte_ethdev.h>
+#include <rte_log.h>
+#include <rte_memzone.h>
+#include <rte_malloc.h>
+
+#include "i40e_logs.h"
+#include "i40e/i40e_type.h"
+#include "i40e_ethdev.h"
+#include "i40e_rxtx.h"
+
+#define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#define I40E_FDIR_PKT_LEN                   512
+
+#define I40E_COUNTER_PF           2
+/* Statistic counter index for one pf */
+#define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+#define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
+
+static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+
+static int
+i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
+{
+	struct i40e_hw *hw = I40E_VSI_TO_HW(rxq->vsi);
+	struct i40e_hmc_obj_rxq rx_ctx;
+	int err = I40E_SUCCESS;
+
+	memset(&rx_ctx, 0, sizeof(struct i40e_hmc_obj_rxq));
+	/* Init the RX queue in hardware */
+	rx_ctx.dbuff = I40E_RXBUF_SZ_1024 >> I40E_RXQ_CTX_DBUFF_SHIFT;
+	rx_ctx.hbuff = 0;
+	rx_ctx.base = rxq->rx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
+	rx_ctx.qlen = rxq->nb_rx_desc;
+#ifndef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+	rx_ctx.dsize = 1;
+#endif
+	rx_ctx.dtype = i40e_header_split_none;
+	rx_ctx.hsplit_0 = I40E_HEADER_SPLIT_NONE;
+	rx_ctx.rxmax = ETHER_MAX_LEN;
+	rx_ctx.tphrdesc_ena = 1;
+	rx_ctx.tphwdesc_ena = 1;
+	rx_ctx.tphdata_ena = 1;
+	rx_ctx.tphhead_ena = 1;
+	rx_ctx.lrxqthresh = 2;
+	rx_ctx.crcstrip = 0;
+	rx_ctx.l2tsel = 1;
+	rx_ctx.showiv = 1;
+	rx_ctx.prefena = 1;
+
+	err = i40e_clear_lan_rx_queue_context(hw, rxq->reg_idx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to clear FDIR RX queue context.");
+		return err;
+	}
+	err = i40e_set_lan_rx_queue_context(hw, rxq->reg_idx, &rx_ctx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to set FDIR RX queue context.");
+		return err;
+	}
+	rxq->qrx_tail = hw->hw_addr +
+		I40E_QRX_TAIL(rxq->vsi->base_queue);
+
+	rte_wmb();
+	/* Init the RX tail regieter. */
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, 0);
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, rxq->nb_rx_desc - 1);
+
+	return err;
+}
+
+/*
+ * i40e_fdir_setup - reserve and initialize the Flow Director resources
+ * @pf: board private structure
+ */
+int
+i40e_fdir_setup(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_vsi *vsi;
+	int err = I40E_SUCCESS;
+	char z_name[RTE_MEMZONE_NAMESIZE];
+	const struct rte_memzone *mz = NULL;
+	struct rte_eth_dev *eth_dev = pf->adapter->eth_dev;
+
+	PMD_DRV_LOG(INFO, "FDIR HW Capabilities: num_filters_guaranteed = %u,"
+			" num_filters_best_effort = %u.",
+			hw->func_caps.fd_filters_guaranteed,
+			hw->func_caps.fd_filters_best_effort);
+
+	vsi = pf->fdir.fdir_vsi;
+	if (vsi) {
+		PMD_DRV_LOG(ERR, "FDIR vsi pointer needs"
+				 "to be null before creation.");
+		return I40E_ERR_BAD_PTR;
+	}
+	/* make new FDIR VSI */
+	vsi = i40e_vsi_setup(pf, I40E_VSI_FDIR, pf->main_vsi, 0);
+	if (!vsi) {
+		PMD_DRV_LOG(ERR, "Couldn't create FDIR VSI.");
+		return I40E_ERR_NO_AVAILABLE_VSI;
+	}
+	pf->fdir.fdir_vsi = vsi;
+
+	/*Fdir tx queue setup*/
+	err = i40e_fdir_setup_tx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR TX resources.");
+		goto fail_setup_tx;
+	}
+
+	/*Fdir rx queue setup*/
+	err = i40e_fdir_setup_rx_resources(pf, 0);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR RX resources.");
+		goto fail_setup_rx;
+	}
+
+	err = i40e_tx_queue_init(pf->fdir.txq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR TX initialization.");
+		goto fail_mem;
+	}
+
+	/* need switch on before dev start*/
+	err = i40e_switch_tx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do fdir TX switch on.");
+		goto fail_mem;
+	}
+
+	/* Init the rx queue in hardware */
+	err = i40e_fdir_rx_queue_init(pf->fdir.rxq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX initialization.");
+		goto fail_mem;
+	}
+
+	/* switch on rx queue */
+	err = i40e_switch_rx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX switch on.");
+		goto fail_mem;
+	}
+
+	/* reserve memory for the fdir programming packet */
+	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
+			eth_dev->driver->pci_drv.name,
+			I40E_FDIR_MZ_NAME,
+			eth_dev->data->port_id);
+	mz = rte_memzone_lookup(z_name);
+	if (!mz) {
+		mz = rte_memzone_reserve(z_name,
+				I40E_FDIR_PKT_LEN,
+				rte_socket_id(),
+				0);
+		if (!mz) {
+			PMD_DRV_LOG(ERR, "Cannot init memzone for"
+				"flow director program packet.");
+			err = I40E_ERR_NO_MEMORY;
+			goto fail_mem;
+		}
+	}
+	pf->fdir.prg_pkt = mz->addr;
+	pf->fdir.dma_addr = (uint64_t)mz->phys_addr;
+	pf->fdir.match_counter_index = I40E_COUNTER_INDEX_FDIR(hw->pf_id);
+	PMD_DRV_LOG(INFO, "FDIR setup successfully, with programming queue %u.",
+		    vsi->base_queue);
+	return I40E_SUCCESS;
+
+fail_mem:
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+fail_setup_rx:
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+fail_setup_tx:
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return err;
+}
\ No newline at end of file
diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 315a9c0..f2334de 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -2150,6 +2150,8 @@ i40e_tx_queue_init(struct i40e_tx_queue *txq)
 	tx_ctx.base = txq->tx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
 	tx_ctx.qlen = txq->nb_tx_desc;
 	tx_ctx.rdylist = rte_le_to_cpu_16(vsi->info.qs_handle[0]);
+	if (vsi->type == I40E_VSI_FDIR)
+		tx_ctx.fd_ena = TRUE;
 
 	err = i40e_clear_lan_tx_queue_context(hw, pf_q);
 	if (err != I40E_SUCCESS) {
@@ -2366,3 +2368,128 @@ i40e_dev_clear_queues(struct rte_eth_dev *dev)
 		i40e_reset_rx_queue(dev->data->rx_queues[i]);
 	}
 }
+
+enum i40e_status_code
+i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_tx_queue *txq;
+	const struct rte_memzone *tz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_TX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	txq = rte_zmalloc_socket("i40e fdir tx queue",
+				  sizeof(struct i40e_tx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!txq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"tx queue structure.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(struct i40e_tx_desc) * I40E_FDIR_NUM_TX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	tz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_tx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!tz) {
+		i40e_dev_tx_queue_release(txq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for TX.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	txq->nb_tx_desc = I40E_FDIR_NUM_TX_DESC;
+	txq->queue_id = I40E_FDIR_QUEUE_ID;
+	txq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	txq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	txq->tx_ring_phys_addr = rte_mem_phy2mch(tz->memseg_id, tz->phys_addr);
+#else
+	txq->tx_ring_phys_addr = (uint64_t)tz->phys_addr;
+#endif
+	txq->tx_ring = (struct i40e_tx_desc *)tz->addr;
+	/*
+	 * don't need to allocate software ring and reset for the fdir
+	 * program queue just set the queue has been configured.
+	 */
+	txq->q_set = TRUE;
+	pf->fdir.txq = txq;
+
+	return I40E_SUCCESS;
+}
+
+enum i40e_status_code
+i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
+				    unsigned int socket_id)
+{
+	struct i40e_rx_queue *rxq;
+	const struct rte_memzone *rz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+#define I40E_FDIR_NUM_RX_DESC  I40E_MIN_RING_DESC
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	rxq = rte_zmalloc_socket("i40e fdir rx queue",
+				  sizeof(struct i40e_rx_queue),
+				  CACHE_LINE_SIZE,
+				  socket_id);
+	if (!rxq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"rx queue structure.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(union i40e_rx_desc) * I40E_FDIR_NUM_RX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	rz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_rx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					socket_id);
+	if (!rz) {
+		i40e_dev_rx_queue_release(rxq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for RX.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	rxq->nb_rx_desc = I40E_FDIR_NUM_RX_DESC;
+	rxq->queue_id = I40E_FDIR_QUEUE_ID;
+	rxq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	rxq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	rxq->rx_ring_phys_addr = rte_mem_phy2mch(rz->memseg_id, rz->phys_addr);
+#else
+	rxq->rx_ring_phys_addr = (uint64_t)rz->phys_addr;
+#endif
+	rxq->rx_ring = (union i40e_rx_desc *)rz->addr;
+
+	/*
+	 * Don't need to allocate software ring and reset for the fdir
+	 * rx queue, just set the queue has been configured.
+	 */
+	rxq->q_set = TRUE;
+	pf->fdir.rxq = rxq;
+
+	return I40E_SUCCESS;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
@ 2014-10-30  8:25       ` Wu, Jingjing
  0 siblings, 0 replies; 123+ messages in thread
From: Wu, Jingjing @ 2014-10-30  8:25 UTC (permalink / raw)
  To: dev

Please ignore this patch sent by mistake. It should be replaced by another patch with the same name.
http://www.dpdk.org/ml/archives/dev/2014-October/007374.html

Sorry for the inconvenience.

> -----Original Message-----
> From: Wu, Jingjing
> Sent: Thursday, October 30, 2014 3:26 PM
> To: dev@dpdk.org
> Cc: Wu, Jingjing; Cao, Min
> Subject: [PATCH v5 01/21] i40e: set up and initialize flow director
> 
> To support flow director, this patch sets up fortville resources. It  includes
>  - Queue 0 pair allocated and set up for flow director
>  - Create vsi
>  - Reserve memzone for flow director programming packet
> 
> Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
> ---
>  lib/librte_pmd_i40e/Makefile      |   2 +
>  lib/librte_pmd_i40e/i40e_ethdev.c |  79 +++++++++++---
> lib/librte_pmd_i40e/i40e_ethdev.h |  31 +++++-
>  lib/librte_pmd_i40e/i40e_fdir.c   | 222
> ++++++++++++++++++++++++++++++++++++++
>  lib/librte_pmd_i40e/i40e_rxtx.c   | 127 ++++++++++++++++++++++
>  5 files changed, 447 insertions(+), 14 deletions(-)  create mode 100644
> lib/librte_pmd_i40e/i40e_fdir.c
> 
> diff --git a/lib/librte_pmd_i40e/Makefile b/lib/librte_pmd_i40e/Makefile
> index bd3428f..98e4bdf 100644
> --- a/lib/librte_pmd_i40e/Makefile
> +++ b/lib/librte_pmd_i40e/Makefile
> @@ -91,6 +91,8 @@ SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) +=
> i40e_ethdev.c
>  SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_rxtx.c
>  SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev_vf.c
>  SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_pf.c
> +SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_fdir.c
> +
>  # this lib depends upon:
>  DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_eal
> lib/librte_ether
>  DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_mempool
> lib/librte_mbuf diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c
> b/lib/librte_pmd_i40e/i40e_ethdev.c
> index c39eedc..cea7725 100644
> --- a/lib/librte_pmd_i40e/i40e_ethdev.c
> +++ b/lib/librte_pmd_i40e/i40e_ethdev.c
> @@ -778,6 +778,12 @@ i40e_dev_start(struct rte_eth_dev *dev)
>  	i40e_vsi_queues_bind_intr(vsi);
>  	i40e_vsi_enable_queues_intr(vsi);
> 
> +	/* enable FDIR MSIX interrupt */
> +	if (pf->flags & I40E_FLAG_FDIR) {
> +		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
> +		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
> +	}
> +
>  	/* Enable all queues which have been configured */
>  	ret = i40e_vsi_switch_queues(vsi, TRUE);
>  	if (ret != I40E_SUCCESS) {
> @@ -2615,16 +2621,30 @@ i40e_vsi_setup(struct i40e_pf *pf,
>  	case I40E_VSI_SRIOV :
>  		vsi->nb_qps = pf->vf_nb_qps;
>  		break;
> +	case I40E_VSI_FDIR:
> +		vsi->nb_qps = pf->fdir_nb_qps;
> +		break;
>  	default:
>  		goto fail_mem;
>  	}
> -	ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
> -	if (ret < 0) {
> -		PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
> -				vsi->seid, ret);
> -		goto fail_mem;
> -	}
> -	vsi->base_queue = ret;
> +	/*
> +	 * The filter status descriptor is reported in rx queue 0,
> +	 * while the tx queue for fdir filter programming has no
> +	 * such constraints, can be non-zero queues.
> +	 * To simplify it, choose FDIR vsi use queue 0 pair.
> +	 * To make sure it will use queue 0 pair, queue allocation
> +	 * need be done before this function is called
> +	 */
> +	if (type != I40E_VSI_FDIR) {
> +		ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
> +			if (ret < 0) {
> +				PMD_DRV_LOG(ERR, "VSI %d allocate queue
> failed %d",
> +						vsi->seid, ret);
> +				goto fail_mem;
> +			}
> +			vsi->base_queue = ret;
> +	} else
> +		vsi->base_queue = I40E_FDIR_QUEUE_ID;
> 
>  	/* VF has MSIX interrupt in VF range, don't allocate here */
>  	if (type != I40E_VSI_SRIOV) {
> @@ -2756,9 +2776,25 @@ i40e_vsi_setup(struct i40e_pf *pf,
>  		 * Since VSI is not created yet, only configure parameter,
>  		 * will add vsi below.
>  		 */
> -	}
> -	else {
> -		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet");
> +	} else if (type == I40E_VSI_FDIR) {
> +		vsi->uplink_seid = uplink_vsi->uplink_seid;
> +		ctxt.pf_num = hw->pf_id;
> +		ctxt.vf_num = 0;
> +		ctxt.uplink_seid = vsi->uplink_seid;
> +		ctxt.connection_type = 0x1;     /* regular data port */
> +		ctxt.flags = I40E_AQ_VSI_TYPE_PF;
> +		ret = i40e_vsi_config_tc_queue_mapping(vsi, &ctxt.info,
> +						I40E_DEFAULT_TCMAP);
> +		if (ret != I40E_SUCCESS) {
> +			PMD_DRV_LOG(ERR, "Failed to configure "
> +					"TC queue mapping\n");
> +			goto fail_msix_alloc;
> +		}
> +		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
> +		ctxt.info.valid_sections |=
> +
> 	rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
> +	} else {
> +		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI
> yet\n");
>  		goto fail_msix_alloc;
>  	}
> 
> @@ -2943,8 +2979,16 @@ i40e_pf_setup(struct i40e_pf *pf)
>  		PMD_DRV_LOG(ERR, "Could not get switch config, err %d",
> ret);
>  		return ret;
>  	}
> -
> -	/* VSI setup */
> +	if (pf->flags & I40E_FLAG_FDIR) {
> +		/* make queue allocated first, let FDIR use queue pair 0*/
> +		ret = i40e_res_pool_alloc(&pf->qp_pool,
> I40E_DEFAULT_QP_NUM_FDIR);
> +		if (ret != I40E_FDIR_QUEUE_ID) {
> +			PMD_DRV_LOG(ERR, "queue allocation fails for
> FDIR :"
> +				    " ret =%d", ret);
> +			pf->flags &= ~I40E_FLAG_FDIR;
> +		}
> +	}
> +	/*  main VSI setup */
>  	vsi = i40e_vsi_setup(pf, I40E_VSI_MAIN, NULL, 0);
>  	if (!vsi) {
>  		PMD_DRV_LOG(ERR, "Setup of main vsi failed"); @@ -2954,9
> +2998,20 @@ i40e_pf_setup(struct i40e_pf *pf)
>  	dev_data->nb_rx_queues = vsi->nb_qps;
>  	dev_data->nb_tx_queues = vsi->nb_qps;
> 
> +	/* setup FDIR after main vsi created.*/
> +	if (pf->flags & I40E_FLAG_FDIR) {
> +		ret = i40e_fdir_setup(pf);
> +		if (ret != I40E_SUCCESS) {
> +			PMD_DRV_LOG(ERR, "Failed to setup flow
> director\n");
> +			pf->flags &= ~I40E_FLAG_FDIR;
> +		}
> +	}
> +
>  	/* Configure filter control */
>  	memset(&settings, 0, sizeof(settings));
>  	settings.hash_lut_size = I40E_HASH_LUT_SIZE_128;
> +	if (pf->flags & I40E_FLAG_FDIR)
> +		settings.enable_fdir = TRUE;
>  	/* Enable ethtype and macvlan filters */
>  	settings.enable_ethtype = TRUE;
>  	settings.enable_macvlan = TRUE;
> diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h
> b/lib/librte_pmd_i40e/i40e_ethdev.h
> index a315adf..6d30f75 100644
> --- a/lib/librte_pmd_i40e/i40e_ethdev.h
> +++ b/lib/librte_pmd_i40e/i40e_ethdev.h
> @@ -46,11 +46,12 @@
>  /* number of VSIs and queue default setting */
>  #define I40E_MAX_QP_NUM_PER_VF    16
>  #define I40E_DEFAULT_QP_NUM_VMDQ  64
> -#define I40E_DEFAULT_QP_NUM_FDIR  64
> +#define I40E_DEFAULT_QP_NUM_FDIR  1
>  #define I40E_UINT32_BIT_SIZE      (CHAR_BIT * sizeof(uint32_t))
>  #define I40E_VFTA_SIZE            (4096 / I40E_UINT32_BIT_SIZE)
>  /* Default TC traffic in case DCB is not enabled */
>  #define I40E_DEFAULT_TCMAP        0x1
> +#define I40E_FDIR_QUEUE_ID        0
> 
>  /* i40e flags */
>  #define I40E_FLAG_RSS                   (1ULL << 0)
> @@ -221,6 +222,27 @@ struct i40e_pf_vf {  };
> 
>  /*
> + *  A structure used to define fields of a FDIR related info.
> + */
> +struct i40e_fdir_info {
> +	struct i40e_vsi *fdir_vsi;     /* pointer to fdir VSI structure */
> +	uint16_t match_counter_index;  /* Statistic counter index used for
> fdir*/
> +	struct i40e_tx_queue *txq;
> +	struct i40e_rx_queue *rxq;
> +	void *prg_pkt;                 /* memory for fdir program packet */
> +	uint64_t dma_addr;             /* physic address of packet memory*/
> +	/*
> +	 * the rule how bytes stream is extracted as flexible payload
> +	 * for each payload layer, the setting can up to three elements
> +	 */
> +	struct {
> +		uint8_t offset;        /* offset in words from the beginning of
> payload */
> +		uint8_t size;          /* size in words */
> +	} flex_set[3][3];
> +
> +};
> +
> +/*
>   * Structure to store private data specific for PF instance.
>   */
>  struct i40e_pf {
> @@ -248,10 +270,10 @@ struct i40e_pf {
>  	uint16_t vmdq_nb_qps; /* The number of queue pairs of VMDq */
>  	uint16_t vf_nb_qps; /* The number of queue pairs of VF */
>  	uint16_t fdir_nb_qps; /* The number of queue pairs of Flow Director
> */
> -
>  	/* store VXLAN UDP ports */
>  	uint16_t vxlan_ports[I40E_MAX_PF_UDP_OFFLOAD_PORTS];
>  	uint16_t vxlan_bitmap; /* Vxlan bit mask */
> +	struct i40e_fdir_info fdir; /* flow director info */
>  };
> 
>  enum pending_msg {
> @@ -352,6 +374,11 @@ int i40e_vsi_vlan_pvid_set(struct i40e_vsi *vsi,  int
> i40e_vsi_config_vlan_stripping(struct i40e_vsi *vsi, bool on);  uint64_t
> i40e_config_hena(uint64_t flags);  uint64_t i40e_parse_hena(uint64_t flags);
> +enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
> +				    unsigned int socket_id);
> +enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
> +				    unsigned int socket_id);
> +int i40e_fdir_setup(struct i40e_pf *pf);
> 
>  /* I40E_DEV_PRIVATE_TO */
>  #define I40E_DEV_PRIVATE_TO_PF(adapter) \ diff --git
> a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c new file
> mode 100644 index 0000000..a44bb73
> --- /dev/null
> +++ b/lib/librte_pmd_i40e/i40e_fdir.c
> @@ -0,0 +1,222 @@
> +/*-
> + *   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 <sys/queue.h>
> +#include <stdio.h>
> +#include <errno.h>
> +#include <stdint.h>
> +#include <string.h>
> +#include <unistd.h>
> +#include <stdarg.h>
> +
> +#include <rte_ether.h>
> +#include <rte_ethdev.h>
> +#include <rte_log.h>
> +#include <rte_memzone.h>
> +#include <rte_malloc.h>
> +
> +#include "i40e_logs.h"
> +#include "i40e/i40e_type.h"
> +#include "i40e_ethdev.h"
> +#include "i40e_rxtx.h"
> +
> +#define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
> +#define I40E_FDIR_PKT_LEN                   512
> +
> +#define I40E_COUNTER_PF           2
> +/* Statistic counter index for one pf */
> +#define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) *
> I40E_COUNTER_PF)
> +#define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
> +
> +static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
> +
> +static int
> +i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq) {
> +	struct i40e_hw *hw = I40E_VSI_TO_HW(rxq->vsi);
> +	struct i40e_hmc_obj_rxq rx_ctx;
> +	int err = I40E_SUCCESS;
> +
> +	memset(&rx_ctx, 0, sizeof(struct i40e_hmc_obj_rxq));
> +	/* Init the RX queue in hardware */
> +	rx_ctx.dbuff = I40E_RXBUF_SZ_1024 >>
> I40E_RXQ_CTX_DBUFF_SHIFT;
> +	rx_ctx.hbuff = 0;
> +	rx_ctx.base = rxq->rx_ring_phys_addr /
> I40E_QUEUE_BASE_ADDR_UNIT;
> +	rx_ctx.qlen = rxq->nb_rx_desc;
> +#ifndef RTE_LIBRTE_I40E_16BYTE_RX_DESC
> +	rx_ctx.dsize = 1;
> +#endif
> +	rx_ctx.dtype = i40e_header_split_none;
> +	rx_ctx.hsplit_0 = I40E_HEADER_SPLIT_NONE;
> +	rx_ctx.rxmax = ETHER_MAX_LEN;
> +	rx_ctx.tphrdesc_ena = 1;
> +	rx_ctx.tphwdesc_ena = 1;
> +	rx_ctx.tphdata_ena = 1;
> +	rx_ctx.tphhead_ena = 1;
> +	rx_ctx.lrxqthresh = 2;
> +	rx_ctx.crcstrip = 0;
> +	rx_ctx.l2tsel = 1;
> +	rx_ctx.showiv = 1;
> +	rx_ctx.prefena = 1;
> +
> +	err = i40e_clear_lan_rx_queue_context(hw, rxq->reg_idx);
> +	if (err != I40E_SUCCESS) {
> +		PMD_DRV_LOG(ERR, "Failed to clear FDIR RX queue
> context.");
> +		return err;
> +	}
> +	err = i40e_set_lan_rx_queue_context(hw, rxq->reg_idx, &rx_ctx);
> +	if (err != I40E_SUCCESS) {
> +		PMD_DRV_LOG(ERR, "Failed to set FDIR RX queue context.");
> +		return err;
> +	}
> +	rxq->qrx_tail = hw->hw_addr +
> +		I40E_QRX_TAIL(rxq->vsi->base_queue);
> +
> +	rte_wmb();
> +	/* Init the RX tail regieter. */
> +	I40E_PCI_REG_WRITE(rxq->qrx_tail, 0);
> +	I40E_PCI_REG_WRITE(rxq->qrx_tail, rxq->nb_rx_desc - 1);
> +
> +	return err;
> +}
> +
> +/*
> + * i40e_fdir_setup - reserve and initialize the Flow Director resources
> + * @pf: board private structure
> + */
> +int
> +i40e_fdir_setup(struct i40e_pf *pf)
> +{
> +	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
> +	struct i40e_vsi *vsi;
> +	int err = I40E_SUCCESS;
> +	char z_name[RTE_MEMZONE_NAMESIZE];
> +	const struct rte_memzone *mz = NULL;
> +	struct rte_eth_dev *eth_dev = pf->adapter->eth_dev;
> +
> +	PMD_DRV_LOG(INFO, "FDIR HW Capabilities:
> num_filters_guaranteed = %u,"
> +			" num_filters_best_effort = %u.",
> +			hw->func_caps.fd_filters_guaranteed,
> +			hw->func_caps.fd_filters_best_effort);
> +
> +	vsi = pf->fdir.fdir_vsi;
> +	if (vsi) {
> +		PMD_DRV_LOG(ERR, "FDIR vsi pointer needs"
> +				 "to be null before creation.");
> +		return I40E_ERR_BAD_PTR;
> +	}
> +	/* make new FDIR VSI */
> +	vsi = i40e_vsi_setup(pf, I40E_VSI_FDIR, pf->main_vsi, 0);
> +	if (!vsi) {
> +		PMD_DRV_LOG(ERR, "Couldn't create FDIR VSI.");
> +		return I40E_ERR_NO_AVAILABLE_VSI;
> +	}
> +	pf->fdir.fdir_vsi = vsi;
> +
> +	/*Fdir tx queue setup*/
> +	err = i40e_fdir_setup_tx_resources(pf, 0);
> +	if (err) {
> +		PMD_DRV_LOG(ERR, "Failed to setup FDIR TX resources.");
> +		goto fail_setup_tx;
> +	}
> +
> +	/*Fdir rx queue setup*/
> +	err = i40e_fdir_setup_rx_resources(pf, 0);
> +	if (err) {
> +		PMD_DRV_LOG(ERR, "Failed to setup FDIR RX resources.");
> +		goto fail_setup_rx;
> +	}
> +
> +	err = i40e_tx_queue_init(pf->fdir.txq);
> +	if (err) {
> +		PMD_DRV_LOG(ERR, "Failed to do FDIR TX initialization.");
> +		goto fail_mem;
> +	}
> +
> +	/* need switch on before dev start*/
> +	err = i40e_switch_tx_queue(hw, vsi->base_queue, TRUE);
> +	if (err) {
> +		PMD_DRV_LOG(ERR, "Failed to do fdir TX switch on.");
> +		goto fail_mem;
> +	}
> +
> +	/* Init the rx queue in hardware */
> +	err = i40e_fdir_rx_queue_init(pf->fdir.rxq);
> +	if (err) {
> +		PMD_DRV_LOG(ERR, "Failed to do FDIR RX initialization.");
> +		goto fail_mem;
> +	}
> +
> +	/* switch on rx queue */
> +	err = i40e_switch_rx_queue(hw, vsi->base_queue, TRUE);
> +	if (err) {
> +		PMD_DRV_LOG(ERR, "Failed to do FDIR RX switch on.");
> +		goto fail_mem;
> +	}
> +
> +	/* reserve memory for the fdir programming packet */
> +	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
> +			eth_dev->driver->pci_drv.name,
> +			I40E_FDIR_MZ_NAME,
> +			eth_dev->data->port_id);
> +	mz = rte_memzone_lookup(z_name);
> +	if (!mz) {
> +		mz = rte_memzone_reserve(z_name,
> +				I40E_FDIR_PKT_LEN,
> +				rte_socket_id(),
> +				0);
> +		if (!mz) {
> +			PMD_DRV_LOG(ERR, "Cannot init memzone for"
> +				"flow director program packet.");
> +			err = I40E_ERR_NO_MEMORY;
> +			goto fail_mem;
> +		}
> +	}
> +	pf->fdir.prg_pkt = mz->addr;
> +	pf->fdir.dma_addr = (uint64_t)mz->phys_addr;
> +	pf->fdir.match_counter_index = I40E_COUNTER_INDEX_FDIR(hw-
> >pf_id);
> +	PMD_DRV_LOG(INFO, "FDIR setup successfully, with programming
> queue %u.",
> +		    vsi->base_queue);
> +	return I40E_SUCCESS;
> +
> +fail_mem:
> +	i40e_dev_rx_queue_release(pf->fdir.rxq);
> +	pf->fdir.rxq = NULL;
> +fail_setup_rx:
> +	i40e_dev_tx_queue_release(pf->fdir.txq);
> +	pf->fdir.txq = NULL;
> +fail_setup_tx:
> +	i40e_vsi_release(vsi);
> +	pf->fdir.fdir_vsi = NULL;
> +	return err;
> +}
> \ No newline at end of file
> diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
> index 315a9c0..f2334de 100644
> --- a/lib/librte_pmd_i40e/i40e_rxtx.c
> +++ b/lib/librte_pmd_i40e/i40e_rxtx.c
> @@ -2150,6 +2150,8 @@ i40e_tx_queue_init(struct i40e_tx_queue *txq)
>  	tx_ctx.base = txq->tx_ring_phys_addr /
> I40E_QUEUE_BASE_ADDR_UNIT;
>  	tx_ctx.qlen = txq->nb_tx_desc;
>  	tx_ctx.rdylist = rte_le_to_cpu_16(vsi->info.qs_handle[0]);
> +	if (vsi->type == I40E_VSI_FDIR)
> +		tx_ctx.fd_ena = TRUE;
> 
>  	err = i40e_clear_lan_tx_queue_context(hw, pf_q);
>  	if (err != I40E_SUCCESS) {
> @@ -2366,3 +2368,128 @@ i40e_dev_clear_queues(struct rte_eth_dev
> *dev)
>  		i40e_reset_rx_queue(dev->data->rx_queues[i]);
>  	}
>  }
> +
> +enum i40e_status_code
> +i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
> +				    unsigned int socket_id)
> +{
> +	struct i40e_tx_queue *txq;
> +	const struct rte_memzone *tz = NULL;
> +	uint32_t ring_size;
> +	struct rte_eth_dev *dev = pf->adapter->eth_dev;
> +
> +#define I40E_FDIR_NUM_TX_DESC  I40E_MIN_RING_DESC
> +	if (!pf) {
> +		PMD_DRV_LOG(ERR, "PF is not available");
> +		return I40E_ERR_BAD_PTR;
> +	}
> +
> +	/* Allocate the TX queue data structure. */
> +	txq = rte_zmalloc_socket("i40e fdir tx queue",
> +				  sizeof(struct i40e_tx_queue),
> +				  CACHE_LINE_SIZE,
> +				  socket_id);
> +	if (!txq) {
> +		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
> +					"tx queue structure\n");
> +		return I40E_ERR_NO_MEMORY;
> +	}
> +
> +	/* Allocate TX hardware ring descriptors. */
> +	ring_size = sizeof(struct i40e_tx_desc) * I40E_FDIR_NUM_TX_DESC;
> +	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
> +
> +	tz = i40e_ring_dma_zone_reserve(dev,
> +					"fdir_tx_ring",
> +					I40E_FDIR_QUEUE_ID,
> +					ring_size,
> +					socket_id);
> +	if (!tz) {
> +		i40e_dev_tx_queue_release(txq);
> +		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for
> TX\n");
> +		return I40E_ERR_NO_MEMORY;
> +	}
> +
> +	txq->nb_tx_desc = I40E_FDIR_NUM_TX_DESC;
> +	txq->queue_id = I40E_FDIR_QUEUE_ID;
> +	txq->reg_idx = pf->fdir.fdir_vsi->base_queue;
> +	txq->vsi = pf->fdir.fdir_vsi;
> +
> +#ifdef RTE_LIBRTE_XEN_DOM0
> +	txq->tx_ring_phys_addr = rte_mem_phy2mch(tz->memseg_id,
> +tz->phys_addr); #else
> +	txq->tx_ring_phys_addr = (uint64_t)tz->phys_addr; #endif
> +	txq->tx_ring = (struct i40e_tx_desc *)tz->addr;
> +	/*
> +	 * don't need to allocate software ring and reset for the fdir
> +	 * program queue just set the queue has been configured.
> +	 */
> +	txq->q_set = TRUE;
> +	pf->fdir.txq = txq;
> +
> +	return I40E_SUCCESS;
> +}
> +
> +enum i40e_status_code
> +i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
> +				    unsigned int socket_id)
> +{
> +	struct i40e_rx_queue *rxq;
> +	const struct rte_memzone *rz = NULL;
> +	uint32_t ring_size;
> +	struct rte_eth_dev *dev = pf->adapter->eth_dev;
> +
> +#define I40E_FDIR_NUM_RX_DESC  I40E_MIN_RING_DESC
> +	if (!pf) {
> +		PMD_DRV_LOG(ERR, "PF is not available");
> +		return I40E_ERR_BAD_PTR;
> +	}
> +
> +	/* Allocate the TX queue data structure. */
> +	rxq = rte_zmalloc_socket("i40e fdir rx queue",
> +				  sizeof(struct i40e_rx_queue),
> +				  CACHE_LINE_SIZE,
> +				  socket_id);
> +	if (!rxq) {
> +		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
> +					"rx queue structure\n");
> +		return I40E_ERR_NO_MEMORY;
> +	}
> +
> +	/* Allocate TX hardware ring descriptors. */
> +	ring_size = sizeof(union i40e_rx_desc) * I40E_FDIR_NUM_RX_DESC;
> +	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
> +
> +	rz = i40e_ring_dma_zone_reserve(dev,
> +					"fdir_rx_ring",
> +					I40E_FDIR_QUEUE_ID,
> +					ring_size,
> +					socket_id);
> +	if (!rz) {
> +		i40e_dev_rx_queue_release(rxq);
> +		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for
> RX\n");
> +		return I40E_ERR_NO_MEMORY;
> +	}
> +
> +	rxq->nb_rx_desc = I40E_FDIR_NUM_RX_DESC;
> +	rxq->queue_id = I40E_FDIR_QUEUE_ID;
> +	rxq->reg_idx = pf->fdir.fdir_vsi->base_queue;
> +	rxq->vsi = pf->fdir.fdir_vsi;
> +
> +#ifdef RTE_LIBRTE_XEN_DOM0
> +	rxq->rx_ring_phys_addr = rte_mem_phy2mch(rz->memseg_id,
> +rz->phys_addr); #else
> +	rxq->rx_ring_phys_addr = (uint64_t)rz->phys_addr; #endif
> +	rxq->rx_ring = (union i40e_rx_desc *)rz->addr;
> +
> +	/*
> +	 * Don't need to allocate software ring and reset for the fdir
> +	 * rx queue, just set the queue has been configured.
> +	 */
> +	rxq->q_set = TRUE;
> +	pf->fdir.rxq = rxq;
> +
> +	return I40E_SUCCESS;
> +}
> --
> 1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete flow director
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete " Jingjing Wu
@ 2014-11-05 21:18       ` De Lara Guarch, Pablo
  2014-11-13  9:50         ` Thomas Monjalon
  0 siblings, 1 reply; 123+ messages in thread
From: De Lara Guarch, Pablo @ 2014-11-05 21:18 UTC (permalink / raw)
  To: Wu, Jingjing, dev



> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, October 30, 2014 7:27 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to
> add/delete flow director
> 
> Deal with two operations for flow director
>  - RTE_ETH_FILTER_ADD
>  - RTE_ETH_FILTER_DELETE
> Encode the flow inputs to programming packet.
> Sent the packet to filter programming queue and check status
> on the status report queue.
> 
> Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
> ---
>  lib/librte_pmd_i40e/i40e_ethdev.c |   3 +
>  lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
>  lib/librte_pmd_i40e/i40e_fdir.c   | 622
> ++++++++++++++++++++++++++++++++++++++
>  3 files changed, 628 insertions(+)
> 
> diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c
> b/lib/librte_pmd_i40e/i40e_ethdev.c
> index 8195e8a..fb43efb 100644
> --- a/lib/librte_pmd_i40e/i40e_ethdev.c
> +++ b/lib/librte_pmd_i40e/i40e_ethdev.c
> @@ -4577,6 +4577,7 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
>  		     enum rte_filter_op filter_op,
>  		     void *arg)
>  {
> +	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data-
> >dev_private);
>  	int ret = 0;
> 
>  	if (dev == NULL)
> @@ -4585,6 +4586,8 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
>  	switch (filter_type) {
>  	case RTE_ETH_FILTER_TUNNEL:
>  		ret = i40e_tunnel_filter_handle(dev, filter_op, arg);

Missing break here?

> +	case RTE_ETH_FILTER_FDIR:
> +		ret = i40e_fdir_ctrl_func(pf, filter_op, arg);
>  		break;
>  	default:
>  		PMD_DRV_LOG(WARNING, "Filter type (%d) not
> supported",

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete flow director
  2014-11-05 21:18       ` De Lara Guarch, Pablo
@ 2014-11-13  9:50         ` Thomas Monjalon
  2014-11-13 11:36           ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-11-13  9:50 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

Hi Jingjing,

You didn't reply to Pablo's comment.
Any news of this patchset? Could it be reviewed?

Thanks
-- 
Thomas

2014-11-05 21:18, De Lara Guarch, Pablo:
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> > Deal with two operations for flow director
> >  - RTE_ETH_FILTER_ADD
> >  - RTE_ETH_FILTER_DELETE
> > Encode the flow inputs to programming packet.
> > Sent the packet to filter programming queue and check status
> > on the status report queue.
> > 
> > Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
> > ---
> >  lib/librte_pmd_i40e/i40e_ethdev.c |   3 +
> >  lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
> >  lib/librte_pmd_i40e/i40e_fdir.c   | 622
> > ++++++++++++++++++++++++++++++++++++++
> >  3 files changed, 628 insertions(+)
> > 
> > diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c
> > b/lib/librte_pmd_i40e/i40e_ethdev.c
> > index 8195e8a..fb43efb 100644
> > --- a/lib/librte_pmd_i40e/i40e_ethdev.c
> > +++ b/lib/librte_pmd_i40e/i40e_ethdev.c
> > @@ -4577,6 +4577,7 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
> >  		     enum rte_filter_op filter_op,
> >  		     void *arg)
> >  {
> > +	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data-
> > >dev_private);
> >  	int ret = 0;
> > 
> >  	if (dev == NULL)
> > @@ -4585,6 +4586,8 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
> >  	switch (filter_type) {
> >  	case RTE_ETH_FILTER_TUNNEL:
> >  		ret = i40e_tunnel_filter_handle(dev, filter_op, arg);
> 
> Missing break here?
> 
> > +	case RTE_ETH_FILTER_FDIR:
> > +		ret = i40e_fdir_ctrl_func(pf, filter_op, arg);
> >  		break;
> >  	default:
> >  		PMD_DRV_LOG(WARNING, "Filter type (%d) not
> > supported",

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete flow director
  2014-11-13  9:50         ` Thomas Monjalon
@ 2014-11-13 11:36           ` Wu, Jingjing
  0 siblings, 0 replies; 123+ messages in thread
From: Wu, Jingjing @ 2014-11-13 11:36 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Pablo & Thomas

You are correct. This is a merge mistake.

Besides that, there are some comments from Konstantin, I'm reworking on this patchset.

The new patchset is coming soon.

Thanks for reminder.

Jingjing

> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Thursday, November 13, 2014 5:50 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org; De Lara Guarch, Pablo
> Subject: Re: [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete flow
> director
> 
> Hi Jingjing,
> 
> You didn't reply to Pablo's comment.
> Any news of this patchset? Could it be reviewed?
> 
> Thanks
> --
> Thomas
> 
> 2014-11-05 21:18, De Lara Guarch, Pablo:
> > From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> > > Deal with two operations for flow director
> > >  - RTE_ETH_FILTER_ADD
> > >  - RTE_ETH_FILTER_DELETE
> > > Encode the flow inputs to programming packet.
> > > Sent the packet to filter programming queue and check status
> > > on the status report queue.
> > >
> > > Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
> > > ---
> > >  lib/librte_pmd_i40e/i40e_ethdev.c |   3 +
> > >  lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
> > >  lib/librte_pmd_i40e/i40e_fdir.c   | 622
> > > ++++++++++++++++++++++++++++++++++++++
> > >  3 files changed, 628 insertions(+)
> > >
> > > diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c
> > > b/lib/librte_pmd_i40e/i40e_ethdev.c
> > > index 8195e8a..fb43efb 100644
> > > --- a/lib/librte_pmd_i40e/i40e_ethdev.c
> > > +++ b/lib/librte_pmd_i40e/i40e_ethdev.c
> > > @@ -4577,6 +4577,7 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
> > >  		     enum rte_filter_op filter_op,
> > >  		     void *arg)
> > >  {
> > > +	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data-
> > > >dev_private);
> > >  	int ret = 0;
> > >
> > >  	if (dev == NULL)
> > > @@ -4585,6 +4586,8 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
> > >  	switch (filter_type) {
> > >  	case RTE_ETH_FILTER_TUNNEL:
> > >  		ret = i40e_tunnel_filter_handle(dev, filter_op, arg);
> >
> > Missing break here?
> >
> > > +	case RTE_ETH_FILTER_FDIR:
> > > +		ret = i40e_fdir_ctrl_func(pf, filter_op, arg);
> > >  		break;
> > >  	default:
> > >  		PMD_DRV_LOG(WARNING, "Filter type (%d) not
> > > supported",

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville
  2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
                     ` (24 preceding siblings ...)
  2014-10-30  7:34   ` [dpdk-dev] [PATCH v4 00/21] " Cao, Min
@ 2014-11-19  7:53   ` Cao, Min
  25 siblings, 0 replies; 123+ messages in thread
From: Cao, Min @ 2014-11-19  7:53 UTC (permalink / raw)
  To: Wu, Jingjing, dev

Tested-by: Min Cao <min.cao@intel.com>

Patch name: 		[PATCH v4 00/21] Support flow director programming on Fortville
Test Flag: 			Tested-by
Tester name: 		min.cao@intel.com
Result summary:		total 3 cases, 3 passed, 0 failed

Test Case 1:		
Name:				Fortville flow director with no flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 2:		
Name:				Fortville flow director with flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 3:		
Name:				Fortville flow director flush
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 4:		
Name:				Fortville flow director performance
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

-----Original Message-----
From: Wu, Jingjing 
Sent: Wednesday, October 22, 2014 9:01 AM
To: dev@dpdk.org
Cc: Wu, Jingjing; Cao, Min
Subject: [PATCH v4 00/21] Support flow director programming on Fortville

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics, FD_ID report.
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison and flex bytes report.

v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 changes:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison 
 
v4 changes:
 - strip the filter APIs definitions from this patch set
 - extend mbuf field to support flex bytes report
 - fix typos

Jingjing Wu (21):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  ethdev: define structures for adding/deleting flow director
  i40e: implement operations to add/delete flow director
  testpmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  mbuf: extend fdir field
  i40e: report flow director match info to mbuf
  testpmd: print extended fdir info in mbuf
  ethdev: define structures for getting flow director information
  i40e: implement operations to get fdir info
  testpmd: display fdir statistics
  i40e: implement operation to flush flow director table
  testpmd: add test command to flush flow director table
  ethdev: define structures for configuring flexible payload
  i40e: implement operations to configure flexible payload
  testpmd: add test command to configure flexible payload
  ethdev:  define structures for configuring flex masks
  i40e: implement operations to configure flexible masks
  testpmd: add test command to configure flexible masks

 app/test-pmd/cmdline.c            |  812 ++++++++++++++++++++++++
 app/test-pmd/config.c             |   38 +-
 app/test-pmd/rxonly.c             |   14 +-
 app/test-pmd/testpmd.h            |    3 +
 lib/librte_ether/rte_eth_ctrl.h   |  266 ++++++++
 lib/librte_ether/rte_ethdev.h     |   23 -
 lib/librte_mbuf/rte_mbuf.h        |   12 +-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  127 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   34 +-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1222 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  225 ++++++-
 12 files changed, 2723 insertions(+), 55 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v5 02/21] i40e: tear down flow director
  2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 02/21] i40e: tear down " Jingjing Wu
@ 2014-11-19  7:53       ` Cao, Min
  0 siblings, 0 replies; 123+ messages in thread
From: Cao, Min @ 2014-11-19  7:53 UTC (permalink / raw)
  To: Wu, Jingjing, dev

Tested-by: Min Cao <min.cao@intel.com>

Patch name: 		[PATCH v5 00/21] Support flow director programming on Fortville
Test Flag: 			Tested-by
Tester name: 		min.cao@intel.com
Result summary:		total 3 cases, 3 passed, 0 failed

Test Case 1:		
Name:				Fortville flow director with no flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 2:		
Name:				Fortville flow director with flexible playload(IPv4/IPv6)
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 3:		
Name:				Fortville flow director flush
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

Test Case 4:		
Name:				Fortville flow director performance
Environment:		OS: Fedora20 3.11.10-301.fc20.x86_64
				gcc (GCC) 4.8.2
				CPU: Intel(R) Xeon(R) CPU E5-2680 0 @ 2.70GHz
				NIC: Fortville eagle/spirit 
Test result:		PASSED

-----Original Message-----
From: Wu, Jingjing 
Sent: Thursday, October 30, 2014 3:26 PM
To: dev@dpdk.org
Cc: Wu, Jingjing; Cao, Min
Subject: [PATCH v5 02/21] i40e: tear down flow director

To support flow director tear down, this patch includes
 - queue 0 pair release
 - release vsi

Signed-off-by: Jingjing Wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  4 +++-
 lib/librte_pmd_i40e/i40e_ethdev.h |  1 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 19 +++++++++++++++++++
 3 files changed, 23 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index cea7725..812c91d 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -514,7 +514,8 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 	return 0;
 
 err_setup_pf_switch:
-	rte_free(pf->main_vsi);
+	i40e_fdir_teardown(pf);
+	i40e_vsi_release(pf->main_vsi);
 err_get_mac_addr:
 err_configure_lan_hmc:
 	(void)i40e_shutdown_lan_hmc(hw);
@@ -849,6 +850,7 @@ i40e_dev_close(struct rte_eth_dev *dev)
 	i40e_shutdown_lan_hmc(hw);
 
 	/* release all the existing VSIs and VEBs */
+	i40e_fdir_teardown(pf);
 	i40e_vsi_release(pf->main_vsi);
 
 	/* shutdown the adminq */
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 6d30f75..35fcc46 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -379,6 +379,7 @@ enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf,
 enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf,
 				    unsigned int socket_id);
 int i40e_fdir_setup(struct i40e_pf *pf);
+void i40e_fdir_teardown(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index a44bb73..bb474d2 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -219,4 +219,23 @@ fail_setup_tx:
 	i40e_vsi_release(vsi);
 	pf->fdir.fdir_vsi = NULL;
 	return err;
+}
+
+/*
+ * i40e_fdir_teardown - release the Flow Director resources
+ * @pf: board private structure
+ */
+void
+i40e_fdir_teardown(struct i40e_pf *pf)
+{
+	struct i40e_vsi *vsi;
+
+	vsi = pf->fdir.fdir_vsi;
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return;
 }
\ No newline at end of file
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville
  2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
                       ` (21 preceding siblings ...)
  2014-10-30  8:07     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
@ 2014-11-21  0:46     ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 01/22] i40e: set up and initialize flow director Jingjing Wu
                         ` (22 more replies)
  22 siblings, 23 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

The patch set supports flow director on fortville.
It includes:
 - set up/tear down fortville resources to support flow director, such as queue and vsi.
 - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6, sctpv6.
 - support flushing flow director table (all filters).
 - support operation to get flow director information.
 - match status statistics, FD_ID report.
 - support operation to configure flexible payload and its mask
 - support flexible payload involved in comparison and flex bytes report.
 
v2 changes:
 - create real fdir vsi and assign queue 0 pair to it.
 - check filter status report on the rx queue 0
 
v3 changes:
 - redefine filter APIs to support multi-kind filters
 - support sctpv4 and sctpv6 type flows
 - support flexible payload involved in comparison
 
v4 changes:
 - strip the filter APIs definitions from this patch set
 - extend mbuf field to support flex bytes report.
 - fix typos.
 
v5 changes:
 - redefine structure rte_eth_fdir_info
 - add doxygen comments about flexible payload and mbuf extend
 - fix typos

v6 changes:
 - extend structure rte_eth_fdir_info
 - move the flex payload and mask setting from filter_ctrl api
   to i40e_fdir_configure when start device
 - change the structure for flex payload and mask setting, and
   add verification of those arguments before HW setting is taken.
 - change flexpayloads from words to bytes format
 - add two more flow_types
 - organize duplicate code lines to macro or function
 - add and correct doxygen comments
 - fix the merging error in v5

Jingjing Wu (22):
  i40e: set up and initialize flow director
  i40e: tear down flow director
  i40e: initialize flexible payload setting
  ethdev: define structures for adding/deleting flow director
  i40e: define functions for transition between flow_type and pctype
  i40e: implement operations to add/delete flow director
  testpmd: add test commands to add/delete flow director filter
  i40e: match counter for flow director
  mbuf: extend fdir field
  i40e: report flow director match info to mbuf
  testpmd: print extended fdir info in mbuf
  i40e: implement operation to flush flow director table
  testpmd: add test command to flush flow director table
  ethdev: define structures for getting flow director information
  i40e: implement operations to get fdir info
  ethdev: define structures for getting flow director statistics
  i40e: implement operations to get fdir statistics
  testpmd: display fdir info
  ethdev: add flexible payload setting in eth_conf
  i40e: take flow director flexible payload configuration
  testpmd: add test command to configure flexible mask
  testpmd: add test command to configure flexible payload

 app/test-pmd/cmdline.c            |  644 ++++++++++++++++++
 app/test-pmd/config.c             |  202 +++++-
 app/test-pmd/rxonly.c             |   14 +-
 app/test-pmd/testpmd.h            |    5 +-
 lib/librte_ether/rte_eth_ctrl.h   |  279 +++++++-
 lib/librte_ether/rte_ethdev.h     |   11 +-
 lib/librte_mbuf/rte_mbuf.h        |   17 +-
 lib/librte_pmd_i40e/Makefile      |    2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  175 ++++-
 lib/librte_pmd_i40e/i40e_ethdev.h |   93 ++-
 lib/librte_pmd_i40e/i40e_fdir.c   | 1362 +++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   |  207 +++++-
 12 files changed, 2965 insertions(+), 46 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 01/22] i40e: set up and initialize flow director
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 02/22] i40e: tear down " Jingjing Wu
                         ` (21 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

set up fortville resources to support flow director, includes
 - queue 0 pair allocated and set up for flow director
 - create vsi
 - reserve memzone for flow director programming packet

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/Makefile      |   2 +
 lib/librte_pmd_i40e/i40e_ethdev.c |  78 +++++++--
 lib/librte_pmd_i40e/i40e_ethdev.h |  25 ++-
 lib/librte_pmd_i40e/i40e_fdir.c   | 324 ++++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_rxtx.c   | 144 +++++++++++++++++
 5 files changed, 562 insertions(+), 11 deletions(-)
 create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c

diff --git a/lib/librte_pmd_i40e/Makefile b/lib/librte_pmd_i40e/Makefile
index bd3428f..98e4bdf 100644
--- a/lib/librte_pmd_i40e/Makefile
+++ b/lib/librte_pmd_i40e/Makefile
@@ -91,6 +91,8 @@ SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_rxtx.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_ethdev_vf.c
 SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_pf.c
+SRCS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += i40e_fdir.c
+
 # this lib depends upon:
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_eal lib/librte_ether
 DEPDIRS-$(CONFIG_RTE_LIBRTE_I40E_PMD) += lib/librte_mempool lib/librte_mbuf
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 5074262..46115c7 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -811,6 +811,18 @@ i40e_dev_start(struct rte_eth_dev *dev)
 		i40e_vsi_enable_queues_intr(pf->vmdq[i].vsi);
 	}
 
+	ret = i40e_fdir_configure(dev);
+	if (ret < 0) {
+		PMD_DRV_LOG(ERR, "failed to configure fdir.");
+		goto err_up;
+	}
+
+	/* enable FDIR MSIX interrupt */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
+		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
+	}
+
 	/* Enable all queues which have been configured */
 	ret = i40e_dev_switch_queues(pf, TRUE);
 	if (ret != I40E_SUCCESS) {
@@ -2818,16 +2830,30 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	case I40E_VSI_VMDQ2:
 		vsi->nb_qps = pf->vmdq_nb_qps;
 		break;
+	case I40E_VSI_FDIR:
+		vsi->nb_qps = pf->fdir_nb_qps;
+		break;
 	default:
 		goto fail_mem;
 	}
-	ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
-	if (ret < 0) {
-		PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
-				vsi->seid, ret);
-		goto fail_mem;
-	}
-	vsi->base_queue = ret;
+	/*
+	 * The filter status descriptor is reported in rx queue 0,
+	 * while the tx queue for fdir filter programming has no
+	 * such constraints, can be non-zero queues.
+	 * To simplify it, choose FDIR vsi use queue 0 pair.
+	 * To make sure it will use queue 0 pair, queue allocation
+	 * need be done before this function is called
+	 */
+	if (type != I40E_VSI_FDIR) {
+		ret = i40e_res_pool_alloc(&pf->qp_pool, vsi->nb_qps);
+			if (ret < 0) {
+				PMD_DRV_LOG(ERR, "VSI %d allocate queue failed %d",
+						vsi->seid, ret);
+				goto fail_mem;
+			}
+			vsi->base_queue = ret;
+	} else
+		vsi->base_queue = I40E_FDIR_QUEUE_ID;
 
 	/* VF has MSIX interrupt in VF range, don't allocate here */
 	if (type != I40E_VSI_SRIOV) {
@@ -2996,6 +3022,23 @@ i40e_vsi_setup(struct i40e_pf *pf,
 		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
 		ctxt.info.valid_sections |=
 			rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
+	} else if (type == I40E_VSI_FDIR) {
+		vsi->uplink_seid = uplink_vsi->uplink_seid;
+		ctxt.pf_num = hw->pf_id;
+		ctxt.vf_num = 0;
+		ctxt.uplink_seid = vsi->uplink_seid;
+		ctxt.connection_type = 0x1;     /* regular data port */
+		ctxt.flags = I40E_AQ_VSI_TYPE_PF;
+		ret = i40e_vsi_config_tc_queue_mapping(vsi, &ctxt.info,
+						I40E_DEFAULT_TCMAP);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to configure "
+					"TC queue mapping.");
+			goto fail_msix_alloc;
+		}
+		ctxt.info.up_enable_bits = I40E_DEFAULT_TCMAP;
+		ctxt.info.valid_sections |=
+			rte_cpu_to_le_16(I40E_AQ_VSI_PROP_SCHED_VALID);
 	} else {
 		PMD_DRV_LOG(ERR, "VSI: Not support other type VSI yet");
 		goto fail_msix_alloc;
@@ -3184,8 +3227,16 @@ i40e_pf_setup(struct i40e_pf *pf)
 		PMD_DRV_LOG(ERR, "Could not get switch config, err %d", ret);
 		return ret;
 	}
-
-	/* VSI setup */
+	if (pf->flags & I40E_FLAG_FDIR) {
+		/* make queue allocated first, let FDIR use queue pair 0*/
+		ret = i40e_res_pool_alloc(&pf->qp_pool, I40E_DEFAULT_QP_NUM_FDIR);
+		if (ret != I40E_FDIR_QUEUE_ID) {
+			PMD_DRV_LOG(ERR, "queue allocation fails for FDIR :"
+				    " ret =%d", ret);
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+	/*  main VSI setup */
 	vsi = i40e_vsi_setup(pf, I40E_VSI_MAIN, NULL, 0);
 	if (!vsi) {
 		PMD_DRV_LOG(ERR, "Setup of main vsi failed");
@@ -3193,6 +3244,15 @@ i40e_pf_setup(struct i40e_pf *pf)
 	}
 	pf->main_vsi = vsi;
 
+	/* setup FDIR after main vsi created.*/
+	if (pf->flags & I40E_FLAG_FDIR) {
+		ret = i40e_fdir_setup(pf);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to setup flow director.");
+			pf->flags &= ~I40E_FLAG_FDIR;
+		}
+	}
+
 	/* Configure filter control */
 	memset(&settings, 0, sizeof(settings));
 	settings.hash_lut_size = I40E_HASH_LUT_SIZE_128;
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 96361c2..e9c714c 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -47,11 +47,12 @@
 #define I40E_QUEUE_BASE_ADDR_UNIT 128
 /* number of VSIs and queue default setting */
 #define I40E_MAX_QP_NUM_PER_VF    16
-#define I40E_DEFAULT_QP_NUM_FDIR  64
+#define I40E_DEFAULT_QP_NUM_FDIR  1
 #define I40E_UINT32_BIT_SIZE      (CHAR_BIT * sizeof(uint32_t))
 #define I40E_VFTA_SIZE            (4096 / I40E_UINT32_BIT_SIZE)
 /* Default TC traffic in case DCB is not enabled */
 #define I40E_DEFAULT_TCMAP        0x1
+#define I40E_FDIR_QUEUE_ID        0
 
 /* Always assign pool 0 to main VSI, VMDQ will start from 1 */
 #define I40E_VMDQ_POOL_BASE       1
@@ -243,6 +244,18 @@ struct i40e_vmdq_info {
 };
 
 /*
+ *  A structure used to define fields of a FDIR related info.
+ */
+struct i40e_fdir_info {
+	struct i40e_vsi *fdir_vsi;     /* pointer to fdir VSI structure */
+	uint16_t match_counter_index;  /* Statistic counter index used for fdir*/
+	struct i40e_tx_queue *txq;
+	struct i40e_rx_queue *rxq;
+	void *prg_pkt;                 /* memory for fdir program packet */
+	uint64_t dma_addr;             /* physic address of packet memory*/
+};
+
+/*
  * Structure to store private data specific for PF instance.
  */
 struct i40e_pf {
@@ -270,7 +283,6 @@ struct i40e_pf {
 	uint16_t vmdq_nb_qps; /* The number of queue pairs of VMDq */
 	uint16_t vf_nb_qps; /* The number of queue pairs of VF */
 	uint16_t fdir_nb_qps; /* The number of queue pairs of Flow Director */
-
 	/* store VXLAN UDP ports */
 	uint16_t vxlan_ports[I40E_MAX_PF_UDP_OFFLOAD_PORTS];
 	uint16_t vxlan_bitmap; /* Vxlan bit mask */
@@ -279,6 +291,8 @@ struct i40e_pf {
 	uint16_t max_nb_vmdq_vsi; /* Max number of VMDQ VSIs supported */
 	uint16_t nb_cfg_vmdq_vsi; /* number of VMDQ VSIs configured */
 	struct i40e_vmdq_info *vmdq;
+
+	struct i40e_fdir_info fdir; /* flow director info */
 };
 
 enum pending_msg {
@@ -380,6 +394,13 @@ int i40e_vsi_vlan_pvid_set(struct i40e_vsi *vsi,
 int i40e_vsi_config_vlan_stripping(struct i40e_vsi *vsi, bool on);
 uint64_t i40e_config_hena(uint64_t flags);
 uint64_t i40e_parse_hena(uint64_t flags);
+enum i40e_status_code i40e_fdir_setup_tx_resources(struct i40e_pf *pf);
+enum i40e_status_code i40e_fdir_setup_rx_resources(struct i40e_pf *pf);
+int i40e_fdir_setup(struct i40e_pf *pf);
+const struct rte_memzone *i40e_memzone_reserve(const char *name,
+					uint32_t len,
+					int socket_id);
+int i40e_fdir_configure(struct rte_eth_dev *dev);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
new file mode 100644
index 0000000..7708887
--- /dev/null
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -0,0 +1,324 @@
+/*-
+ *   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 <sys/queue.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdint.h>
+#include <string.h>
+#include <unistd.h>
+#include <stdarg.h>
+
+#include <rte_ether.h>
+#include <rte_ethdev.h>
+#include <rte_log.h>
+#include <rte_memzone.h>
+#include <rte_malloc.h>
+
+#include "i40e_logs.h"
+#include "i40e/i40e_type.h"
+#include "i40e_ethdev.h"
+#include "i40e_rxtx.h"
+
+#define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
+#define I40E_FDIR_PKT_LEN                   512
+
+
+/* Wait count and interval for fdir filter flush */
+#define I40E_FDIR_FLUSH_RETRY       50
+#define I40E_FDIR_FLUSH_INTERVAL_MS 5
+
+#define I40E_COUNTER_PF           2
+/* Statistic counter index for one pf */
+#define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+#define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
+
+static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_fdir_flush(struct rte_eth_dev *dev);
+
+static int
+i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
+{
+	struct i40e_hw *hw = I40E_VSI_TO_HW(rxq->vsi);
+	struct i40e_hmc_obj_rxq rx_ctx;
+	int err = I40E_SUCCESS;
+
+	memset(&rx_ctx, 0, sizeof(struct i40e_hmc_obj_rxq));
+	/* Init the RX queue in hardware */
+	rx_ctx.dbuff = I40E_RXBUF_SZ_1024 >> I40E_RXQ_CTX_DBUFF_SHIFT;
+	rx_ctx.hbuff = 0;
+	rx_ctx.base = rxq->rx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
+	rx_ctx.qlen = rxq->nb_rx_desc;
+#ifndef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+	rx_ctx.dsize = 1;
+#endif
+	rx_ctx.dtype = i40e_header_split_none;
+	rx_ctx.hsplit_0 = I40E_HEADER_SPLIT_NONE;
+	rx_ctx.rxmax = ETHER_MAX_LEN;
+	rx_ctx.tphrdesc_ena = 1;
+	rx_ctx.tphwdesc_ena = 1;
+	rx_ctx.tphdata_ena = 1;
+	rx_ctx.tphhead_ena = 1;
+	rx_ctx.lrxqthresh = 2;
+	rx_ctx.crcstrip = 0;
+	rx_ctx.l2tsel = 1;
+	rx_ctx.showiv = 1;
+	rx_ctx.prefena = 1;
+
+	err = i40e_clear_lan_rx_queue_context(hw, rxq->reg_idx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to clear FDIR RX queue context.");
+		return err;
+	}
+	err = i40e_set_lan_rx_queue_context(hw, rxq->reg_idx, &rx_ctx);
+	if (err != I40E_SUCCESS) {
+		PMD_DRV_LOG(ERR, "Failed to set FDIR RX queue context.");
+		return err;
+	}
+	rxq->qrx_tail = hw->hw_addr +
+		I40E_QRX_TAIL(rxq->vsi->base_queue);
+
+	rte_wmb();
+	/* Init the RX tail regieter. */
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, 0);
+	I40E_PCI_REG_WRITE(rxq->qrx_tail, rxq->nb_rx_desc - 1);
+
+	return err;
+}
+
+/*
+ * i40e_fdir_setup - reserve and initialize the Flow Director resources
+ * @pf: board private structure
+ */
+int
+i40e_fdir_setup(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_vsi *vsi;
+	int err = I40E_SUCCESS;
+	char z_name[RTE_MEMZONE_NAMESIZE];
+	const struct rte_memzone *mz = NULL;
+	struct rte_eth_dev *eth_dev = pf->adapter->eth_dev;
+
+	PMD_DRV_LOG(INFO, "FDIR HW Capabilities: num_filters_guaranteed = %u,"
+			" num_filters_best_effort = %u.",
+			hw->func_caps.fd_filters_guaranteed,
+			hw->func_caps.fd_filters_best_effort);
+
+	vsi = pf->fdir.fdir_vsi;
+	if (vsi) {
+		PMD_DRV_LOG(ERR, "FDIR vsi pointer needs"
+				 "to be null before creation.");
+		return I40E_ERR_BAD_PTR;
+	}
+	/* make new FDIR VSI */
+	vsi = i40e_vsi_setup(pf, I40E_VSI_FDIR, pf->main_vsi, 0);
+	if (!vsi) {
+		PMD_DRV_LOG(ERR, "Couldn't create FDIR VSI.");
+		return I40E_ERR_NO_AVAILABLE_VSI;
+	}
+	pf->fdir.fdir_vsi = vsi;
+
+	/*Fdir tx queue setup*/
+	err = i40e_fdir_setup_tx_resources(pf);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR TX resources.");
+		goto fail_setup_tx;
+	}
+
+	/*Fdir rx queue setup*/
+	err = i40e_fdir_setup_rx_resources(pf);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to setup FDIR RX resources.");
+		goto fail_setup_rx;
+	}
+
+	err = i40e_tx_queue_init(pf->fdir.txq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR TX initialization.");
+		goto fail_mem;
+	}
+
+	/* need switch on before dev start*/
+	err = i40e_switch_tx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do fdir TX switch on.");
+		goto fail_mem;
+	}
+
+	/* Init the rx queue in hardware */
+	err = i40e_fdir_rx_queue_init(pf->fdir.rxq);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX initialization.");
+		goto fail_mem;
+	}
+
+	/* switch on rx queue */
+	err = i40e_switch_rx_queue(hw, vsi->base_queue, TRUE);
+	if (err) {
+		PMD_DRV_LOG(ERR, "Failed to do FDIR RX switch on.");
+		goto fail_mem;
+	}
+
+	/* reserve memory for the fdir programming packet */
+	snprintf(z_name, sizeof(z_name), "%s_%s_%d",
+			eth_dev->driver->pci_drv.name,
+			I40E_FDIR_MZ_NAME,
+			eth_dev->data->port_id);
+	mz = i40e_memzone_reserve(z_name, I40E_FDIR_PKT_LEN, SOCKET_ID_ANY);
+	if (!mz) {
+		PMD_DRV_LOG(ERR, "Cannot init memzone for"
+				 "flow director program packet.");
+		err = I40E_ERR_NO_MEMORY;
+		goto fail_mem;
+	}
+	pf->fdir.prg_pkt = mz->addr;
+#ifdef RTE_LIBRTE_XEN_DOM0
+	pf->fdir.dma_addr = rte_mem_phy2mch(mz->memseg_id, mz->phys_addr);
+#else
+	pf->fdir.dma_addr = (uint64_t)mz->phys_addr;
+#endif
+	pf->fdir.match_counter_index = I40E_COUNTER_INDEX_FDIR(hw->pf_id);
+	PMD_DRV_LOG(INFO, "FDIR setup successfully, with programming queue %u.",
+		    vsi->base_queue);
+	return I40E_SUCCESS;
+
+fail_mem:
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+fail_setup_rx:
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+fail_setup_tx:
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+	return err;
+}
+
+/* check whether the flow director table in empty */
+static inline int
+i40e_fdir_empty(struct i40e_hw *hw)
+{
+	uint32_t guarant_cnt, best_cnt;
+
+	guarant_cnt = (uint32_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				 I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+				 I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	best_cnt = (uint32_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+			      I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+			      I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	if (best_cnt + guarant_cnt > 0)
+		return -1;
+
+	return 0;
+}
+
+/*
+ * Configure flow director related setting
+ */
+int
+i40e_fdir_configure(struct rte_eth_dev *dev)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	struct i40e_hw *hw = I40E_DEV_PRIVATE_TO_HW(dev->data->dev_private);
+	uint32_t val;
+	int ret = 0;
+
+	/*
+	* configuration need to be done before
+	* flow director filters are added
+	* If filters exist, flush them.
+	*/
+	if (i40e_fdir_empty(hw) < 0) {
+		ret = i40e_fdir_flush(dev);
+		if (ret) {
+			PMD_DRV_LOG(ERR, "failed to flush fdir table.");
+			return ret;
+		}
+	}
+
+	val = I40E_READ_REG(hw, I40E_PFQF_CTL_0);
+	if ((pf->flags & I40E_FLAG_FDIR) &&
+		dev->data->dev_conf.fdir_conf.mode == RTE_FDIR_MODE_PERFECT) {
+		/* enable FDIR filter */
+		val |= I40E_PFQF_CTL_0_FD_ENA_MASK;
+		I40E_WRITE_REG(hw, I40E_PFQF_CTL_0, val);
+	} else {
+		/* disable FDIR filter */
+		val &= ~I40E_PFQF_CTL_0_FD_ENA_MASK;
+		I40E_WRITE_REG(hw, I40E_PFQF_CTL_0, val);
+		pf->flags &= ~I40E_FLAG_FDIR;
+	}
+
+	return ret;
+}
+
+/*
+ * i40e_fdir_flush - clear all filters of Flow Director table
+ * @pf: board private structure
+ */
+static int
+i40e_fdir_flush(struct rte_eth_dev *dev)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t reg;
+	uint16_t guarant_cnt, best_cnt;
+	int i;
+
+	I40E_WRITE_REG(hw, I40E_PFQF_CTL_1, I40E_PFQF_CTL_1_CLEARFDTABLE_MASK);
+	I40E_WRITE_FLUSH(hw);
+
+	for (i = 0; i < I40E_FDIR_FLUSH_RETRY; i++) {
+		rte_delay_ms(I40E_FDIR_FLUSH_INTERVAL_MS);
+		reg = I40E_READ_REG(hw, I40E_PFQF_CTL_1);
+		if (!(reg & I40E_PFQF_CTL_1_CLEARFDTABLE_MASK))
+			break;
+	}
+	if (i >= I40E_FDIR_FLUSH_RETRY) {
+		PMD_DRV_LOG(ERR, "FD table did not flush, may need more time.");
+		return -ETIMEDOUT;
+	}
+	guarant_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	best_cnt = (uint16_t)((I40E_READ_REG(hw, I40E_PFQF_FDSTAT) &
+				I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+				I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+	if (guarant_cnt != 0 || best_cnt != 0) {
+		PMD_DRV_LOG(ERR, "Failed to flush FD table.");
+		return -ENOSYS;
+	} else
+		PMD_DRV_LOG(INFO, "FD table Flush success.");
+	return 0;
+}
diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 487591d..1c5cfd6 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -2098,6 +2098,24 @@ i40e_ring_dma_zone_reserve(struct rte_eth_dev *dev,
 #endif
 }
 
+const struct rte_memzone *
+i40e_memzone_reserve(const char *name, uint32_t len, int socket_id)
+{
+	const struct rte_memzone *mz = NULL;
+
+	mz = rte_memzone_lookup(name);
+	if (mz)
+		return mz;
+#ifdef RTE_LIBRTE_XEN_DOM0
+	mz = rte_memzone_reserve_bounded(name, len,
+		socket_id, 0, I40E_ALIGN, RTE_PGSIZE_2M);
+#else
+	mz = rte_memzone_reserve_aligned(name, len,
+				socket_id, 0, I40E_ALIGN);
+#endif
+	return mz;
+}
+
 void
 i40e_rx_queue_release_mbufs(struct i40e_rx_queue *rxq)
 {
@@ -2231,6 +2249,8 @@ i40e_tx_queue_init(struct i40e_tx_queue *txq)
 	tx_ctx.base = txq->tx_ring_phys_addr / I40E_QUEUE_BASE_ADDR_UNIT;
 	tx_ctx.qlen = txq->nb_tx_desc;
 	tx_ctx.rdylist = rte_le_to_cpu_16(vsi->info.qs_handle[0]);
+	if (vsi->type == I40E_VSI_FDIR)
+		tx_ctx.fd_ena = TRUE;
 
 	err = i40e_clear_lan_tx_queue_context(hw, pf_q);
 	if (err != I40E_SUCCESS) {
@@ -2447,3 +2467,127 @@ i40e_dev_clear_queues(struct rte_eth_dev *dev)
 		i40e_reset_rx_queue(dev->data->rx_queues[i]);
 	}
 }
+
+#define I40E_FDIR_NUM_TX_DESC  I40E_MIN_RING_DESC
+#define I40E_FDIR_NUM_RX_DESC  I40E_MIN_RING_DESC
+
+enum i40e_status_code
+i40e_fdir_setup_tx_resources(struct i40e_pf *pf)
+{
+	struct i40e_tx_queue *txq;
+	const struct rte_memzone *tz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the TX queue data structure. */
+	txq = rte_zmalloc_socket("i40e fdir tx queue",
+				  sizeof(struct i40e_tx_queue),
+				  CACHE_LINE_SIZE,
+				  SOCKET_ID_ANY);
+	if (!txq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"tx queue structure.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate TX hardware ring descriptors. */
+	ring_size = sizeof(struct i40e_tx_desc) * I40E_FDIR_NUM_TX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	tz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_tx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					SOCKET_ID_ANY);
+	if (!tz) {
+		i40e_dev_tx_queue_release(txq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for TX.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	txq->nb_tx_desc = I40E_FDIR_NUM_TX_DESC;
+	txq->queue_id = I40E_FDIR_QUEUE_ID;
+	txq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	txq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	txq->tx_ring_phys_addr = rte_mem_phy2mch(tz->memseg_id, tz->phys_addr);
+#else
+	txq->tx_ring_phys_addr = (uint64_t)tz->phys_addr;
+#endif
+	txq->tx_ring = (struct i40e_tx_desc *)tz->addr;
+	/*
+	 * don't need to allocate software ring and reset for the fdir
+	 * program queue just set the queue has been configured.
+	 */
+	txq->q_set = TRUE;
+	pf->fdir.txq = txq;
+
+	return I40E_SUCCESS;
+}
+
+enum i40e_status_code
+i40e_fdir_setup_rx_resources(struct i40e_pf *pf)
+{
+	struct i40e_rx_queue *rxq;
+	const struct rte_memzone *rz = NULL;
+	uint32_t ring_size;
+	struct rte_eth_dev *dev = pf->adapter->eth_dev;
+
+	if (!pf) {
+		PMD_DRV_LOG(ERR, "PF is not available");
+		return I40E_ERR_BAD_PTR;
+	}
+
+	/* Allocate the RX queue data structure. */
+	rxq = rte_zmalloc_socket("i40e fdir rx queue",
+				  sizeof(struct i40e_rx_queue),
+				  CACHE_LINE_SIZE,
+				  SOCKET_ID_ANY);
+	if (!rxq) {
+		PMD_DRV_LOG(ERR, "Failed to allocate memory for "
+					"rx queue structure.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	/* Allocate RX hardware ring descriptors. */
+	ring_size = sizeof(union i40e_rx_desc) * I40E_FDIR_NUM_RX_DESC;
+	ring_size = RTE_ALIGN(ring_size, I40E_DMA_MEM_ALIGN);
+
+	rz = i40e_ring_dma_zone_reserve(dev,
+					"fdir_rx_ring",
+					I40E_FDIR_QUEUE_ID,
+					ring_size,
+					SOCKET_ID_ANY);
+	if (!rz) {
+		i40e_dev_rx_queue_release(rxq);
+		PMD_DRV_LOG(ERR, "Failed to reserve DMA memory for RX.");
+		return I40E_ERR_NO_MEMORY;
+	}
+
+	rxq->nb_rx_desc = I40E_FDIR_NUM_RX_DESC;
+	rxq->queue_id = I40E_FDIR_QUEUE_ID;
+	rxq->reg_idx = pf->fdir.fdir_vsi->base_queue;
+	rxq->vsi = pf->fdir.fdir_vsi;
+
+#ifdef RTE_LIBRTE_XEN_DOM0
+	rxq->rx_ring_phys_addr = rte_mem_phy2mch(rz->memseg_id, rz->phys_addr);
+#else
+	rxq->rx_ring_phys_addr = (uint64_t)rz->phys_addr;
+#endif
+	rxq->rx_ring = (union i40e_rx_desc *)rz->addr;
+
+	/*
+	 * Don't need to allocate software ring and reset for the fdir
+	 * rx queue, just set the queue has been configured.
+	 */
+	rxq->q_set = TRUE;
+	pf->fdir.rxq = rxq;
+
+	return I40E_SUCCESS;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 02/22] i40e: tear down flow director
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 01/22] i40e: set up and initialize flow director Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 03/22] i40e: initialize flexible payload setting Jingjing Wu
                         ` (20 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

release fortville resources on flow director, includes
 - queue 0 pair release
 - release vsi

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  7 +++++++
 lib/librte_pmd_i40e/i40e_ethdev.h |  1 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 21 +++++++++++++++++++++
 3 files changed, 29 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 46115c7..ac68540 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -521,6 +521,7 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 err_mac_alloc:
 	i40e_vsi_release(pf->main_vsi);
 err_setup_pf_switch:
+	i40e_fdir_teardown(pf);
 err_get_mac_addr:
 err_configure_lan_hmc:
 	(void)i40e_shutdown_lan_hmc(hw);
@@ -877,11 +878,16 @@ i40e_dev_stop(struct rte_eth_dev *dev)
 		i40e_vsi_queues_unbind_intr(pf->vmdq[i].vsi);
 	}
 
+	if (pf->flags & I40E_FLAG_FDIR) {
+		i40e_vsi_queues_bind_intr(pf->fdir.fdir_vsi);
+		i40e_vsi_enable_queues_intr(pf->fdir.fdir_vsi);
+	}
 	/* Clear all queues and release memory */
 	i40e_dev_clear_queues(dev);
 
 	/* Set link down */
 	i40e_dev_set_link_down(dev);
+
 }
 
 static void
@@ -903,6 +909,7 @@ i40e_dev_close(struct rte_eth_dev *dev)
 	i40e_shutdown_lan_hmc(hw);
 
 	/* release all the existing VSIs and VEBs */
+	i40e_fdir_teardown(pf);
 	i40e_vsi_release(pf->main_vsi);
 
 	/* shutdown the adminq */
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index e9c714c..7ad6501 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -401,6 +401,7 @@ const struct rte_memzone *i40e_memzone_reserve(const char *name,
 					uint32_t len,
 					int socket_id);
 int i40e_fdir_configure(struct rte_eth_dev *dev);
+void i40e_fdir_teardown(struct i40e_pf *pf);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 7708887..9b678ce 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -225,6 +225,27 @@ fail_setup_tx:
 	return err;
 }
 
+/*
+ * i40e_fdir_teardown - release the Flow Director resources
+ * @pf: board private structure
+ */
+void
+i40e_fdir_teardown(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_vsi *vsi;
+
+	vsi = pf->fdir.fdir_vsi;
+	i40e_switch_tx_queue(hw, vsi->base_queue, FALSE);
+	i40e_switch_rx_queue(hw, vsi->base_queue, FALSE);
+	i40e_dev_rx_queue_release(pf->fdir.rxq);
+	pf->fdir.rxq = NULL;
+	i40e_dev_tx_queue_release(pf->fdir.txq);
+	pf->fdir.txq = NULL;
+	i40e_vsi_release(vsi);
+	pf->fdir.fdir_vsi = NULL;
+}
+
 /* check whether the flow director table in empty */
 static inline int
 i40e_fdir_empty(struct i40e_hw *hw)
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 03/22] i40e: initialize flexible payload setting
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 01/22] i40e: set up and initialize flow director Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 02/22] i40e: tear down " Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 04/22] ethdev: define structures for adding/deleting flow director Jingjing Wu
                         ` (19 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

set flexible payload related registers to default value at initialization time.

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 36 ++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_ethdev.h | 35 +++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_fdir.c   | 43 +++++++++++++++++++++++++++++++++++++++
 3 files changed, 114 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index ac68540..e57b9b4 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -333,6 +333,35 @@ static struct rte_driver rte_i40e_driver = {
 
 PMD_REGISTER_DRIVER(rte_i40e_driver);
 
+/*
+ * Initialize registers for flexible payload, which should be set by NVM.
+ * This should be removed from code once it is fixed in NVM.
+ */
+#ifndef I40E_GLQF_ORT
+#define I40E_GLQF_ORT(_i)    (0x00268900 + ((_i) * 4))
+#endif
+#ifndef I40E_GLQF_PIT
+#define I40E_GLQF_PIT(_i)    (0x00268C80 + ((_i) * 4))
+#endif
+
+static inline void i40e_flex_payload_reg_init(struct i40e_hw *hw)
+{
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(18), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(19), 0x00000030);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(26), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(30), 0x0000002B);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(33), 0x000000E0);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(34), 0x000000E3);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(35), 0x000000E6);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(20), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(23), 0x00000031);
+	I40E_WRITE_REG(hw, I40E_GLQF_ORT(63), 0x0000002D);
+
+	/* GLQF_PIT Registers */
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(16), 0x00007480);
+	I40E_WRITE_REG(hw, I40E_GLQF_PIT(17), 0x00007440);
+}
+
 static int
 eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
                   struct rte_eth_dev *dev)
@@ -396,6 +425,13 @@ eth_i40e_dev_init(__rte_unused struct eth_driver *eth_drv,
 		return ret;
 	}
 
+	/*
+	 * To work around the NVM issue,initialize registers
+	 * for flexible payload by software.
+	 * It should be removed once issues are fixed in NVM.
+	 */
+	i40e_flex_payload_reg_init(hw);
+
 	/* Initialize the parameters for adminq */
 	i40e_init_adminq_parameter(hw);
 	ret = i40e_init_adminq(hw);
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 7ad6501..341599d 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -57,6 +57,17 @@
 /* Always assign pool 0 to main VSI, VMDQ will start from 1 */
 #define I40E_VMDQ_POOL_BASE       1
 
+/* index flex payload per layer */
+enum i40e_flxpld_layer_idx {
+	I40E_FLXPLD_L2_IDX    = 0,
+	I40E_FLXPLD_L3_IDX    = 1,
+	I40E_FLXPLD_L4_IDX    = 2,
+	I40E_MAX_FLXPLD_LAYER = 3,
+};
+#define I40E_MAX_FLXPLD_FIED        3  /* max number of flex payload fields */
+#define I40E_FDIR_BITMASK_NUM_WORD  2  /* max number of bitmask words */
+#define I40E_FDIR_MAX_FLEXWORD_NUM  8  /* max number of flexpayload words */
+
 /* i40e flags */
 #define I40E_FLAG_RSS                   (1ULL << 0)
 #define I40E_FLAG_DCB                   (1ULL << 1)
@@ -244,6 +255,24 @@ struct i40e_vmdq_info {
 };
 
 /*
+ * Structure to store flex pit for flow diretor.
+ */
+struct i40e_fdir_flex_pit {
+	uint8_t src_offset;    /* offset in words from the beginning of payload */
+	uint8_t size;          /* size in words */
+	uint8_t dst_offset;    /* offset in words of flexible payload */
+};
+
+struct i40e_fdir_flex_mask {
+	uint8_t word_mask;  /**< Bit i enables word i of flexible payload */
+	struct {
+		uint8_t offset;
+		uint16_t mask;
+	} bitmask[I40E_FDIR_BITMASK_NUM_WORD];
+};
+
+#define I40E_FILTER_PCTYPE_MAX 64
+/*
  *  A structure used to define fields of a FDIR related info.
  */
 struct i40e_fdir_info {
@@ -253,6 +282,12 @@ struct i40e_fdir_info {
 	struct i40e_rx_queue *rxq;
 	void *prg_pkt;                 /* memory for fdir program packet */
 	uint64_t dma_addr;             /* physic address of packet memory*/
+	/*
+	 * the rule how bytes stream is extracted as flexible payload
+	 * for each payload layer, the setting can up to three elements
+	 */
+	struct i40e_fdir_flex_pit flex_set[I40E_MAX_FLXPLD_LAYER * I40E_MAX_FLXPLD_FIED];
+	struct i40e_fdir_flex_mask flex_mask[I40E_FILTER_PCTYPE_MAX];
 };
 
 /*
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 9b678ce..ed61f2a 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -265,6 +265,47 @@ i40e_fdir_empty(struct i40e_hw *hw)
 }
 
 /*
+ * Initialize the configuration about bytes stream extracted as flexible payload
+ * and mask setting
+ */
+static inline void
+i40e_init_flx_pld(struct i40e_pf *pf)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint8_t pctype;
+	int i, index;
+
+	/*
+	 * Define the bytes stream extracted as flexible payload in
+	 * field vector. By default, select 8 words from the beginning
+	 * of payload as flexible payload.
+	 */
+	for (i = I40E_FLXPLD_L2_IDX; i < I40E_MAX_FLXPLD_LAYER; i++) {
+		index = i * I40E_MAX_FLXPLD_FIED;
+		pf->fdir.flex_set[index].src_offset = 0;
+		pf->fdir.flex_set[index].size = I40E_FDIR_MAX_FLEXWORD_NUM;
+		pf->fdir.flex_set[index].dst_offset = 0;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(index), 0x0000C900);
+		I40E_WRITE_REG(hw,
+			I40E_PRTQF_FLX_PIT(index + 1), 0x0000FC29);/*non-used*/
+		I40E_WRITE_REG(hw,
+			I40E_PRTQF_FLX_PIT(index + 2), 0x0000FC2A);/*non-used*/
+	}
+
+	/* initialize the masks */
+	for (pctype = I40E_FILTER_PCTYPE_NONF_IPV4_UDP;
+	     pctype <= I40E_FILTER_PCTYPE_FRAG_IPV6; pctype++) {
+		pf->fdir.flex_mask[pctype].word_mask = 0;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), 0);
+		for (i = 0; i < I40E_FDIR_BITMASK_NUM_WORD; i++) {
+			pf->fdir.flex_mask[pctype].bitmask[i].offset = 0;
+			pf->fdir.flex_mask[pctype].bitmask[i].mask = 0;
+			I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, i), 0);
+		}
+	}
+}
+
+/*
  * Configure flow director related setting
  */
 int
@@ -294,6 +335,8 @@ i40e_fdir_configure(struct rte_eth_dev *dev)
 		/* enable FDIR filter */
 		val |= I40E_PFQF_CTL_0_FD_ENA_MASK;
 		I40E_WRITE_REG(hw, I40E_PFQF_CTL_0, val);
+
+		i40e_init_flx_pld(pf); /* set flex config to default value */
 	} else {
 		/* disable FDIR filter */
 		val &= ~I40E_PFQF_CTL_0_FD_ENA_MASK;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 04/22] ethdev: define structures for adding/deleting flow director
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (2 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 03/22] i40e: initialize flexible payload setting Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 05/22] i40e: define functions for transition between flow_type and pctype Jingjing Wu
                         ` (18 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

define structures to add or delete flow director filter
  - struct rte_eth_fdir_filter

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 167 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 167 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 8dd384d..9856842 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -53,6 +53,7 @@ enum rte_filter_type {
 	RTE_ETH_FILTER_NONE = 0,
 	RTE_ETH_FILTER_MACVLAN,
 	RTE_ETH_FILTER_TUNNEL,
+	RTE_ETH_FILTER_FDIR,
 	RTE_ETH_FILTER_MAX
 };
 
@@ -155,6 +156,172 @@ struct rte_eth_tunnel_filter_conf {
 	uint16_t queue_id;      /** < queue number. */
 };
 
+#define RTE_ETH_FDIR_MAX_FLEXLEN         16 /** < Max length of flexbytes. */
+
+/**
+ * Flow type
+ */
+enum rte_eth_flow_type {
+	RTE_ETH_FLOW_TYPE_NONE = 0,
+	RTE_ETH_FLOW_TYPE_UDPV4,
+	RTE_ETH_FLOW_TYPE_TCPV4,
+	RTE_ETH_FLOW_TYPE_SCTPV4,
+	RTE_ETH_FLOW_TYPE_IPV4_OTHER,
+	RTE_ETH_FLOW_TYPE_FRAG_IPV4,
+	RTE_ETH_FLOW_TYPE_UDPV6,
+	RTE_ETH_FLOW_TYPE_TCPV6,
+	RTE_ETH_FLOW_TYPE_SCTPV6,
+	RTE_ETH_FLOW_TYPE_IPV6_OTHER,
+	RTE_ETH_FLOW_TYPE_FRAG_IPV6,
+	RTE_ETH_FLOW_TYPE_MAX = 64,
+};
+
+/**
+ * A structure used to define the input for IPV4 flow
+ */
+struct rte_eth_ipv4_flow {
+	uint32_t src_ip;      /**< IPv4 source address to match. */
+	uint32_t dst_ip;      /**< IPv4 destination address to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 UDP flow
+ */
+struct rte_eth_udpv4_flow {
+	struct rte_eth_ipv4_flow ip; /**< IPv4 fields to match. */
+	uint16_t src_port;           /**< UDP source port to match. */
+	uint16_t dst_port;           /**< UDP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 TCP flow
+ */
+struct rte_eth_tcpv4_flow {
+	struct rte_eth_ipv4_flow ip; /**< IPv4 fields to match. */
+	uint16_t src_port;           /**< TCP source port to match. */
+	uint16_t dst_port;           /**< TCP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV4 SCTP flow
+ */
+struct rte_eth_sctpv4_flow {
+	struct rte_eth_ipv4_flow ip; /**< IPv4 fields to match. */
+	uint32_t verify_tag;         /**< Verify tag to match */
+};
+
+/**
+ * A structure used to define the input for IPV6 flow
+ */
+struct rte_eth_ipv6_flow {
+	uint32_t src_ip[4];      /**< IPv6 source address to match. */
+	uint32_t dst_ip[4];      /**< IPv6 destination address to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 UDP flow
+ */
+struct rte_eth_udpv6_flow {
+	struct rte_eth_ipv6_flow ip; /**< IPv6 fields to match. */
+	uint16_t src_port;           /**< UDP source port to match. */
+	uint16_t dst_port;           /**< UDP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 TCP flow
+ */
+struct rte_eth_tcpv6_flow {
+	struct rte_eth_ipv6_flow ip; /**< IPv6 fields to match. */
+	uint16_t src_port;           /**< TCP source port to match. */
+	uint16_t dst_port;           /**< TCP destination port to match. */
+};
+
+/**
+ * A structure used to define the input for IPV6 SCTP flow
+ */
+struct rte_eth_sctpv6_flow {
+	struct rte_eth_ipv6_flow ip; /**< IPv6 fields to match. */
+	uint32_t verify_tag;         /**< Verify tag to match */
+};
+
+/**
+ * An union contains the inputs for all types of flow
+ */
+union rte_eth_fdir_flow {
+	struct rte_eth_udpv4_flow  udp4_flow;
+	struct rte_eth_tcpv4_flow  tcp4_flow;
+	struct rte_eth_sctpv4_flow sctp4_flow;
+	struct rte_eth_ipv4_flow   ip4_flow;
+	struct rte_eth_udpv6_flow  udp6_flow;
+	struct rte_eth_tcpv6_flow  tcp6_flow;
+	struct rte_eth_sctpv6_flow sctp6_flow;
+	struct rte_eth_ipv6_flow   ip6_flow;
+};
+
+/**
+ * A structure used to contain extend input of flow
+ */
+struct rte_eth_fdir_flow_ext {
+	uint16_t vlan_tci;
+	uint8_t flexbytes[RTE_ETH_FDIR_MAX_FLEXLEN];
+	/**< It is filled by the flexible payload to match. */
+};
+
+/**
+ * A structure used to define the input for a flow director filter entry
+ */
+struct rte_eth_fdir_input {
+	enum rte_eth_flow_type flow_type;      /**< Type of flow */
+	union rte_eth_fdir_flow flow;
+	/**< Flow fields to match, dependent on flow_type */
+	struct rte_eth_fdir_flow_ext flow_ext;
+	/**< Additional fields to match */
+};
+
+/**
+ * Behavior will be taken if FDIR match
+ */
+enum rte_eth_fdir_behavior {
+	RTE_ETH_FDIR_ACCEPT = 0,
+	RTE_ETH_FDIR_REJECT,
+};
+
+/**
+ * Flow director report status
+ * It defines what will be reported if FDIR entry is matched.
+ */
+enum rte_eth_fdir_status {
+	RTE_ETH_FDIR_NO_REPORT_STATUS = 0, /**< Report nothing. */
+	RTE_ETH_FDIR_REPORT_ID,            /**< Only report FD ID. */
+	RTE_ETH_FDIR_REPORT_ID_FLEX_4,     /**< Report FD ID and 4 flex bytes. */
+	RTE_ETH_FDIR_REPORT_FLEX_8,        /**< Report 8 flex bytes. */
+};
+
+/**
+ * A structure used to define an action when match FDIR packet filter.
+ */
+struct rte_eth_fdir_action {
+	uint16_t rx_queue;        /**< Queue assigned to if FDIR match. */
+	enum rte_eth_fdir_behavior behavior;     /**< Behavior will be taken */
+	enum rte_eth_fdir_status report_status;  /**< Status report option */
+	uint8_t flex_off;
+	/**< If report_status is RTE_ETH_FDIR_REPORT_ID_FLEX_4 or
+	     RTE_ETH_FDIR_REPORT_FLEX_8, flex_off specifies where the reported
+	     flex bytes start from in flexible payload. */
+};
+
+/**
+ * A structure used to define the flow director filter entry by filter_ctrl API
+ * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_ADD and
+ * RTE_ETH_FILTER_DELETE operations.
+ */
+struct rte_eth_fdir_filter {
+	uint32_t soft_id;
+	/**< ID, an unique value is required when deal with FDIR entry */
+	struct rte_eth_fdir_input input;    /**< Input set */
+	struct rte_eth_fdir_action action;  /**< Action taken when match */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 05/22] i40e: define functions for transition between flow_type and pctype
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (3 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 04/22] ethdev: define structures for adding/deleting flow director Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 06/22] i40e: implement operations to add/delete flow director Jingjing Wu
                         ` (17 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

- macros to validate flow_type and pctype
- functions for transition between flow_type and pctype:
  - i40e_flowtype_to_pctype
  - i40e_pctype_to_flowtype

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 46 +++++++++++++++++++++++++++++++++++++++
 lib/librte_pmd_i40e/i40e_ethdev.h | 28 ++++++++++++++++++++++++
 2 files changed, 74 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index e57b9b4..29b971c 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -5120,3 +5120,49 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 
 	return ret;
 }
+
+enum i40e_filter_pctype
+i40e_flowtype_to_pctype(enum rte_eth_flow_type flow_type)
+{
+	static const enum i40e_filter_pctype pctype_table[] = {
+		[RTE_ETH_FLOW_TYPE_UDPV4] = I40E_FILTER_PCTYPE_NONF_IPV4_UDP,
+		[RTE_ETH_FLOW_TYPE_TCPV4] = I40E_FILTER_PCTYPE_NONF_IPV4_TCP,
+		[RTE_ETH_FLOW_TYPE_SCTPV4] = I40E_FILTER_PCTYPE_NONF_IPV4_SCTP,
+		[RTE_ETH_FLOW_TYPE_IPV4_OTHER] =
+					I40E_FILTER_PCTYPE_NONF_IPV4_OTHER,
+		[RTE_ETH_FLOW_TYPE_FRAG_IPV4] =
+					I40E_FILTER_PCTYPE_FRAG_IPV4,
+		[RTE_ETH_FLOW_TYPE_UDPV6] = I40E_FILTER_PCTYPE_NONF_IPV6_UDP,
+		[RTE_ETH_FLOW_TYPE_TCPV6] = I40E_FILTER_PCTYPE_NONF_IPV6_TCP,
+		[RTE_ETH_FLOW_TYPE_SCTPV6] = I40E_FILTER_PCTYPE_NONF_IPV6_SCTP,
+		[RTE_ETH_FLOW_TYPE_IPV6_OTHER] =
+					I40E_FILTER_PCTYPE_NONF_IPV6_OTHER,
+		[RTE_ETH_FLOW_TYPE_FRAG_IPV6] =
+					I40E_FILTER_PCTYPE_FRAG_IPV6,
+	};
+
+	return pctype_table[flow_type];
+}
+
+enum rte_eth_flow_type
+i40e_pctype_to_flowtype(enum i40e_filter_pctype pctype)
+{
+	static const enum rte_eth_flow_type flowtype_table[] = {
+		[I40E_FILTER_PCTYPE_NONF_IPV4_UDP] = RTE_ETH_FLOW_TYPE_UDPV4,
+		[I40E_FILTER_PCTYPE_NONF_IPV4_TCP] = RTE_ETH_FLOW_TYPE_TCPV4,
+		[I40E_FILTER_PCTYPE_NONF_IPV4_SCTP] = RTE_ETH_FLOW_TYPE_SCTPV4,
+		[I40E_FILTER_PCTYPE_NONF_IPV4_OTHER] =
+					RTE_ETH_FLOW_TYPE_IPV4_OTHER,
+		[I40E_FILTER_PCTYPE_FRAG_IPV4] =
+					RTE_ETH_FLOW_TYPE_FRAG_IPV4,
+		[I40E_FILTER_PCTYPE_NONF_IPV6_UDP] = RTE_ETH_FLOW_TYPE_UDPV6,
+		[I40E_FILTER_PCTYPE_NONF_IPV6_TCP] = RTE_ETH_FLOW_TYPE_TCPV6,
+		[I40E_FILTER_PCTYPE_NONF_IPV6_SCTP] = RTE_ETH_FLOW_TYPE_SCTPV6,
+		[I40E_FILTER_PCTYPE_NONF_IPV6_OTHER] =
+					RTE_ETH_FLOW_TYPE_IPV6_OTHER,
+		[I40E_FILTER_PCTYPE_FRAG_IPV6] =
+					RTE_ETH_FLOW_TYPE_FRAG_IPV6,
+	};
+
+	return flowtype_table[pctype];
+}
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 341599d..cda309a 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -437,6 +437,10 @@ const struct rte_memzone *i40e_memzone_reserve(const char *name,
 					int socket_id);
 int i40e_fdir_configure(struct rte_eth_dev *dev);
 void i40e_fdir_teardown(struct i40e_pf *pf);
+enum i40e_filter_pctype i40e_flowtype_to_pctype(
+				enum rte_eth_flow_type flow_type);
+enum rte_eth_flow_type i40e_pctype_to_flowtype(
+				enum i40e_filter_pctype pctype);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
@@ -499,4 +503,28 @@ i40e_init_adminq_parameter(struct i40e_hw *hw)
 	hw->aq.asq_buf_size = I40E_AQ_BUF_SZ;
 }
 
+#define I40E_VALID_FLOW_TYPE(flow_type) \
+	((flow_type) == RTE_ETH_FLOW_TYPE_UDPV4 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_TCPV4 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_SCTPV4 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_IPV4_OTHER || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_FRAG_IPV4 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_UDPV6 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_TCPV6 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_SCTPV6 || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_IPV6_OTHER || \
+	(flow_type) == RTE_ETH_FLOW_TYPE_FRAG_IPV6)
+
+#define I40E_VALID_PCTYPE(pctype) \
+	((pctype) == I40E_FILTER_PCTYPE_NONF_IPV4_UDP || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV4_TCP || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV4_SCTP || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV4_OTHER || \
+	(pctype) == I40E_FILTER_PCTYPE_FRAG_IPV4 || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV6_UDP || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV6_TCP || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV6_SCTP || \
+	(pctype) == I40E_FILTER_PCTYPE_NONF_IPV6_OTHER || \
+	(pctype) == I40E_FILTER_PCTYPE_FRAG_IPV6)
+
 #endif /* _I40E_ETHDEV_H_ */
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 06/22] i40e: implement operations to add/delete flow director
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (4 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 05/22] i40e: define functions for transition between flow_type and pctype Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 07/22] testpmd: add test commands to add/delete flow director filter Jingjing Wu
                         ` (16 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

deal with two operations for flow director
 - RTE_ETH_FILTER_ADD
 - RTE_ETH_FILTER_DELETE
encode the flow inputs to programming packet
sent the packet to filter programming queue and check status on the status report queue

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |   3 +
 lib/librte_pmd_i40e/i40e_ethdev.h |   3 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 518 +++++++++++++++++++++++++++++++++++++-
 3 files changed, 523 insertions(+), 1 deletion(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 29b971c..66286ee 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -5111,6 +5111,9 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 	case RTE_ETH_FILTER_TUNNEL:
 		ret = i40e_tunnel_filter_handle(dev, filter_op, arg);
 		break;
+	case RTE_ETH_FILTER_FDIR:
+		ret = i40e_fdir_ctrl_func(dev, filter_op, arg);
+		break;
 	default:
 		PMD_DRV_LOG(WARNING, "Filter type (%d) not supported",
 							filter_type);
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index cda309a..fbce86a 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -441,6 +441,9 @@ enum i40e_filter_pctype i40e_flowtype_to_pctype(
 				enum rte_eth_flow_type flow_type);
 enum rte_eth_flow_type i40e_pctype_to_flowtype(
 				enum i40e_filter_pctype pctype);
+int i40e_fdir_ctrl_func(struct rte_eth_dev *dev,
+			  enum rte_filter_op filter_op,
+			  void *arg);
 
 /* I40E_DEV_PRIVATE_TO */
 #define I40E_DEV_PRIVATE_TO_PF(adapter) \
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index ed61f2a..5205530 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -44,6 +44,10 @@
 #include <rte_log.h>
 #include <rte_memzone.h>
 #include <rte_malloc.h>
+#include <rte_ip.h>
+#include <rte_udp.h>
+#include <rte_tcp.h>
+#include <rte_sctp.h>
 
 #include "i40e_logs.h"
 #include "i40e/i40e_type.h"
@@ -51,8 +55,23 @@
 #include "i40e_rxtx.h"
 
 #define I40E_FDIR_MZ_NAME          "FDIR_MEMZONE"
-#define I40E_FDIR_PKT_LEN                   512
+#ifndef IPV6_ADDR_LEN
+#define IPV6_ADDR_LEN              16
+#endif
 
+#define I40E_FDIR_PKT_LEN                   512
+#define I40E_FDIR_IP_DEFAULT_LEN            420
+#define I40E_FDIR_IP_DEFAULT_TTL            0x40
+#define I40E_FDIR_IP_DEFAULT_VERSION_IHL    0x45
+#define I40E_FDIR_TCP_DEFAULT_DATAOFF       0x50
+#define I40E_FDIR_IPv6_DEFAULT_VTC_FLOW     0x60300000
+#define I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS   0xFF
+#define I40E_FDIR_IPv6_PAYLOAD_LEN          380
+#define I40E_FDIR_UDP_DEFAULT_LEN           400
+
+/* Wait count and interval for fdir filter programming */
+#define I40E_FDIR_WAIT_COUNT       10
+#define I40E_FDIR_WAIT_INTERVAL_US 1000
 
 /* Wait count and interval for fdir filter flush */
 #define I40E_FDIR_FLUSH_RETRY       50
@@ -64,6 +83,16 @@
 #define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
+				     const struct rte_eth_fdir_input *fdir_input,
+				     unsigned char *raw_pkt);
+static int i40e_add_del_fdir_filter(struct rte_eth_dev *dev,
+			    const struct rte_eth_fdir_filter *filter,
+			    bool add);
+static int i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			const struct rte_eth_fdir_filter *filter,
+			bool add);
 static int i40e_fdir_flush(struct rte_eth_dev *dev);
 
 static int
@@ -347,6 +376,451 @@ i40e_fdir_configure(struct rte_eth_dev *dev)
 	return ret;
 }
 
+static inline void
+i40e_fdir_fill_eth_ip_head(const struct rte_eth_fdir_input *fdir_input,
+			       unsigned char *raw_pkt)
+{
+	struct ether_hdr *ether = (struct ether_hdr *)raw_pkt;
+	struct ipv4_hdr *ip;
+	struct ipv6_hdr *ip6;
+	static const uint8_t next_proto[] = {
+		[RTE_ETH_FLOW_TYPE_UDPV4] = IPPROTO_UDP,
+		[RTE_ETH_FLOW_TYPE_TCPV4] = IPPROTO_TCP,
+		[RTE_ETH_FLOW_TYPE_SCTPV4] = IPPROTO_SCTP,
+		[RTE_ETH_FLOW_TYPE_IPV4_OTHER] = IPPROTO_IP,
+		[RTE_ETH_FLOW_TYPE_FRAG_IPV4] = IPPROTO_IP,
+		[RTE_ETH_FLOW_TYPE_UDPV6] = IPPROTO_UDP,
+		[RTE_ETH_FLOW_TYPE_TCPV6] = IPPROTO_TCP,
+		[RTE_ETH_FLOW_TYPE_SCTPV6] = IPPROTO_SCTP,
+		[RTE_ETH_FLOW_TYPE_IPV6_OTHER] = IPPROTO_NONE,
+		[RTE_ETH_FLOW_TYPE_FRAG_IPV6] = IPPROTO_NONE,
+	};
+
+	switch (fdir_input->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+	case RTE_ETH_FLOW_TYPE_FRAG_IPV4:
+		ip = (struct ipv4_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv4);
+		ip->version_ihl = I40E_FDIR_IP_DEFAULT_VERSION_IHL;
+		/* set len to by default */
+		ip->total_length = rte_cpu_to_be_16(I40E_FDIR_IP_DEFAULT_LEN);
+		ip->time_to_live = I40E_FDIR_IP_DEFAULT_TTL;
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		ip->src_addr = fdir_input->flow.ip4_flow.dst_ip;
+		ip->dst_addr = fdir_input->flow.ip4_flow.src_ip;
+		ip->next_proto_id = next_proto[fdir_input->flow_type];
+		break;
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+	case RTE_ETH_FLOW_TYPE_FRAG_IPV6:
+		ip6 = (struct ipv6_hdr *)(raw_pkt + sizeof(struct ether_hdr));
+
+		ether->ether_type = rte_cpu_to_be_16(ETHER_TYPE_IPv6);
+		ip6->vtc_flow =
+			rte_cpu_to_be_32(I40E_FDIR_IPv6_DEFAULT_VTC_FLOW);
+		ip6->payload_len =
+			rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		ip6->hop_limits = I40E_FDIR_IPv6_DEFAULT_HOP_LIMITS;
+
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		rte_memcpy(&(ip6->src_addr),
+			   &(fdir_input->flow.ip6_flow.dst_ip),
+			   IPV6_ADDR_LEN);
+		rte_memcpy(&(ip6->dst_addr),
+			   &(fdir_input->flow.ip6_flow.src_ip),
+			   IPV6_ADDR_LEN);
+		ip6->proto = next_proto[fdir_input->flow_type];
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown flow type %u.",
+			    fdir_input->flow_type);
+		break;
+	}
+}
+
+
+/*
+ * i40e_fdir_construct_pkt - construct packet based on fields in input
+ * @pf: board private structure
+ * @fdir_input: input set of the flow director entry
+ * @raw_pkt: a packet to be constructed
+ */
+static int
+i40e_fdir_construct_pkt(struct i40e_pf *pf,
+			     const struct rte_eth_fdir_input *fdir_input,
+			     unsigned char *raw_pkt)
+{
+	unsigned char *payload, *ptr;
+	struct udp_hdr *udp;
+	struct tcp_hdr *tcp;
+	struct sctp_hdr *sctp;
+	uint8_t size, dst = 0;
+	uint8_t i, pit_idx, set_idx = I40E_FLXPLD_L4_IDX; /* use l4 by default*/
+
+	/* fill the ethernet and IP head */
+	i40e_fdir_fill_eth_ip_head(fdir_input, raw_pkt);
+
+	/* fill the L4 head */
+	switch (fdir_input->flow_type) {
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+				sizeof(struct ipv4_hdr));
+		payload = (unsigned char *)udp + sizeof(struct udp_hdr);
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		udp->src_port = fdir_input->flow.udp4_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp4_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_UDP_DEFAULT_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv4_hdr));
+		payload = (unsigned char *)tcp + sizeof(struct tcp_hdr);
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		tcp->src_port = fdir_input->flow.tcp4_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.tcp4_flow.src_port;
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv4_hdr));
+		payload = (unsigned char *)sctp + sizeof(struct sctp_hdr);
+		sctp->tag = fdir_input->flow.sctp4_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+	case RTE_ETH_FLOW_TYPE_FRAG_IPV4:
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv4_hdr);
+		set_idx = I40E_FLXPLD_L3_IDX;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+		udp = (struct udp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = (unsigned char *)udp + sizeof(struct udp_hdr);
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		udp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		udp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		udp->dgram_len = rte_cpu_to_be_16(I40E_FDIR_IPv6_PAYLOAD_LEN);
+		break;
+
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		tcp = (struct tcp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					 sizeof(struct ipv6_hdr));
+		payload = (unsigned char *)tcp + sizeof(struct tcp_hdr);
+		/*
+		 * The source and destination fields in the transmitted packet
+		 * need to be presented in a reversed order with respect
+		 * to the expected received packets.
+		 */
+		tcp->data_off = I40E_FDIR_TCP_DEFAULT_DATAOFF;
+		tcp->src_port = fdir_input->flow.udp6_flow.dst_port;
+		tcp->dst_port = fdir_input->flow.udp6_flow.src_port;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		sctp = (struct sctp_hdr *)(raw_pkt + sizeof(struct ether_hdr) +
+					   sizeof(struct ipv6_hdr));
+		payload = (unsigned char *)sctp + sizeof(struct sctp_hdr);
+		sctp->tag = fdir_input->flow.sctp6_flow.verify_tag;
+		break;
+
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+	case RTE_ETH_FLOW_TYPE_FRAG_IPV6:
+		payload = raw_pkt + sizeof(struct ether_hdr) +
+			  sizeof(struct ipv6_hdr);
+		set_idx = I40E_FLXPLD_L3_IDX;
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown flow type %u.", fdir_input->flow_type);
+		return -EINVAL;
+	}
+
+	/* fill the flexbytes to payload */
+	for (i = 0; i < I40E_MAX_FLXPLD_FIED; i++) {
+		pit_idx = set_idx * I40E_MAX_FLXPLD_FIED + i;
+		size = pf->fdir.flex_set[pit_idx].size;
+		if (size == 0)
+			continue;
+		dst = pf->fdir.flex_set[pit_idx].dst_offset * sizeof(uint16_t);
+		ptr = payload +
+			pf->fdir.flex_set[pit_idx].src_offset * sizeof(uint16_t);
+		(void)rte_memcpy(ptr,
+				 &fdir_input->flow_ext.flexbytes[dst],
+				 size * sizeof(uint16_t));
+	}
+
+	return 0;
+}
+
+/* Construct the tx flags */
+static inline uint64_t
+i40e_build_ctob(uint32_t td_cmd,
+		uint32_t td_offset,
+		unsigned int size,
+		uint32_t td_tag)
+{
+	return rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DATA |
+			((uint64_t)td_cmd  << I40E_TXD_QW1_CMD_SHIFT) |
+			((uint64_t)td_offset << I40E_TXD_QW1_OFFSET_SHIFT) |
+			((uint64_t)size  << I40E_TXD_QW1_TX_BUF_SZ_SHIFT) |
+			((uint64_t)td_tag  << I40E_TXD_QW1_L2TAG1_SHIFT));
+}
+
+/*
+ * check the programming status descriptor in rx queue.
+ * done after Programming Flow Director is programmed on
+ * tx queue
+ */
+static inline int
+i40e_check_fdir_programming_status(struct i40e_rx_queue *rxq)
+{
+	volatile union i40e_rx_desc *rxdp;
+	uint64_t qword1;
+	uint32_t rx_status;
+	uint32_t len, id;
+	uint32_t error;
+	int ret = 0;
+
+	rxdp = &rxq->rx_ring[rxq->rx_tail];
+	qword1 = rte_le_to_cpu_64(rxdp->wb.qword1.status_error_len);
+	rx_status = (qword1 & I40E_RXD_QW1_STATUS_MASK)
+			>> I40E_RXD_QW1_STATUS_SHIFT;
+
+	if (rx_status & (1 << I40E_RX_DESC_STATUS_DD_SHIFT)) {
+		len = qword1 >> I40E_RX_PROG_STATUS_DESC_LENGTH_SHIFT;
+		id = (qword1 & I40E_RX_PROG_STATUS_DESC_QW1_PROGID_MASK) >>
+			    I40E_RX_PROG_STATUS_DESC_QW1_PROGID_SHIFT;
+
+		if (len  == I40E_RX_PROG_STATUS_DESC_LENGTH &&
+		    id == I40E_RX_PROG_STATUS_DESC_FD_FILTER_STATUS) {
+			error = (qword1 &
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_MASK) >>
+				I40E_RX_PROG_STATUS_DESC_QW1_ERROR_SHIFT;
+			if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_FD_TBL_FULL_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to add FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else if (error == (0x1 <<
+				I40E_RX_PROG_STATUS_DESC_NO_FD_ENTRY_SHIFT)) {
+				PMD_DRV_LOG(ERR, "Failed to delete FDIR filter"
+					    " (FD_ID %u): programming status"
+					    " reported.",
+					    rxdp->wb.qword0.hi_dword.fd_id);
+				ret = -1;
+			} else
+				PMD_DRV_LOG(ERR, "invalid programming status"
+					    " reported, error = %u.", error);
+		} else
+			PMD_DRV_LOG(ERR, "unknown programming status"
+				    " reported, len = %d, id = %u.", len, id);
+		rxdp->wb.qword1.status_error_len = 0;
+		rxq->rx_tail++;
+		if (unlikely(rxq->rx_tail == rxq->nb_rx_desc))
+			rxq->rx_tail = 0;
+	}
+	return ret;
+}
+
+/*
+ * i40e_add_del_fdir_filter - add or remove a flow director filter.
+ * @pf: board private structure
+ * @filter: fdir filter entry
+ * @add: 0 - delete, 1 - add
+ */
+static int
+i40e_add_del_fdir_filter(struct rte_eth_dev *dev,
+			    const struct rte_eth_fdir_filter *filter,
+			    bool add)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	unsigned char *pkt = (unsigned char *)pf->fdir.prg_pkt;
+	enum i40e_filter_pctype pctype;
+	int ret = 0;
+
+	if (!(pf->flags & I40E_FLAG_FDIR)) {
+		PMD_DRV_LOG(ERR, "FDIR is not enabled.");
+		return -ENOTSUP;
+	}
+	if (!I40E_VALID_FLOW_TYPE(filter->input.flow_type)) {
+		PMD_DRV_LOG(ERR, "invalid flow_type input.");
+		return -EINVAL;
+	}
+	if (filter->action.rx_queue >= pf->dev_data->nb_rx_queues) {
+		PMD_DRV_LOG(ERR, "Invalid queue ID");
+		return -EINVAL;
+	}
+
+	memset(pkt, 0, I40E_FDIR_PKT_LEN);
+
+	ret = i40e_fdir_construct_pkt(pf, &filter->input, pkt);
+	if (ret < 0) {
+		PMD_DRV_LOG(ERR, "construct packet for fdir fails.");
+		return ret;
+	}
+	pctype = i40e_flowtype_to_pctype(filter->input.flow_type);
+	ret = i40e_fdir_filter_programming(pf, pctype, filter, add);
+	if (ret < 0) {
+		PMD_DRV_LOG(ERR, "fdir programming fails for PCTYPE(%u).",
+			    pctype);
+		return ret;
+	}
+	return ret;
+}
+
+/*
+ * i40e_fdir_filter_programming - Program a flow director filter rule.
+ * Is done by Flow Director Programming Descriptor followed by packet
+ * structure that contains the filter fields need to match.
+ * @pf: board private structure
+ * @pctype: pctype
+ * @filter: fdir filter entry
+ * @add: 0 - delelet, 1 - add
+ */
+static int
+i40e_fdir_filter_programming(struct i40e_pf *pf,
+			enum i40e_filter_pctype pctype,
+			const struct rte_eth_fdir_filter *filter,
+			bool add)
+{
+	struct i40e_tx_queue *txq = pf->fdir.txq;
+	struct i40e_rx_queue *rxq = pf->fdir.rxq;
+	const struct rte_eth_fdir_action *fdir_action = &filter->action;
+	volatile struct i40e_tx_desc *txdp;
+	volatile struct i40e_filter_program_desc *fdirdp;
+	uint32_t td_cmd;
+	uint16_t i;
+	uint8_t dest;
+
+	PMD_DRV_LOG(INFO, "filling filter programming descriptor.");
+	fdirdp = (volatile struct i40e_filter_program_desc *)
+			(&(txq->tx_ring[txq->tx_tail]));
+
+	fdirdp->qindex_flex_ptype_vsi =
+			rte_cpu_to_le_32((fdir_action->rx_queue <<
+					  I40E_TXD_FLTR_QW0_QINDEX_SHIFT) &
+					  I40E_TXD_FLTR_QW0_QINDEX_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((fdir_action->flex_off <<
+					  I40E_TXD_FLTR_QW0_FLEXOFF_SHIFT) &
+					  I40E_TXD_FLTR_QW0_FLEXOFF_MASK);
+
+	fdirdp->qindex_flex_ptype_vsi |=
+			rte_cpu_to_le_32((pctype <<
+					  I40E_TXD_FLTR_QW0_PCTYPE_SHIFT) &
+					  I40E_TXD_FLTR_QW0_PCTYPE_MASK);
+
+	/* Use LAN VSI Id by default */
+	fdirdp->qindex_flex_ptype_vsi |=
+		rte_cpu_to_le_32((pf->main_vsi->vsi_id <<
+				  I40E_TXD_FLTR_QW0_DEST_VSI_SHIFT) &
+				  I40E_TXD_FLTR_QW0_DEST_VSI_MASK);
+
+	fdirdp->dtype_cmd_cntindex =
+			rte_cpu_to_le_32(I40E_TX_DESC_DTYPE_FILTER_PROG);
+
+	if (add)
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_ADD_UPDATE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+	else
+		fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32(
+				I40E_FILTER_PROGRAM_DESC_PCMD_REMOVE <<
+				I40E_TXD_FLTR_QW1_PCMD_SHIFT);
+
+	if (fdir_action->behavior == RTE_ETH_FDIR_REJECT)
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DROP_PACKET;
+	else
+		dest = I40E_FILTER_PROGRAM_DESC_DEST_DIRECT_PACKET_QINDEX;
+	fdirdp->dtype_cmd_cntindex |= rte_cpu_to_le_32((dest <<
+				I40E_TXD_FLTR_QW1_DEST_SHIFT) &
+				I40E_TXD_FLTR_QW1_DEST_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+		rte_cpu_to_le_32((fdir_action->report_status<<
+				I40E_TXD_FLTR_QW1_FD_STATUS_SHIFT) &
+				I40E_TXD_FLTR_QW1_FD_STATUS_MASK);
+
+	fdirdp->dtype_cmd_cntindex |=
+			rte_cpu_to_le_32(I40E_TXD_FLTR_QW1_CNT_ENA_MASK);
+	fdirdp->dtype_cmd_cntindex |=
+			rte_cpu_to_le_32((pf->fdir.match_counter_index <<
+			I40E_TXD_FLTR_QW1_CNTINDEX_SHIFT) &
+			I40E_TXD_FLTR_QW1_CNTINDEX_MASK);
+
+	fdirdp->fd_id = rte_cpu_to_le_32(filter->soft_id);
+
+	PMD_DRV_LOG(INFO, "filling transmit descriptor.");
+	txdp = &(txq->tx_ring[txq->tx_tail + 1]);
+	txdp->buffer_addr = rte_cpu_to_le_64(pf->fdir.dma_addr);
+	td_cmd = I40E_TX_DESC_CMD_EOP |
+		 I40E_TX_DESC_CMD_RS  |
+		 I40E_TX_DESC_CMD_DUMMY;
+
+	txdp->cmd_type_offset_bsz =
+		i40e_build_ctob(td_cmd, 0, I40E_FDIR_PKT_LEN, 0);
+
+	txq->tx_tail += 2; /* set 2 descriptors above, fdirdp and txdp */
+	if (txq->tx_tail >= txq->nb_tx_desc)
+		txq->tx_tail = 0;
+	/* Update the tx tail register */
+	rte_wmb();
+	I40E_PCI_REG_WRITE(txq->qtx_tail, txq->tx_tail);
+
+	for (i = 0; i < I40E_FDIR_WAIT_COUNT; i++) {
+		rte_delay_us(I40E_FDIR_WAIT_INTERVAL_US);
+		if (txdp->cmd_type_offset_bsz &
+				rte_cpu_to_le_64(I40E_TX_DESC_DTYPE_DESC_DONE))
+			break;
+	}
+	if (i >= I40E_FDIR_WAIT_COUNT) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " time out to get DD on tx queue.");
+		return -ETIMEDOUT;
+	}
+	/* totally delay 10 ms to check programming status*/
+	rte_delay_us((I40E_FDIR_WAIT_COUNT - i) * I40E_FDIR_WAIT_INTERVAL_US);
+	if (i40e_check_fdir_programming_status(rxq) < 0) {
+		PMD_DRV_LOG(ERR, "Failed to program FDIR filter:"
+			    " programming status reported.");
+		return -ENOSYS;
+	}
+
+	return 0;
+}
+
 /*
  * i40e_fdir_flush - clear all filters of Flow Director table
  * @pf: board private structure
@@ -386,3 +860,45 @@ i40e_fdir_flush(struct rte_eth_dev *dev)
 		PMD_DRV_LOG(INFO, "FD table Flush success.");
 	return 0;
 }
+
+/*
+ * i40e_fdir_ctrl_func - deal with all operations on flow director.
+ * @pf: board private structure
+ * @filter_op:operation will be taken.
+ * @arg: a pointer to specific structure corresponding to the filter_op
+ */
+int
+i40e_fdir_ctrl_func(struct rte_eth_dev *dev,
+		       enum rte_filter_op filter_op,
+		       void *arg)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	int ret = 0;
+
+	if (filter_op == RTE_ETH_FILTER_NOP) {
+		if (!(pf->flags & I40E_FLAG_FDIR))
+			ret = -ENOTSUP;
+		return ret;
+	}
+
+	if (arg == NULL)
+		return -EINVAL;
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_ADD:
+		ret = i40e_add_del_fdir_filter(dev,
+			(struct rte_eth_fdir_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_DELETE:
+		ret = i40e_add_del_fdir_filter(dev,
+			(struct rte_eth_fdir_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
+		ret = -EINVAL;
+		break;
+	}
+	return ret;
+}
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 07/22] testpmd: add test commands to add/delete flow director filter
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (5 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 06/22] i40e: implement operations to add/delete flow director Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 08/22] i40e: match counter for flow director Jingjing Wu
                         ` (15 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

Commands are added to test adding or deleting flow director filters.
10 flow types in flow director are supported: ipv4, ipv4-frag, tcpv4, udpv4, sctpv4, ipv6, ipv6-frag, tcpv6, udpv6, sctpv6

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 381 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 381 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 4c3fc76..91f6388 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -683,6 +683,29 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"get_flex_filter (port_id) index (idx)\n"
 			"    get info of a flex filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del)"
+			" flow (ip4|ip4-frag|ip6|ip6-frag)"
+			" src (src_ip_address) dst (dst_ip_address)"
+			" flexbytes (flexbytes_value)"
+			" (drop|fwd) queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del an IP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del)"
+			" flow (udp4|tcp4|udp6|tcp6)"
+			" src (src_ip_address) (src_port)"
+			" dst (dst_ip_address) (dst_port)"
+			" flexbytes (flexbytes_value)"
+			" (drop|fwd) queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del an UDP/TCP type flow director filter.\n\n"
+
+			"flow_director_filter (port_id) (add|del)"
+			" flow (sctp4|sctp6)"
+			" src (src_ip_address) dst (dst_ip_address)"
+			" tag (verification_tag)"
+			" flexbytes (flexbytes_value) (drop|fwd)"
+			" queue (queue_id) fd_id (fd_id_value)\n"
+			"    Add/Del a SCTP type flow director filter.\n\n"
 		);
 	}
 }
@@ -7745,6 +7768,361 @@ cmdline_parse_inst_t cmd_get_flex_filter = {
 	},
 };
 
+/* *** Filters Control *** */
+
+/* *** deal with flow director filter *** */
+struct cmd_flow_director_result {
+	cmdline_fixed_string_t flow_director_filter;
+	uint8_t port_id;
+	cmdline_fixed_string_t ops;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t src;
+	cmdline_ipaddr_t ip_src;
+	uint16_t port_src;
+	cmdline_fixed_string_t dst;
+	cmdline_ipaddr_t ip_dst;
+	uint16_t port_dst;
+	cmdline_fixed_string_t verify_tag;
+	uint32_t verify_tag_value;
+	cmdline_fixed_string_t flexbytes;
+	cmdline_fixed_string_t flexbytes_value;
+	cmdline_fixed_string_t drop;
+	cmdline_fixed_string_t queue;
+	uint16_t  queue_id;
+	cmdline_fixed_string_t fd_id;
+	uint32_t  fd_id_value;
+};
+
+static inline int
+parse_flexbytes(const char *q_arg, uint8_t *flexbytes, uint16_t max_num)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	unsigned long int_fld;
+	char *str_fld[max_num];
+	int i;
+	unsigned size;
+	int ret = -1;
+
+	p = strchr(p0, '(');
+	if (p == NULL)
+		return -1;
+	++p;
+	p0 = strchr(p, ')');
+	if (p0 == NULL)
+		return -1;
+
+	size = p0 - p;
+	if (size >= sizeof(s))
+		return -1;
+
+	snprintf(s, sizeof(s), "%.*s", size, p);
+	ret = rte_strsplit(s, sizeof(s), str_fld, max_num, ',');
+	if (ret < 0 || ret > max_num)
+		return -1;
+	for (i = 0; i < ret; i++) {
+		errno = 0;
+		int_fld = strtoul(str_fld[i], &end, 0);
+		if (errno != 0 || *end != '\0' || int_fld > UINT8_MAX)
+			return -1;
+		flexbytes[i] = (uint8_t)int_fld;
+	}
+	return ret;
+}
+
+static enum rte_eth_flow_type
+str2flowtype(char *string)
+{
+	uint8_t i = 0;
+	static const struct {
+		char str[32];
+		enum rte_eth_flow_type type;
+	} flowtype_str[] = {
+		{"ip4", RTE_ETH_FLOW_TYPE_IPV4_OTHER},
+		{"ip4-frag", RTE_ETH_FLOW_TYPE_FRAG_IPV4},
+		{"udp4", RTE_ETH_FLOW_TYPE_UDPV4},
+		{"tcp4", RTE_ETH_FLOW_TYPE_TCPV4},
+		{"sctp4", RTE_ETH_FLOW_TYPE_SCTPV4},
+		{"ip6", RTE_ETH_FLOW_TYPE_IPV6_OTHER},
+		{"ip6-frag", RTE_ETH_FLOW_TYPE_FRAG_IPV6},
+		{"udp6", RTE_ETH_FLOW_TYPE_UDPV6},
+		{"tcp6", RTE_ETH_FLOW_TYPE_TCPV6},
+		{"sctp6", RTE_ETH_FLOW_TYPE_TCPV6},
+	};
+
+	for (i = 0; i < RTE_DIM(flowtype_str); i++) {
+		if (!strcmp(flowtype_str[i].str, string))
+			return flowtype_str[i].type;
+	}
+	return RTE_ETH_FLOW_TYPE_NONE;
+}
+
+#define IPV4_ADDR_TO_UINT(ip_addr, ip) \
+do { \
+	if ((ip_addr).family == AF_INET) \
+		(ip) = (ip_addr).addr.ipv4.s_addr; \
+	else { \
+		printf("invalid parameter.\n"); \
+		return; \
+	} \
+} while (0)
+
+#define IPV6_ADDR_TO_ARRAY(ip_addr, ip) \
+do { \
+	if ((ip_addr).family == AF_INET6) \
+		(void)rte_memcpy(&(ip), \
+				 &((ip_addr).addr.ipv6), \
+				 sizeof(struct in6_addr)); \
+	else { \
+		printf("invalid parameter.\n"); \
+		return; \
+	} \
+} while (0)
+
+static void
+cmd_flow_director_filter_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	struct rte_eth_fdir_filter entry;
+	uint8_t flexbytes[RTE_ETH_FDIR_MAX_FLEXLEN];
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+	memset(flexbytes, 0, sizeof(flexbytes));
+	memset(&entry, 0, sizeof(struct rte_eth_fdir_filter));
+	ret = parse_flexbytes(res->flexbytes_value,
+					flexbytes,
+					RTE_ETH_FDIR_MAX_FLEXLEN);
+	if (ret < 0) {
+		printf("error: Cannot parse flexbytes input.\n");
+		return;
+	}
+
+	entry.input.flow_type = str2flowtype(res->flow_type);
+	switch (entry.input.flow_type) {
+	case RTE_ETH_FLOW_TYPE_IPV4_OTHER:
+	case RTE_ETH_FLOW_TYPE_UDPV4:
+	case RTE_ETH_FLOW_TYPE_TCPV4:
+		IPV4_ADDR_TO_UINT(res->ip_dst,
+			entry.input.flow.ip4_flow.dst_ip);
+		IPV4_ADDR_TO_UINT(res->ip_src,
+			entry.input.flow.ip4_flow.src_ip);
+		/* need convert to big endian. */
+		entry.input.flow.udp4_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp4_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV4:
+		IPV4_ADDR_TO_UINT(res->ip_dst,
+			entry.input.flow.sctp4_flow.ip.dst_ip);
+		IPV4_ADDR_TO_UINT(res->ip_src,
+			entry.input.flow.sctp4_flow.ip.src_ip);
+		/* need convert to big endian. */
+		entry.input.flow.sctp4_flow.verify_tag =
+				rte_cpu_to_be_32(res->verify_tag_value);
+		break;
+	case RTE_ETH_FLOW_TYPE_IPV6_OTHER:
+	case RTE_ETH_FLOW_TYPE_UDPV6:
+	case RTE_ETH_FLOW_TYPE_TCPV6:
+		IPV6_ADDR_TO_ARRAY(res->ip_dst,
+			entry.input.flow.ip6_flow.dst_ip);
+		IPV6_ADDR_TO_ARRAY(res->ip_src,
+			entry.input.flow.ip6_flow.src_ip);
+		/* need convert to big endian. */
+		entry.input.flow.udp6_flow.dst_port =
+				rte_cpu_to_be_16(res->port_dst);
+		entry.input.flow.udp6_flow.src_port =
+				rte_cpu_to_be_16(res->port_src);
+		break;
+	case RTE_ETH_FLOW_TYPE_SCTPV6:
+		IPV6_ADDR_TO_ARRAY(res->ip_dst,
+			entry.input.flow.sctp6_flow.ip.dst_ip);
+		IPV6_ADDR_TO_ARRAY(res->ip_src,
+			entry.input.flow.sctp6_flow.ip.src_ip);
+		/* need convert to big endian. */
+		entry.input.flow.sctp6_flow.verify_tag =
+				rte_cpu_to_be_32(res->verify_tag_value);
+		break;
+	default:
+		printf("invalid parameter.\n");
+		return;
+	}
+	(void)rte_memcpy(entry.input.flow_ext.flexbytes,
+		   flexbytes,
+		   RTE_ETH_FDIR_MAX_FLEXLEN);
+
+	entry.action.flex_off = 0;  /*use 0 by default */
+	if (!strcmp(res->drop, "drop"))
+		entry.action.behavior = RTE_ETH_FDIR_REJECT;
+	else
+		entry.action.behavior = RTE_ETH_FDIR_ACCEPT;
+	/* set to report FD ID by default */
+	entry.action.report_status = RTE_ETH_FDIR_REPORT_ID;
+	entry.action.rx_queue = res->queue_id;
+	entry.soft_id = res->fd_id_value;
+	if (!strcmp(res->ops, "add"))
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_ADD, &entry);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+					     RTE_ETH_FILTER_DELETE, &entry);
+	if (ret < 0)
+		printf("flow director programming error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_token_string_t cmd_flow_director_filter =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_director_filter, "flow_director_filter");
+cmdline_parse_token_num_t cmd_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_ops =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 ops, "add#del");
+cmdline_parse_token_string_t cmd_flow_director_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flow_type,
+				 "ip4#ip4-frag#tcp4#udp4#sctp4#"
+				 "ip6#ip6-frag#tcp6#udp6#sctp6");
+cmdline_parse_token_string_t cmd_flow_director_src =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 src, "src");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_src =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_src);
+cmdline_parse_token_num_t cmd_flow_director_port_src =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_src, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_dst =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 dst, "dst");
+cmdline_parse_token_ipaddr_t cmd_flow_director_ip_dst =
+	TOKEN_IPADDR_INITIALIZER(struct cmd_flow_director_result,
+				 ip_dst);
+cmdline_parse_token_num_t cmd_flow_director_port_dst =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      port_dst, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_verify_tag =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				  verify_tag, "verify_tag");
+cmdline_parse_token_num_t cmd_flow_director_verify_tag_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      verify_tag_value, UINT32);
+cmdline_parse_token_string_t cmd_flow_director_flexbytes =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 flexbytes, "flexbytes");
+cmdline_parse_token_string_t cmd_flow_director_flexbytes_value =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+			      flexbytes_value, NULL);
+cmdline_parse_token_string_t cmd_flow_director_drop =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 drop, "drop#fwd");
+cmdline_parse_token_string_t cmd_flow_director_queue =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 queue, "queue");
+cmdline_parse_token_num_t cmd_flow_director_queue_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      queue_id, UINT16);
+cmdline_parse_token_string_t cmd_flow_director_fd_id =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_result,
+				 fd_id, "fd_id");
+cmdline_parse_token_num_t cmd_flow_director_fd_id_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_result,
+			      fd_id_value, UINT32);
+
+cmdline_parse_inst_t cmd_add_del_ip_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete an ip flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_flexbytes,
+		(void *)&cmd_flow_director_flexbytes_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_udp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete an udp/tcp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_port_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_port_dst,
+		(void *)&cmd_flow_director_flexbytes,
+		(void *)&cmd_flow_director_flexbytes_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
+cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
+	.f = cmd_flow_director_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a sctp flow director entry on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_filter,
+		(void *)&cmd_flow_director_port_id,
+		(void *)&cmd_flow_director_ops,
+		(void *)&cmd_flow_director_flow,
+		(void *)&cmd_flow_director_flow_type,
+		(void *)&cmd_flow_director_src,
+		(void *)&cmd_flow_director_ip_src,
+		(void *)&cmd_flow_director_dst,
+		(void *)&cmd_flow_director_ip_dst,
+		(void *)&cmd_flow_director_verify_tag,
+		(void *)&cmd_flow_director_verify_tag_value,
+		(void *)&cmd_flow_director_flexbytes,
+		(void *)&cmd_flow_director_flexbytes_value,
+		(void *)&cmd_flow_director_drop,
+		(void *)&cmd_flow_director_queue,
+		(void *)&cmd_flow_director_queue_id,
+		(void *)&cmd_flow_director_fd_id,
+		(void *)&cmd_flow_director_fd_id_value,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7874,6 +8252,9 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_remove_flex_filter,
 	(cmdline_parse_inst_t *)&cmd_get_flex_filter,
+	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 08/22] i40e: match counter for flow director
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (6 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 07/22] testpmd: add test commands to add/delete flow director filter Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field Jingjing Wu
                         ` (14 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

support to get the fdir_match counter

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 66286ee..c88eb42 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1360,6 +1360,9 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			    I40E_GLPRT_PTC9522L(hw->port),
 			    pf->offset_loaded, &os->tx_size_big,
 			    &ns->tx_size_big);
+	i40e_stat_update_32(hw, I40E_GLQF_PCNT(pf->fdir.match_counter_index),
+			   pf->offset_loaded,
+			   &os->fd_sb_match, &ns->fd_sb_match);
 	/* GLPRT_MSPDC not supported */
 	/* GLPRT_XEC not supported */
 
@@ -1376,6 +1379,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 	stats->obytes   = ns->eth.tx_bytes;
 	stats->oerrors  = ns->eth.tx_errors;
 	stats->imcasts  = ns->eth.rx_multicast;
+	stats->fdirmatch = ns->fd_sb_match;
 
 	/* Rx Errors */
 	stats->ibadcrc  = ns->crc_errors;
@@ -1451,6 +1455,7 @@ i40e_dev_stats_get(struct rte_eth_dev *dev, struct rte_eth_stats *stats)
 			ns->mac_short_packet_dropped);
 	PMD_DRV_LOG(DEBUG, "checksum_error:           %lu",
 		    ns->checksum_error);
+	PMD_DRV_LOG(DEBUG, "fdir_match:               %lu", ns->fd_sb_match);
 	PMD_DRV_LOG(DEBUG, "***************** PF stats end ********************");
 }
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (7 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 08/22] i40e: match counter for flow director Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21 17:03         ` Chilikin, Andrey
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 10/22] i40e: report flow director match info to mbuf Jingjing Wu
                         ` (13 subsequent siblings)
  22 siblings, 1 reply; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

fdir field in rte_mbuf is extened to support flex bytes reported when fdir match.
8 flex bytes can be reported in maximum.
The reported flex bytes are part of flexible payload.

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_mbuf/rte_mbuf.h | 17 ++++++++++++++---
 1 file changed, 14 insertions(+), 3 deletions(-)

diff --git a/lib/librte_mbuf/rte_mbuf.h b/lib/librte_mbuf/rte_mbuf.h
index f5f8658..5899e5c 100644
--- a/lib/librte_mbuf/rte_mbuf.h
+++ b/lib/librte_mbuf/rte_mbuf.h
@@ -77,7 +77,7 @@ extern "C" {
  */
 #define PKT_RX_VLAN_PKT      (1ULL << 0)  /**< RX packet is a 802.1q VLAN packet. */
 #define PKT_RX_RSS_HASH      (1ULL << 1)  /**< RX packet with RSS hash result. */
-#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR infos. */
+#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR match indicate. */
 #define PKT_RX_L4_CKSUM_BAD  (1ULL << 3)  /**< L4 cksum of RX pkt. is not OK. */
 #define PKT_RX_IP_CKSUM_BAD  (1ULL << 4)  /**< IP cksum of RX pkt. is not OK. */
 #define PKT_RX_EIP_CKSUM_BAD (0ULL << 0)  /**< External IP header checksum error. */
@@ -93,6 +93,8 @@ extern "C" {
 #define PKT_RX_IEEE1588_TMST (1ULL << 10) /**< RX IEEE1588 L2/L4 timestamped packet.*/
 #define PKT_RX_TUNNEL_IPV4_HDR (1ULL << 11) /**< RX tunnel packet with IPv4 header.*/
 #define PKT_RX_TUNNEL_IPV6_HDR (1ULL << 12) /**< RX tunnel packet with IPv6 header. */
+#define PKT_RX_FDIR_ID       (1ULL << 13) /**< FD id reported if FDIR match. */
+#define PKT_RX_FDIR_FLX      (1ULL << 14) /**< Flexible bytes reported if FDIR match. */
 
 #define PKT_TX_VLAN_PKT      (1ULL << 55) /**< TX packet is a 802.1q VLAN packet. */
 #define PKT_TX_IP_CKSUM      (1ULL << 54) /**< IP cksum of TX pkt. computed by NIC. */
@@ -181,8 +183,17 @@ struct rte_mbuf {
 	union {
 		uint32_t rss;     /**< RSS hash result if RSS enabled */
 		struct {
-			uint16_t hash;
-			uint16_t id;
+			union {
+				struct {
+					uint16_t hash;
+					uint16_t id;
+				};
+				uint32_t lo;
+				/**< Second 4 flexible bytes */
+			};
+			uint32_t hi;
+			/**< First 4 flexible bytes or FD ID, dependent on
+			     PKT_RX_FDIR_* flag in ol_flags. */
 		} fdir;           /**< Filter identifier if FDIR enabled */
 		uint32_t sched;   /**< Hierarchical scheduler */
 		uint32_t usr;	  /**< User defined tags. See @rte_distributor_process */
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 10/22] i40e: report flow director match info to mbuf
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (8 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 11/22] testpmd: print extended fdir info in mbuf Jingjing Wu
                         ` (12 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

setting the FDIR flag and report FD_ID plus flex bytes in mbuf if match

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_rxtx.c | 63 ++++++++++++++++++++++++++++++++++++++---
 1 file changed, 59 insertions(+), 4 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_rxtx.c b/lib/librte_pmd_i40e/i40e_rxtx.c
index 1c5cfd6..cce6911 100644
--- a/lib/librte_pmd_i40e/i40e_rxtx.c
+++ b/lib/librte_pmd_i40e/i40e_rxtx.c
@@ -105,6 +105,10 @@ i40e_rxd_status_to_pkt_flags(uint64_t qword)
 					I40E_RX_DESC_FLTSTAT_RSS_HASH) ==
 			I40E_RX_DESC_FLTSTAT_RSS_HASH) ? PKT_RX_RSS_HASH : 0;
 
+	/* Check if FDIR Match */
+	flags |= (qword & (1 << I40E_RX_DESC_STATUS_FLM_SHIFT) ?
+							PKT_RX_FDIR : 0);
+
 	return flags;
 }
 
@@ -410,6 +414,48 @@ i40e_rxd_ptype_to_pkt_flags(uint64_t qword)
 	return ip_ptype_map[ptype];
 }
 
+#define I40E_RX_DESC_EXT_STATUS_FLEXBH_MASK   0x03
+#define I40E_RX_DESC_EXT_STATUS_FLEXBH_FD_ID  0x01
+#define I40E_RX_DESC_EXT_STATUS_FLEXBH_FLEX   0x02
+#define I40E_RX_DESC_EXT_STATUS_FLEXBL_MASK   0x03
+#define I40E_RX_DESC_EXT_STATUS_FLEXBL_FLEX   0x01
+
+static inline uint64_t
+i40e_rxd_build_fdir(volatile union i40e_rx_desc *rxdp, struct rte_mbuf *mb)
+{
+	uint64_t flags = 0;
+	uint16_t flexbh, flexbl;
+
+#ifdef RTE_LIBRTE_I40E_16BYTE_RX_DESC
+	mb->hash.fdir.hi =
+		rte_le_to_cpu_32(rxdp->wb.qword0.hi_dword.fd);
+	flags |= PKT_RX_FDIR_ID;
+#else
+	flexbh = (rte_le_to_cpu_32(rxdp->wb.qword2.ext_status) >>
+		I40E_RX_DESC_EXT_STATUS_FLEXBH_SHIFT) &
+		I40E_RX_DESC_EXT_STATUS_FLEXBH_MASK;
+	flexbl = (rte_le_to_cpu_32(rxdp->wb.qword2.ext_status) >>
+		I40E_RX_DESC_EXT_STATUS_FLEXBL_SHIFT) &
+		I40E_RX_DESC_EXT_STATUS_FLEXBL_MASK;
+
+
+	if (flexbh == I40E_RX_DESC_EXT_STATUS_FLEXBH_FD_ID) {
+		mb->hash.fdir.hi =
+			rte_le_to_cpu_32(rxdp->wb.qword3.hi_dword.fd_id);
+		flags |= PKT_RX_FDIR_ID;
+	} else if (flexbh == I40E_RX_DESC_EXT_STATUS_FLEXBH_FLEX) {
+		mb->hash.fdir.hi =
+			rte_le_to_cpu_32(rxdp->wb.qword3.hi_dword.flex_bytes_hi);
+		flags |= PKT_RX_FDIR_FLX;
+	}
+	if (flexbl == I40E_RX_DESC_EXT_STATUS_FLEXBL_FLEX) {
+		mb->hash.fdir.lo =
+			rte_le_to_cpu_32(rxdp->wb.qword3.lo_dword.flex_bytes_lo);
+		flags |= PKT_RX_FDIR_FLX;
+	}
+#endif
+	return flags;
+}
 static inline void
 i40e_txd_enable_checksum(uint64_t ol_flags,
 			uint32_t *td_cmd,
@@ -661,14 +707,17 @@ i40e_rx_scan_hw_ring(struct i40e_rx_queue *rxq)
 			pkt_flags = i40e_rxd_status_to_pkt_flags(qword1);
 			pkt_flags |= i40e_rxd_error_to_pkt_flags(qword1);
 			pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
-			mb->ol_flags = pkt_flags;
 
 			mb->packet_type = (uint16_t)((qword1 &
 					I40E_RXD_QW1_PTYPE_MASK) >>
 					I40E_RXD_QW1_PTYPE_SHIFT);
 			if (pkt_flags & PKT_RX_RSS_HASH)
 				mb->hash.rss = rte_le_to_cpu_32(\
-					rxdp->wb.qword0.hi_dword.rss);
+					rxdp[j].wb.qword0.hi_dword.rss);
+			if (pkt_flags & PKT_RX_FDIR)
+				pkt_flags |= i40e_rxd_build_fdir(&rxdp[j], mb);
+
+			mb->ol_flags = pkt_flags;
 		}
 
 		for (j = 0; j < I40E_LOOK_AHEAD; j++)
@@ -903,10 +952,13 @@ i40e_recv_pkts(void *rx_queue, struct rte_mbuf **rx_pkts, uint16_t nb_pkts)
 		pkt_flags |= i40e_rxd_ptype_to_pkt_flags(qword1);
 		rxm->packet_type = (uint16_t)((qword1 & I40E_RXD_QW1_PTYPE_MASK) >>
 				I40E_RXD_QW1_PTYPE_SHIFT);
-		rxm->ol_flags = pkt_flags;
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR)
+			pkt_flags |= i40e_rxd_build_fdir(&rxd, rxm);
+
+		rxm->ol_flags = pkt_flags;
 
 		rx_pkts[nb_rx++] = rxm;
 	}
@@ -1060,10 +1112,13 @@ i40e_recv_scattered_pkts(void *rx_queue,
 		first_seg->packet_type = (uint16_t)((qword1 &
 					I40E_RXD_QW1_PTYPE_MASK) >>
 					I40E_RXD_QW1_PTYPE_SHIFT);
-		first_seg->ol_flags = pkt_flags;
 		if (pkt_flags & PKT_RX_RSS_HASH)
 			rxm->hash.rss =
 				rte_le_to_cpu_32(rxd.wb.qword0.hi_dword.rss);
+		if (pkt_flags & PKT_RX_FDIR)
+			pkt_flags |= i40e_rxd_build_fdir(&rxd, rxm);
+
+		first_seg->ol_flags = pkt_flags;
 
 		/* Prefetch data of first segment, if configured to do so. */
 		rte_prefetch0(RTE_PTR_ADD(first_seg->buf_addr,
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 11/22] testpmd: print extended fdir info in mbuf
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (9 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 10/22] i40e: report flow director match info to mbuf Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 12/22] i40e: implement operation to flush flow director table Jingjing Wu
                         ` (11 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

Extended fdir info is printed in rxonly fwd engine when fdir match.

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 app/test-pmd/rxonly.c | 14 +++++++++++---
 1 file changed, 11 insertions(+), 3 deletions(-)

diff --git a/app/test-pmd/rxonly.c b/app/test-pmd/rxonly.c
index 9ad1df6..88b65bc 100644
--- a/app/test-pmd/rxonly.c
+++ b/app/test-pmd/rxonly.c
@@ -167,10 +167,18 @@ pkt_burst_receive(struct fwd_stream *fs)
 		if (ol_flags & PKT_RX_RSS_HASH) {
 			printf(" - RSS hash=0x%x", (unsigned) mb->hash.rss);
 			printf(" - RSS queue=0x%x",(unsigned) fs->rx_queue);
+		} else if (ol_flags & PKT_RX_FDIR) {
+			printf(" - FDIR matched ");
+			if (ol_flags & PKT_RX_FDIR_ID)
+				printf("ID=0x%x",
+				       mb->hash.fdir.hi);
+			else if (ol_flags & PKT_RX_FDIR_FLX)
+				printf("flex bytes=0x%08x %08x",
+				       mb->hash.fdir.hi, mb->hash.fdir.lo);
+			else
+				printf("hash=0x%x ID=0x%x ",
+				       mb->hash.fdir.hash, mb->hash.fdir.id);
 		}
-		else if (ol_flags & PKT_RX_FDIR)
-			printf(" - FDIR hash=0x%x - FDIR id=0x%x ",
-			       mb->hash.fdir.hash, mb->hash.fdir.id);
 		if (ol_flags & PKT_RX_VLAN_PKT)
 			printf(" - VLAN tci=0x%x", mb->vlan_tci);
 		if (is_encapsulation) {
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 12/22] i40e: implement operation to flush flow director table
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (10 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 11/22] testpmd: print extended fdir info in mbuf Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 13/22] testpmd: add test command " Jingjing Wu
                         ` (10 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

implement operation to flush flow director table

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 7 +++++--
 1 file changed, 5 insertions(+), 2 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 5205530..93aa8a1 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -832,7 +832,7 @@ i40e_fdir_flush(struct rte_eth_dev *dev)
 	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
 	uint32_t reg;
 	uint16_t guarant_cnt, best_cnt;
-	int i;
+	uint16_t i;
 
 	I40E_WRITE_REG(hw, I40E_PFQF_CTL_1, I40E_PFQF_CTL_1_CLEARFDTABLE_MASK);
 	I40E_WRITE_FLUSH(hw);
@@ -881,7 +881,7 @@ i40e_fdir_ctrl_func(struct rte_eth_dev *dev,
 		return ret;
 	}
 
-	if (arg == NULL)
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_FLUSH)
 		return -EINVAL;
 
 	switch (filter_op) {
@@ -895,6 +895,9 @@ i40e_fdir_ctrl_func(struct rte_eth_dev *dev,
 			(struct rte_eth_fdir_filter *)arg,
 			FALSE);
 		break;
+	case RTE_ETH_FILTER_FLUSH:
+		ret = i40e_fdir_flush(dev);
+		break;
 	default:
 		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
 		ret = -EINVAL;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 13/22] testpmd: add test command to flush flow director table
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (11 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 12/22] i40e: implement operation to flush flow director table Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 14/22] ethdev: define structures for getting flow director information Jingjing Wu
                         ` (9 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

Test command is added to flush flow director table

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 49 +++++++++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 49 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 91f6388..066769f 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -706,6 +706,9 @@ static void cmd_help_long_parsed(void *parsed_result,
 			" flexbytes (flexbytes_value) (drop|fwd)"
 			" queue (queue_id) fd_id (fd_id_value)\n"
 			"    Add/Del a SCTP type flow director filter.\n\n"
+
+			"flush_flow_director (port_id)\n"
+			"    Flush all flow director entries of a device.\n\n"
 		);
 	}
 }
@@ -8123,6 +8126,51 @@ cmdline_parse_inst_t cmd_add_del_sctp_flow_director = {
 	},
 };
 
+struct cmd_flush_flow_director_result {
+	cmdline_fixed_string_t flush_flow_director;
+	uint8_t port_id;
+};
+
+cmdline_parse_token_string_t cmd_flush_flow_director_flush =
+	TOKEN_STRING_INITIALIZER(struct cmd_flush_flow_director_result,
+				 flush_flow_director, "flush_flow_director");
+cmdline_parse_token_num_t cmd_flush_flow_director_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flush_flow_director_result,
+			      port_id, UINT8);
+
+static void
+cmd_flush_flow_director_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_result *res = parsed_result;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		printf("flow director is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	ret = rte_eth_dev_filter_ctrl(res->port_id, RTE_ETH_FILTER_FDIR,
+			RTE_ETH_FILTER_FLUSH, NULL);
+	if (ret < 0)
+		printf("flow director table flushing error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_inst_t cmd_flush_flow_director = {
+	.f = cmd_flush_flow_director_parsed,
+	.data = NULL,
+	.help_str = "flush all flow director entries of a device on NIC",
+	.tokens = {
+		(void *)&cmd_flush_flow_director_flush,
+		(void *)&cmd_flush_flow_director_port_id,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8255,6 +8303,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_ip_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
+	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
 	NULL,
 };
 
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 14/22] ethdev: define structures for getting flow director information
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (12 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 13/22] testpmd: add test command " Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 15/22] i40e: implement operations to get fdir info Jingjing Wu
                         ` (8 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

define structures for getting flow director information includes:
 - mode
 - supported flow types
 - table space
 - flexible payload size and granularity
 - configured flexible payload and mask information

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 92 ++++++++++++++++++++++++++++++++++++++++-
 lib/librte_ether/rte_ethdev.h   |  9 ----
 2 files changed, 90 insertions(+), 11 deletions(-)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 9856842..b05d9eb 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -69,8 +69,7 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_FLUSH,    /**< flush all entries */
 	RTE_ETH_FILTER_GET,      /**< get filter entry */
 	RTE_ETH_FILTER_SET,      /**< configurations */
-	RTE_ETH_FILTER_INFO,
-	/**< get information of filter, such as status or statistics */
+	RTE_ETH_FILTER_INFO,     /**< retrieve information */
 	RTE_ETH_FILTER_OP_MAX
 };
 
@@ -322,6 +321,95 @@ struct rte_eth_fdir_filter {
 	struct rte_eth_fdir_action action;  /**< Action taken when match */
 };
 
+/**
+ * Payload type
+ */
+enum rte_eth_payload_type {
+	RTE_ETH_PAYLOAD_UNKNOWN = 0,
+	RTE_ETH_L2_PAYLOAD,
+	RTE_ETH_L3_PAYLOAD,
+	RTE_ETH_L4_PAYLOAD,
+	RTE_ETH_PAYLOAD_MAX = 8,
+};
+
+/**
+ * A structure used to select bytes extracted from the protocol layers to
+ * flexible payload for filter
+ */
+struct rte_eth_flex_payload_cfg {
+	enum rte_eth_payload_type type;  /**< Payload type */
+	uint16_t src_offset[RTE_ETH_FDIR_MAX_FLEXLEN];
+	/**< Offset in bytes from the beginning of packet's payload
+	     src_offset[i] indicates the flexbyte i's offset in original
+	     packet payload. This value should be less than
+	     flex_payload_limit in struct rte_eth_fdir_info.*/
+};
+
+/**
+ * A structure used to define FDIR masks for flexible payload
+ * for each flow type
+ */
+struct rte_eth_fdir_flex_mask {
+	enum rte_eth_flow_type flow_type;  /**< Flow type */
+	uint8_t mask[RTE_ETH_FDIR_MAX_FLEXLEN];
+	/**< Mask for the whole flexible payload */
+};
+
+/**
+ * A structure used to define all flexible payload related setting
+ * include flexpay load and flex mask
+ */
+struct rte_eth_fdir_flex_conf {
+	uint16_t nb_payloads;  /**< The number of following payload cfg */
+	uint16_t nb_flexmasks; /**< The number of following mask */
+	struct rte_eth_flex_payload_cfg flex_set[RTE_ETH_PAYLOAD_MAX];
+	/**< Flex payload configuration for each payload type */
+	struct rte_eth_fdir_flex_mask flex_mask[RTE_ETH_FLOW_TYPE_MAX];
+	/**< Flex mask configuration for each flow type */
+};
+
+/**
+ *  Flow Director setting modes: none, signature or perfect.
+ */
+enum rte_fdir_mode {
+	RTE_FDIR_MODE_NONE      = 0, /**< Disable FDIR support. */
+	RTE_FDIR_MODE_SIGNATURE,     /**< Enable FDIR signature filter mode. */
+	RTE_FDIR_MODE_PERFECT,       /**< Enable FDIR perfect filter mode. */
+};
+
+/**
+ * A structure used to get the information of flow director filter.
+ * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_INFO operation.
+ * It includes the mode, flexible payload configuration information,
+ * capabilities and supported flow types, flexible payload characters.
+ * It can be gotten to help taking specific configurations per device.
+ */
+struct rte_eth_fdir_info {
+	enum rte_fdir_mode mode;     /**< Flow director mode */
+	struct rte_eth_fdir_flex_conf flex_conf;
+	/**< Flex payload configuration information */
+	uint32_t guarant_spc;          /**< Guaranteed spaces.*/
+	uint32_t best_spc;             /**< Best effort spaces.*/
+	uint32_t flow_types_mask[RTE_ETH_FLOW_TYPE_MAX / sizeof(uint32_t)];
+	/**< Bit mask for every supported flow type. */
+	uint32_t max_flexpayload;      /**< Total flex payload in bytes. */
+	uint32_t flex_payload_unit;
+	/**< Flexible payload unit in bytes. Size and alignments of all flex
+	     payload segments should be multiplies of this value. */
+	uint32_t max_flex_payload_segment_num;
+	/**< Max number of flexible payload continuous segments.
+	     Each segment should be a multiple of flex_payload_unit.*/
+	uint16_t flex_payload_limit;
+	/**< Maximum src_offset in bytes allowed. It indicates that
+	     src_offset[i] in struct rte_eth_flex_payload_cfg should be
+	     less than this value. */
+	uint32_t flex_bitmask_unit;
+	/**< Flex bitmask unit in bytes. Size of flex bitmasks should
+	     be a multiply of this value. */
+	uint32_t max_flex_bitmask_num;
+	/**< Max supported size of flex bitmasks in flex_bitmask_unit */
+};
+
 #ifdef __cplusplus
 }
 #endif
diff --git a/lib/librte_ether/rte_ethdev.h b/lib/librte_ether/rte_ethdev.h
index c29525b..b658cf4 100644
--- a/lib/librte_ether/rte_ethdev.h
+++ b/lib/librte_ether/rte_ethdev.h
@@ -683,15 +683,6 @@ struct rte_eth_pfc_conf {
 };
 
 /**
- *  Flow Director setting modes: none (default), signature or perfect.
- */
-enum rte_fdir_mode {
-	RTE_FDIR_MODE_NONE      = 0, /**< Disable FDIR support. */
-	RTE_FDIR_MODE_SIGNATURE,     /**< Enable FDIR signature filter mode. */
-	RTE_FDIR_MODE_PERFECT,       /**< Enable FDIR perfect filter mode. */
-};
-
-/**
  *  Memory space that can be configured to store Flow Director filters
  *  in the board memory.
  */
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 15/22] i40e: implement operations to get fdir info
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (13 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 14/22] ethdev: define structures for getting flow director information Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 16/22] ethdev: define structures for getting flow director statistics Jingjing Wu
                         ` (7 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

implement operation to get flow director information in i40e pmd driver, includes
 - mode
 - supported flow types
 - table space
 - flexible payload size and granularity
 - configured flexible payload and mask information

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.h |   1 +
 lib/librte_pmd_i40e/i40e_fdir.c   | 145 ++++++++++++++++++++++++++++++++++++++
 2 files changed, 146 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index fbce86a..f3ef65f 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -67,6 +67,7 @@ enum i40e_flxpld_layer_idx {
 #define I40E_MAX_FLXPLD_FIED        3  /* max number of flex payload fields */
 #define I40E_FDIR_BITMASK_NUM_WORD  2  /* max number of bitmask words */
 #define I40E_FDIR_MAX_FLEXWORD_NUM  8  /* max number of flexpayload words */
+#define I40E_FDIR_MAX_FLEX_LEN      16 /* len in bytes of flex payload */
 
 /* i40e flags */
 #define I40E_FLAG_RSS                   (1ULL << 0)
diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 93aa8a1..2edb3a6 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -80,8 +80,34 @@
 #define I40E_COUNTER_PF           2
 /* Statistic counter index for one pf */
 #define I40E_COUNTER_INDEX_FDIR(pf_id)   (0 + (pf_id) * I40E_COUNTER_PF)
+#define I40E_MAX_FLX_SOURCE_OFF           480
 #define I40E_FLX_OFFSET_IN_FIELD_VECTOR   50
 
+#define NONUSE_FLX_PIT_DEST_OFF 63
+#define NONUSE_FLX_PIT_FSIZE    1
+#define MK_FLX_PIT(src_offset, fsize, dst_offset) ( \
+	(((src_offset) << I40E_PRTQF_FLX_PIT_SOURCE_OFF_SHIFT) & \
+		I40E_PRTQF_FLX_PIT_SOURCE_OFF_MASK) | \
+	(((fsize) << I40E_PRTQF_FLX_PIT_FSIZE_SHIFT) & \
+			I40E_PRTQF_FLX_PIT_FSIZE_MASK) | \
+	((((dst_offset) + I40E_FLX_OFFSET_IN_FIELD_VECTOR) << \
+			I40E_PRTQF_FLX_PIT_DEST_OFF_SHIFT) & \
+			I40E_PRTQF_FLX_PIT_DEST_OFF_MASK))
+
+#define I40E_FDIR_FLOW_TYPES ( \
+	(1 << RTE_ETH_FLOW_TYPE_UDPV4) | \
+	(1 << RTE_ETH_FLOW_TYPE_TCPV4) | \
+	(1 << RTE_ETH_FLOW_TYPE_SCTPV4) | \
+	(1 << RTE_ETH_FLOW_TYPE_IPV4_OTHER) | \
+	(1 << RTE_ETH_FLOW_TYPE_FRAG_IPV4) | \
+	(1 << RTE_ETH_FLOW_TYPE_UDPV6) | \
+	(1 << RTE_ETH_FLOW_TYPE_TCPV6) | \
+	(1 << RTE_ETH_FLOW_TYPE_SCTPV6) | \
+	(1 << RTE_ETH_FLOW_TYPE_IPV6_OTHER) | \
+	(1 << RTE_ETH_FLOW_TYPE_FRAG_IPV6))
+
+#define I40E_FLEX_WORD_MASK(off) (0x80 >> (off))
+
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     const struct rte_eth_fdir_input *fdir_input,
@@ -94,6 +120,8 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 			const struct rte_eth_fdir_filter *filter,
 			bool add);
 static int i40e_fdir_flush(struct rte_eth_dev *dev);
+static void i40e_fdir_info_get(struct rte_eth_dev *dev,
+			   struct rte_eth_fdir_info *fdir);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -861,6 +889,120 @@ i40e_fdir_flush(struct rte_eth_dev *dev)
 	return 0;
 }
 
+static inline void
+i40e_fdir_info_get_flex_set(struct i40e_pf *pf,
+			struct rte_eth_flex_payload_cfg *flex_set,
+			uint16_t *num)
+{
+	struct i40e_fdir_flex_pit *flex_pit;
+	struct rte_eth_flex_payload_cfg *ptr = flex_set;
+	uint16_t src, dst, size, j, k;
+	uint8_t i, layer_idx;
+
+	for (layer_idx = I40E_FLXPLD_L2_IDX;
+	     layer_idx <= I40E_FLXPLD_L4_IDX;
+	     layer_idx++) {
+		if (layer_idx == I40E_FLXPLD_L2_IDX)
+			ptr->type = RTE_ETH_L2_PAYLOAD;
+		else if (layer_idx == I40E_FLXPLD_L3_IDX)
+			ptr->type = RTE_ETH_L3_PAYLOAD;
+		else if (layer_idx == I40E_FLXPLD_L4_IDX)
+			ptr->type = RTE_ETH_L4_PAYLOAD;
+
+		for (i = 0; i < I40E_MAX_FLXPLD_FIED; i++) {
+			flex_pit = &pf->fdir.flex_set[layer_idx *
+				I40E_MAX_FLXPLD_FIED + i];
+			if (flex_pit->size == 0)
+				continue;
+			src = flex_pit->src_offset * sizeof(uint16_t);
+			dst = flex_pit->dst_offset * sizeof(uint16_t);
+			size = flex_pit->size * sizeof(uint16_t);
+			for (j = src, k = dst; j < src + size; j++, k++)
+				ptr->src_offset[k] = j;
+		}
+		(*num)++;
+		ptr++;
+	}
+}
+
+static inline void
+i40e_fdir_info_get_flex_mask(struct i40e_pf *pf,
+			struct rte_eth_fdir_flex_mask *flex_mask,
+			uint16_t *num)
+{
+	struct i40e_fdir_flex_mask *mask;
+	struct rte_eth_fdir_flex_mask *ptr = flex_mask;
+	enum rte_eth_flow_type flow_type;
+	uint8_t i, j;
+	uint16_t off_bytes, mask_tmp;
+
+	for (i = I40E_FILTER_PCTYPE_NONF_IPV4_UDP;
+	     i <= I40E_FILTER_PCTYPE_FRAG_IPV6;
+	     i++) {
+		mask =  &pf->fdir.flex_mask[i];
+		if (!I40E_VALID_PCTYPE((enum i40e_filter_pctype)i))
+			continue;
+		flow_type = i40e_pctype_to_flowtype((enum i40e_filter_pctype)i);
+		for (j = 0; j < I40E_FDIR_MAX_FLEXWORD_NUM; j++) {
+			if (mask->word_mask & I40E_FLEX_WORD_MASK(j)) {
+				ptr->mask[j * sizeof(uint16_t)] = UINT8_MAX;
+				ptr->mask[j * sizeof(uint16_t) + 1] = UINT8_MAX;
+			} else {
+				ptr->mask[j * sizeof(uint16_t)] = 0x0;
+				ptr->mask[j * sizeof(uint16_t) + 1] = 0x0;
+			}
+		}
+		for (j = 0; j < I40E_FDIR_BITMASK_NUM_WORD; j++) {
+			off_bytes = mask->bitmask[j].offset * sizeof(uint16_t);
+			mask_tmp = ~mask->bitmask[j].mask;
+			ptr->mask[off_bytes] &= I40E_HI_BYTE(mask_tmp);
+			ptr->mask[off_bytes + 1] &= I40E_LO_BYTE(mask_tmp);
+		}
+		ptr->flow_type = flow_type;
+		ptr++;
+		(*num)++;
+	}
+}
+
+/*
+ * i40e_fdir_info_get - get information of Flow Director
+ * @pf: ethernet device to get info from
+ * @fdir: a pointer to a structure of type *rte_eth_fdir_info* to be filled with
+ *    the flow director information.
+ */
+static void
+i40e_fdir_info_get(struct rte_eth_dev *dev, struct rte_eth_fdir_info *fdir)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint16_t num_flex_set = 0;
+	uint16_t num_flex_mask = 0;
+
+	fdir->mode = (pf->flags & I40E_FLAG_FDIR) ?
+			RTE_FDIR_MODE_PERFECT : RTE_FDIR_MODE_NONE;
+	fdir->guarant_spc =
+		(uint32_t)hw->func_caps.fd_filters_guaranteed;
+	fdir->best_spc =
+		(uint32_t)hw->func_caps.fd_filters_best_effort;
+	fdir->max_flexpayload = I40E_FDIR_MAX_FLEX_LEN;
+	fdir->flow_types_mask[0] = I40E_FDIR_FLOW_TYPES;
+	fdir->flex_payload_unit = sizeof(uint16_t);
+	fdir->flex_bitmask_unit = sizeof(uint16_t);
+	fdir->max_flex_payload_segment_num = I40E_MAX_FLXPLD_FIED;
+	fdir->flex_payload_limit = I40E_MAX_FLX_SOURCE_OFF;
+	fdir->max_flex_bitmask_num = I40E_FDIR_BITMASK_NUM_WORD;
+
+	i40e_fdir_info_get_flex_set(pf,
+				fdir->flex_conf.flex_set,
+				&num_flex_set);
+	i40e_fdir_info_get_flex_mask(pf,
+				fdir->flex_conf.flex_mask,
+				&num_flex_mask);
+
+	fdir->flex_conf.nb_payloads = num_flex_set;
+	fdir->flex_conf.nb_flexmasks = num_flex_mask;
+}
+
 /*
  * i40e_fdir_ctrl_func - deal with all operations on flow director.
  * @pf: board private structure
@@ -898,6 +1040,9 @@ i40e_fdir_ctrl_func(struct rte_eth_dev *dev,
 	case RTE_ETH_FILTER_FLUSH:
 		ret = i40e_fdir_flush(dev);
 		break;
+	case RTE_ETH_FILTER_INFO:
+		i40e_fdir_info_get(dev, (struct rte_eth_fdir_info *)arg);
+		break;
 	default:
 		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
 		ret = -EINVAL;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 16/22] ethdev: define structures for getting flow director statistics
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (14 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 15/22] i40e: implement operations to get fdir info Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 17/22] i40e: implement operations to get fdir statistics Jingjing Wu
                         ` (6 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

define structures for getting flow director statistics

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h | 20 ++++++++++++++++++++
 1 file changed, 20 insertions(+)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index b05d9eb..7fa7103 100644
--- a/lib/librte_ether/rte_eth_ctrl.h
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -70,6 +70,7 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_GET,      /**< get filter entry */
 	RTE_ETH_FILTER_SET,      /**< configurations */
 	RTE_ETH_FILTER_INFO,     /**< retrieve information */
+	RTE_ETH_FILTER_STATS,    /**< retrieve statistics */
 	RTE_ETH_FILTER_OP_MAX
 };
 
@@ -410,6 +411,25 @@ struct rte_eth_fdir_info {
 	/**< Max supported size of flex bitmasks in flex_bitmask_unit */
 };
 
+/**
+ * A structure used to define the statistics of flow director.
+ * It supports RTE_ETH_FILTER_FDIR with RTE_ETH_FILTER_STATS operation.
+ */
+struct rte_eth_fdir_stats {
+	uint32_t collision;    /**< Number of filters with collision. */
+	uint32_t free;         /**< Number of free filters. */
+	uint32_t maxhash;
+	/**< The lookup hash value of the added filter that updated the value
+	   of the MAXLEN field */
+	uint32_t maxlen;       /**< Longest linked list of filters. */
+	uint64_t add;          /**< Number of added filters. */
+	uint64_t remove;       /**< Number of removed filters. */
+	uint64_t f_add;        /**< Number of failed added filters. */
+	uint64_t f_remove;     /**< Number of failed removed filters. */
+	uint32_t guarant_cnt;  /**< Number of filters in guaranteed spaces. */
+	uint32_t best_cnt;     /**< Number of filters in best effort spaces. */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 17/22] i40e: implement operations to get fdir statistics
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (15 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 16/22] ethdev: define structures for getting flow director statistics Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 18/22] testpmd: display fdir info Jingjing Wu
                         ` (5 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

implement operation to get flow director statistics in i40e pmd driver

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 27 +++++++++++++++++++++++++++
 1 file changed, 27 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index 2edb3a6..c452a80 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -122,6 +122,8 @@ static int i40e_fdir_filter_programming(struct i40e_pf *pf,
 static int i40e_fdir_flush(struct rte_eth_dev *dev);
 static void i40e_fdir_info_get(struct rte_eth_dev *dev,
 			   struct rte_eth_fdir_info *fdir);
+static void i40e_fdir_stats_get(struct rte_eth_dev *dev,
+			   struct rte_eth_fdir_stats *stat);
 
 static int
 i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq)
@@ -1004,6 +1006,28 @@ i40e_fdir_info_get(struct rte_eth_dev *dev, struct rte_eth_fdir_info *fdir)
 }
 
 /*
+ * i40e_fdir_stat_get - get statistics of Flow Director
+ * @pf: ethernet device to get info from
+ * @stat: a pointer to a structure of type *rte_eth_fdir_stats* to be filled with
+ *    the flow director statistics.
+ */
+static void
+i40e_fdir_stats_get(struct rte_eth_dev *dev, struct rte_eth_fdir_stats *stat)
+{
+	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	uint32_t fdstat;
+
+	fdstat = I40E_READ_REG(hw, I40E_PFQF_FDSTAT);
+	stat->guarant_cnt =
+		(uint32_t)((fdstat & I40E_PFQF_FDSTAT_GUARANT_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_GUARANT_CNT_SHIFT);
+	stat->best_cnt =
+		(uint32_t)((fdstat & I40E_PFQF_FDSTAT_BEST_CNT_MASK) >>
+			    I40E_PFQF_FDSTAT_BEST_CNT_SHIFT);
+}
+
+/*
  * i40e_fdir_ctrl_func - deal with all operations on flow director.
  * @pf: board private structure
  * @filter_op:operation will be taken.
@@ -1043,6 +1067,9 @@ i40e_fdir_ctrl_func(struct rte_eth_dev *dev,
 	case RTE_ETH_FILTER_INFO:
 		i40e_fdir_info_get(dev, (struct rte_eth_fdir_info *)arg);
 		break;
+	case RTE_ETH_FILTER_STATS:
+		i40e_fdir_stats_get(dev, (struct rte_eth_fdir_stats *)arg);
+		break;
 	default:
 		PMD_DRV_LOG(ERR, "unknown operation %u.", filter_op);
 		ret = -EINVAL;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 18/22] testpmd: display fdir info
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (16 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 17/22] i40e: implement operations to get fdir statistics Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 19/22] ethdev: add flexible payload setting in eth_conf Jingjing Wu
                         ` (4 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

display flow director's information, includes
 - statistics
 - configuration
 - capability

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 app/test-pmd/config.c | 141 +++++++++++++++++++++++++++++++++++++++++++++-----
 1 file changed, 128 insertions(+), 13 deletions(-)

diff --git a/app/test-pmd/config.c b/app/test-pmd/config.c
index b102b72..b7e4412 100644
--- a/app/test-pmd/config.c
+++ b/app/test-pmd/config.c
@@ -96,6 +96,20 @@
 
 #include "testpmd.h"
 
+static const char *flowtype_str[RTE_ETH_FLOW_TYPE_MAX] = {
+	NULL,
+	"udp4",
+	"tcp4",
+	"sctp4",
+	"ip4",
+	"ip4-frag",
+	"udp6",
+	"tcp6",
+	"sctp6",
+	"ip6",
+	"ip6-frag",
+};
+
 static void
 print_ethaddr(const char *name, struct ether_addr *eth_addr)
 {
@@ -1808,29 +1822,130 @@ fdir_remove_signature_filter(portid_t port_id,
 
 }
 
+static inline void
+print_fdir_flex_payload(struct rte_eth_fdir_flex_conf *flex_conf)
+{
+	struct rte_eth_flex_payload_cfg *cfg;
+	int i, j;
+
+	for (i = 0; i < flex_conf->nb_payloads; i++) {
+		cfg = &flex_conf->flex_set[i];
+		if (cfg->type == RTE_ETH_L2_PAYLOAD)
+			printf("\n    L2_PAYLOAD:  ");
+		else if (cfg->type == RTE_ETH_L3_PAYLOAD)
+			printf("\n    L3_PAYLOAD:  ");
+		else if (cfg->type == RTE_ETH_L4_PAYLOAD)
+			printf("\n    L4_PAYLOAD:  ");
+		else
+			printf("\n    UNKNOWN PAYLOAD(%u):  ", cfg->type);
+		for (j = 0; j < RTE_ETH_FDIR_MAX_FLEXLEN; j++)
+			printf("  %-5u", cfg->src_offset[j]);
+	}
+	printf("\n");
+}
+
+static inline void
+print_fdir_flex_mask(struct rte_eth_fdir_flex_conf *flex_conf)
+{
+	struct rte_eth_fdir_flex_mask *mask;
+	int i, j;
+
+	for (i = 0; i < flex_conf->nb_flexmasks; i++) {
+		mask = &flex_conf->flex_mask[i];
+		printf("\n    %s:\t", flowtype_str[mask->flow_type]);
+		for (j = 0; j < RTE_ETH_FDIR_MAX_FLEXLEN; j++)
+			printf(" %02x", mask->mask[j]);
+	}
+	printf("\n");
+}
+
+static inline void
+print_fdir_flow_type(uint32_t flow_types_mask)
+{
+	int i = 0;
+
+	for (i = RTE_ETH_FLOW_TYPE_UDPV4;
+	     i <= RTE_ETH_FLOW_TYPE_FRAG_IPV6;
+	     i++) {
+		if (flow_types_mask & (1 << i))
+			printf(" %s", flowtype_str[i]);
+	}
+	printf("\n");
+}
+
 void
 fdir_get_infos(portid_t port_id)
 {
-	struct rte_eth_fdir fdir_infos;
+	struct rte_eth_fdir_stats fdir_stat;
+	struct rte_eth_fdir_info fdir_info;
+	int ret;
 
 	static const char *fdir_stats_border = "########################";
 
 	if (port_id_is_invalid(port_id))
 		return;
-
-	rte_eth_dev_fdir_get_infos(port_id, &fdir_infos);
-
+	ret = rte_eth_dev_filter_supported(port_id, RTE_ETH_FILTER_FDIR);
+	if (ret < 0) {
+		/* use the old fdir APIs to get info */
+		struct rte_eth_fdir fdir;
+		memset(&fdir, 0, sizeof(fdir));
+		ret = rte_eth_dev_fdir_get_infos(port_id, &fdir);
+		if (ret < 0) {
+			printf("\n getting fdir info fails on port %-2d\n",
+				port_id);
+			return;
+		}
+		printf("\n  %s FDIR infos for port %-2d     %s\n",
+			fdir_stats_border, port_id, fdir_stats_border);
+		printf("  collision: %-10"PRIu64"  free:     %"PRIu64"\n"
+		       "  maxhash:   %-10"PRIu64"  maxlen:   %"PRIu64"\n"
+		       "  add:	     %-10"PRIu64"  remove:   %"PRIu64"\n"
+		       "  f_add:     %-10"PRIu64"  f_remove: %"PRIu64"\n",
+		       (uint64_t)(fdir.collision), (uint64_t)(fdir.free),
+		       (uint64_t)(fdir.maxhash), (uint64_t)(fdir.maxlen),
+		       fdir.add, fdir.remove, fdir.f_add, fdir.f_remove);
+		printf("  %s############################%s\n",
+		       fdir_stats_border, fdir_stats_border);
+		return;
+	}
+
+	memset(&fdir_info, 0, sizeof(fdir_info));
+	rte_eth_dev_filter_ctrl(port_id, RTE_ETH_FILTER_FDIR,
+			       RTE_ETH_FILTER_INFO, &fdir_info);
+	memset(&fdir_stat, 0, sizeof(fdir_stat));
+	rte_eth_dev_filter_ctrl(port_id, RTE_ETH_FILTER_FDIR,
+			       RTE_ETH_FILTER_STATS, &fdir_stat);
 	printf("\n  %s FDIR infos for port %-2d     %s\n",
 	       fdir_stats_border, port_id, fdir_stats_border);
-
-	printf("  collision: %-10"PRIu64"  free:     %"PRIu64"\n"
-	       "  maxhash:   %-10"PRIu64"  maxlen:   %"PRIu64"\n"
-	       "  add:       %-10"PRIu64"  remove:   %"PRIu64"\n"
-	       "  f_add:     %-10"PRIu64"  f_remove: %"PRIu64"\n",
-	       (uint64_t)(fdir_infos.collision), (uint64_t)(fdir_infos.free),
-	       (uint64_t)(fdir_infos.maxhash), (uint64_t)(fdir_infos.maxlen),
-	       fdir_infos.add, fdir_infos.remove,
-	       fdir_infos.f_add, fdir_infos.f_remove);
+	printf("  MODE: ");
+	if (fdir_info.mode == RTE_FDIR_MODE_PERFECT)
+			printf("  PERFECT\n");
+	else if (fdir_info.mode == RTE_FDIR_MODE_SIGNATURE)
+			printf("  SIGNATURE\n");
+	else
+			printf("  DISABLE\n");
+	printf("  SUPPORTED FLOW TYPE: ");
+	print_fdir_flow_type(fdir_info.flow_types_mask[0]);
+	printf("  FLEX PAYLOAD INFO:\n");
+	printf("  max_len:       %-10"PRIu32"  payload_limit: %-10"PRIu32"\n"
+	       "  payload_unit:  %-10"PRIu32"  payload_seg:   %-10"PRIu32"\n"
+	       "  bitmask_unit:  %-10"PRIu32"  bitmask_num:   %-10"PRIu32"\n",
+		fdir_info.max_flexpayload, fdir_info.flex_payload_limit,
+		fdir_info.flex_payload_unit,
+		fdir_info.max_flex_payload_segment_num,
+		fdir_info.flex_bitmask_unit, fdir_info.max_flex_bitmask_num);
+	if (fdir_info.flex_conf.nb_payloads > 0) {
+		printf("  FLEX PAYLOAD SRC OFFSET:");
+		print_fdir_flex_payload(&fdir_info.flex_conf);
+	}
+	if (fdir_info.flex_conf.nb_flexmasks > 0) {
+		printf("  FLEX MASK CFG:");
+		print_fdir_flex_mask(&fdir_info.flex_conf);
+	}
+	printf("  guarant_count: %-10"PRIu32"  best_count:    %-10"PRIu32"\n",
+	       fdir_stat.guarant_cnt, fdir_stat.best_cnt);
+	printf("  guarant_space: %-10"PRIu32"  best_space:    %-10"PRIu32"\n",
+	       fdir_info.guarant_spc, fdir_info.guarant_spc);
 	printf("  %s############################%s\n",
 	       fdir_stats_border, fdir_stats_border);
 }
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 19/22] ethdev: add flexible payload setting in eth_conf
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (17 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 18/22] testpmd: display fdir info Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 20/22] i40e: take flow director flexible payload configuration Jingjing Wu
                         ` (3 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

add flexible payload setting in eth_conf

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_ether/rte_ethdev.h | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/lib/librte_ether/rte_ethdev.h b/lib/librte_ether/rte_ethdev.h
index b658cf4..e14bbde 100644
--- a/lib/librte_ether/rte_ethdev.h
+++ b/lib/librte_ether/rte_ethdev.h
@@ -715,6 +715,8 @@ struct rte_fdir_conf {
 	uint8_t flexbytes_offset;
 	/** RX queue of packets matching a "drop" filter in perfect mode. */
 	uint8_t drop_queue;
+	struct rte_eth_fdir_flex_conf flex_conf;
+	/**< Flex payload configuration. */
 };
 
 /**
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 20/22] i40e: take flow director flexible payload configuration
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (18 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 19/22] ethdev: add flexible payload setting in eth_conf Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 21/22] testpmd: add test command to configure flexible mask Jingjing Wu
                         ` (2 subsequent siblings)
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

configure flexible payload and flex mask in i40e driver
It includes arguments verification and HW setting.

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_pmd_i40e/i40e_fdir.c | 283 ++++++++++++++++++++++++++++++++++++++++
 1 file changed, 283 insertions(+)

diff --git a/lib/librte_pmd_i40e/i40e_fdir.c b/lib/librte_pmd_i40e/i40e_fdir.c
index c452a80..54f3e24 100644
--- a/lib/librte_pmd_i40e/i40e_fdir.c
+++ b/lib/librte_pmd_i40e/i40e_fdir.c
@@ -109,6 +109,13 @@
 #define I40E_FLEX_WORD_MASK(off) (0x80 >> (off))
 
 static int i40e_fdir_rx_queue_init(struct i40e_rx_queue *rxq);
+static int i40e_check_fdir_flex_conf(
+	const struct rte_eth_fdir_flex_conf *conf);
+static void i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 const struct rte_eth_flex_payload_cfg *cfg);
+static void i40e_set_flex_mask_on_pctype(struct i40e_pf *pf,
+		enum i40e_filter_pctype pctype,
+		const struct rte_eth_fdir_flex_mask *mask_cfg);
 static int i40e_fdir_construct_pkt(struct i40e_pf *pf,
 				     const struct rte_eth_fdir_input *fdir_input,
 				     unsigned char *raw_pkt);
@@ -364,6 +371,261 @@ i40e_init_flx_pld(struct i40e_pf *pf)
 	}
 }
 
+#define I40E_WORD(hi, lo) (uint16_t)((((hi) << 8) & 0xFF00) | ((lo) & 0xFF))
+
+#define I40E_VALIDATE_FLEX_PIT(flex_pit1, flex_pit2) do { \
+	if ((flex_pit2).src_offset < \
+		(flex_pit1).src_offset + (flex_pit1).size) { \
+		PMD_DRV_LOG(ERR, "src_offset should be not" \
+			" less than than previous offset" \
+			" + previous FSIZE."); \
+		return -EINVAL; \
+	} \
+} while (0)
+
+/*
+ * i40e_srcoff_to_flx_pit - transform the src_offset into flex_pit structure,
+ * and the flex_pit will be sorted by it's src_offset value
+ */
+static inline uint16_t
+i40e_srcoff_to_flx_pit(const uint16_t *src_offset,
+			struct i40e_fdir_flex_pit *flex_pit)
+{
+	uint16_t src_tmp, size, num = 0;
+	uint16_t i, k, j = 0;
+
+	while (j < I40E_FDIR_MAX_FLEX_LEN) {
+		size = 1;
+		for (; j < I40E_FDIR_MAX_FLEX_LEN; j++) {
+			if (src_offset[j + 1] == src_offset[j] + 1)
+				size++;
+			else {
+				src_tmp = src_offset[j] + 1 - size;
+				/* the flex_pit need to be sort by scr_offset */
+				for (i = 0; i < num; i++) {
+					if (src_tmp < flex_pit[i].src_offset)
+						break;
+				}
+				/* if insert required, move backward */
+				for (k = num; k > i; k--)
+					flex_pit[k] = flex_pit[k - 1];
+				/* insert */
+				flex_pit[i].dst_offset = j + 1 - size;
+				flex_pit[i].src_offset = src_tmp;
+				flex_pit[i].size = size;
+				j++;
+				num++;
+				break;
+			}
+		}
+	}
+	return num;
+}
+
+/* i40e_check_fdir_flex_payload -check flex payload configuration arguments */
+static inline int
+i40e_check_fdir_flex_payload(const struct rte_eth_flex_payload_cfg *flex_cfg)
+{
+	struct i40e_fdir_flex_pit flex_pit[I40E_FDIR_MAX_FLEX_LEN];
+	uint16_t num, i;
+
+	for (i = 0; i < I40E_FDIR_MAX_FLEX_LEN; i++) {
+		if (flex_cfg->src_offset[i] >= I40E_MAX_FLX_SOURCE_OFF) {
+			PMD_DRV_LOG(ERR, "exceeds maxmial payload limit.");
+			return -EINVAL;
+		}
+	}
+
+	memset(flex_pit, 0, sizeof(flex_pit));
+	num = i40e_srcoff_to_flx_pit(flex_cfg->src_offset, flex_pit);
+	if (num > I40E_MAX_FLXPLD_FIED) {
+		PMD_DRV_LOG(ERR, "exceeds maxmial number of flex fields.");
+		return -EINVAL;
+	}
+	for (i = 0; i < num; i++) {
+		if (flex_pit[i].size & 0x01 || flex_pit[i].dst_offset & 0x01 ||
+			flex_pit[i].src_offset & 0x01) {
+			PMD_DRV_LOG(ERR, "flexpayload should be measured"
+				" in word");
+			return -EINVAL;
+		}
+		if (i != num - 1)
+			I40E_VALIDATE_FLEX_PIT(flex_pit[i], flex_pit[i + 1]);
+	}
+	return 0;
+}
+
+/*
+ * i40e_check_fdir_flex_conf -check if the flex payload and mask configuration
+ * arguments are valid
+ */
+static int
+i40e_check_fdir_flex_conf(const struct rte_eth_fdir_flex_conf *conf)
+{
+	const struct rte_eth_flex_payload_cfg *flex_cfg;
+	const struct rte_eth_fdir_flex_mask *flex_mask;
+	uint16_t mask_tmp;
+	uint8_t nb_bitmask;
+	uint16_t i, j;
+	int ret = 0;
+
+	if (conf == NULL) {
+		PMD_DRV_LOG(INFO, "NULL pointer.");
+		return -EINVAL;
+	}
+	/* check flexible payload setting configuration */
+	if (conf->nb_payloads > RTE_ETH_L4_PAYLOAD) {
+		PMD_DRV_LOG(ERR, "invalid number of payload setting.");
+		return -EINVAL;
+	}
+	for (i = 0; i < conf->nb_payloads; i++) {
+		flex_cfg = &conf->flex_set[i];
+		if (flex_cfg->type > RTE_ETH_L4_PAYLOAD) {
+			PMD_DRV_LOG(ERR, "invalid payload type.");
+			return -EINVAL;
+		}
+		ret = i40e_check_fdir_flex_payload(flex_cfg);
+		if (ret < 0) {
+			PMD_DRV_LOG(ERR, "invalid flex payload arguments.");
+			return -EINVAL;
+		}
+	}
+
+	/* check flex mask setting configuration */
+	if (conf->nb_flexmasks > RTE_ETH_FLOW_TYPE_FRAG_IPV6) {
+		PMD_DRV_LOG(ERR, "invalid number of flex masks.");
+		return -EINVAL;
+	}
+	for (i = 0; i < conf->nb_flexmasks; i++) {
+		flex_mask = &conf->flex_mask[i];
+		if (!I40E_VALID_FLOW_TYPE(flex_mask->flow_type)) {
+			PMD_DRV_LOG(WARNING, "invalid flow type.");
+			return -EINVAL;
+		}
+		nb_bitmask = 0;
+		for (j = 0; j < I40E_FDIR_MAX_FLEX_LEN; j += sizeof(uint16_t)) {
+			mask_tmp = I40E_WORD(flex_mask->mask[j],
+					     flex_mask->mask[j + 1]);
+			if (mask_tmp != 0x0 && mask_tmp != UINT16_MAX) {
+				nb_bitmask++;
+				if (nb_bitmask > I40E_FDIR_BITMASK_NUM_WORD) {
+					PMD_DRV_LOG(ERR, " exceed maximal"
+						" number of bitmasks.");
+					return -EINVAL;
+				}
+			}
+		}
+	}
+	return 0;
+}
+
+/*
+ * i40e_set_flx_pld_cfg -configure the rule how bytes stream is extracted as flexible payload
+ * @pf: board private structure
+ * @cfg: the rule how bytes stream is extracted as flexible payload
+ */
+static void
+i40e_set_flx_pld_cfg(struct i40e_pf *pf,
+			 const struct rte_eth_flex_payload_cfg *cfg)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_fdir_flex_pit flex_pit[I40E_MAX_FLXPLD_FIED];
+	uint32_t flx_pit;
+	uint16_t num, min_next_off;  /* in words */
+	uint8_t field_idx = 0;
+	uint8_t layer_idx = 0;
+	uint16_t i;
+
+	if (cfg->type == RTE_ETH_L2_PAYLOAD)
+		layer_idx = I40E_FLXPLD_L2_IDX;
+	else if (cfg->type == RTE_ETH_L3_PAYLOAD)
+		layer_idx = I40E_FLXPLD_L3_IDX;
+	else if (cfg->type == RTE_ETH_L4_PAYLOAD)
+		layer_idx = I40E_FLXPLD_L4_IDX;
+
+	memset(flex_pit, 0, sizeof(flex_pit));
+	num = i40e_srcoff_to_flx_pit(cfg->src_offset, flex_pit);
+
+	for (i = 0; i < num; i++) {
+		field_idx = layer_idx * I40E_MAX_FLXPLD_FIED + i;
+		/* record the info in fdir structure */
+		pf->fdir.flex_set[field_idx].src_offset =
+			flex_pit[i].src_offset / sizeof(uint16_t);
+		pf->fdir.flex_set[field_idx].size =
+			flex_pit[i].size / sizeof(uint16_t);
+		pf->fdir.flex_set[field_idx].dst_offset =
+			flex_pit[i].dst_offset / sizeof(uint16_t);
+		flx_pit = MK_FLX_PIT(pf->fdir.flex_set[field_idx].src_offset,
+				pf->fdir.flex_set[field_idx].size,
+				pf->fdir.flex_set[field_idx].dst_offset);
+
+		I40E_WRITE_REG(hw, I40E_PRTQF_FLX_PIT(field_idx), flx_pit);
+	}
+	min_next_off = pf->fdir.flex_set[field_idx].src_offset +
+				pf->fdir.flex_set[field_idx].size;
+
+	for (; i < I40E_MAX_FLXPLD_FIED; i++) {
+		/* set the non-used register obeying register's constrain */
+		flx_pit = MK_FLX_PIT(min_next_off, NONUSE_FLX_PIT_FSIZE,
+			   NONUSE_FLX_PIT_DEST_OFF);
+		I40E_WRITE_REG(hw,
+			I40E_PRTQF_FLX_PIT(layer_idx * I40E_MAX_FLXPLD_FIED + i),
+			flx_pit);
+		min_next_off++;
+	}
+}
+
+/*
+ * i40e_set_flex_mask_on_pctype - configure the mask on flexible payload
+ * @pf: board private structure
+ * @pctype: packet classify type
+ * @flex_masks: mask for flexible payload
+ */
+static void
+i40e_set_flex_mask_on_pctype(struct i40e_pf *pf,
+		enum i40e_filter_pctype pctype,
+		const struct rte_eth_fdir_flex_mask *mask_cfg)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_fdir_flex_mask *flex_mask;
+	uint32_t flxinset, fd_mask;
+	uint16_t mask_tmp;
+	uint8_t i, nb_bitmask = 0;
+
+	flex_mask = &pf->fdir.flex_mask[pctype];
+	memset(flex_mask, 0, sizeof(struct i40e_fdir_flex_mask));
+	for (i = 0; i < I40E_FDIR_MAX_FLEX_LEN; i += sizeof(uint16_t)) {
+		mask_tmp = I40E_WORD(mask_cfg->mask[i], mask_cfg->mask[i + 1]);
+		if (mask_tmp != 0x0) {
+			flex_mask->word_mask |=
+				I40E_FLEX_WORD_MASK(i / sizeof(uint16_t));
+			if (mask_tmp != UINT16_MAX) {
+				/* set bit mask */
+				flex_mask->bitmask[nb_bitmask].mask = ~mask_tmp;
+				flex_mask->bitmask[nb_bitmask].offset =
+					i / sizeof(uint16_t);
+				nb_bitmask++;
+			}
+		}
+	}
+	/* write mask to hw */
+	flxinset = (flex_mask->word_mask <<
+		I40E_PRTQF_FD_FLXINSET_INSET_SHIFT) &
+		I40E_PRTQF_FD_FLXINSET_INSET_MASK;
+	I40E_WRITE_REG(hw, I40E_PRTQF_FD_FLXINSET(pctype), flxinset);
+
+	for (i = 0; i < nb_bitmask; i++) {
+		fd_mask = (flex_mask->bitmask[i].mask <<
+			I40E_PRTQF_FD_MSK_MASK_SHIFT) &
+			I40E_PRTQF_FD_MSK_MASK_MASK;
+		fd_mask |= ((flex_mask->bitmask[i].offset +
+			I40E_FLX_OFFSET_IN_FIELD_VECTOR) <<
+			I40E_PRTQF_FD_MSK_OFFSET_SHIFT) &
+			I40E_PRTQF_FD_MSK_OFFSET_MASK;
+		I40E_WRITE_REG(hw, I40E_PRTQF_FD_MSK(pctype, i), fd_mask);
+	}
+}
+
 /*
  * Configure flow director related setting
  */
@@ -372,7 +634,10 @@ i40e_fdir_configure(struct rte_eth_dev *dev)
 {
 	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
 	struct i40e_hw *hw = I40E_DEV_PRIVATE_TO_HW(dev->data->dev_private);
+	struct rte_eth_fdir_flex_conf *conf;
+	enum i40e_filter_pctype pctype;
 	uint32_t val;
+	uint8_t i;
 	int ret = 0;
 
 	/*
@@ -396,6 +661,24 @@ i40e_fdir_configure(struct rte_eth_dev *dev)
 		I40E_WRITE_REG(hw, I40E_PFQF_CTL_0, val);
 
 		i40e_init_flx_pld(pf); /* set flex config to default value */
+
+		conf = &dev->data->dev_conf.fdir_conf.flex_conf;
+		ret = i40e_check_fdir_flex_conf(conf);
+		if (ret < 0) {
+			PMD_DRV_LOG(ERR, " invalid configuration arguments.");
+			return -EINVAL;
+		}
+		/* configure flex payload */
+		for (i = 0; i < conf->nb_payloads; i++)
+			i40e_set_flx_pld_cfg(pf, &conf->flex_set[i]);
+		/* configure flex mask*/
+		for (i = 0; i < conf->nb_flexmasks; i++) {
+			pctype = i40e_flowtype_to_pctype(
+				conf->flex_mask[i].flow_type);
+			i40e_set_flex_mask_on_pctype(pf,
+					pctype,
+					&conf->flex_mask[i]);
+		}
 	} else {
 		/* disable FDIR filter */
 		val &= ~I40E_PFQF_CTL_0_FD_ENA_MASK;
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 21/22] testpmd: add test command to configure flexible mask
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (19 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 20/22] i40e: take flow director flexible payload configuration Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 22/22] testpmd: add test command to configure flexible payload Jingjing Wu
  2014-11-21 11:34       ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Ananyev, Konstantin
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

test command added to configure flexible mask

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 94 ++++++++++++++++++++++++++++++++++++++++++++++++++
 app/test-pmd/config.c  | 30 ++++++++++++++++
 app/test-pmd/testpmd.h |  3 +-
 3 files changed, 126 insertions(+), 1 deletion(-)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 066769f..bb10b9f 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -709,6 +709,11 @@ static void cmd_help_long_parsed(void *parsed_result,
 
 			"flush_flow_director (port_id)\n"
 			"    Flush all flow director entries of a device.\n\n"
+
+			"flow_director_flex_mask (port_id)"
+			" flow (ip4|ip4-frag|tcp4|udp4|sctp4|ip6|ip6-frag|tcp6|udp6|sctp6|all)"
+			" (mask)\n"
+			"    Configure mask of flex payload.\n\n"
 		);
 	}
 }
@@ -8171,6 +8176,94 @@ cmdline_parse_inst_t cmd_flush_flow_director = {
 	},
 };
 
+/* *** deal with flow director mask on flexible payload *** */
+struct cmd_flow_director_flex_mask_result {
+	cmdline_fixed_string_t flow_director_flexmask;
+	uint8_t port_id;
+	cmdline_fixed_string_t flow;
+	cmdline_fixed_string_t flow_type;
+	cmdline_fixed_string_t mask;
+};
+
+static void
+cmd_flow_director_flex_mask_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flex_mask_result *res = parsed_result;
+	struct rte_eth_fdir_flex_mask flex_mask;
+	struct rte_port *port;
+	enum rte_eth_flow_type i;
+	int ret;
+
+	if (res->port_id > nb_ports) {
+		printf("Invalid port, range is [0, %d]\n", nb_ports - 1);
+		return;
+	}
+
+	port = &ports[res->port_id];
+	/** Check if the port is not started **/
+	if (port->port_status != RTE_PORT_STOPPED) {
+		printf("Please stop port %d first\n", res->port_id);
+		return;
+	}
+
+	memset(&flex_mask, 0, sizeof(struct rte_eth_fdir_flex_mask));
+	ret = parse_flexbytes(res->mask,
+			flex_mask.mask,
+			RTE_ETH_FDIR_MAX_FLEXLEN);
+	if (ret < 0) {
+		printf("error: Cannot parse mask input.\n");
+		return;
+	}
+	if (!strcmp(res->flow_type, "all")) {
+		for (i = RTE_ETH_FLOW_TYPE_UDPV4;
+		     i <= RTE_ETH_FLOW_TYPE_FRAG_IPV6;
+		     i++) {
+			flex_mask.flow_type = i;
+			fdir_set_flex_mask(res->port_id, &flex_mask);
+		}
+		cmd_reconfig_device_queue(res->port_id, 1, 0);
+		return;
+	}
+	flex_mask.flow_type = str2flowtype(res->flow_type);
+	fdir_set_flex_mask(res->port_id, &flex_mask);
+	cmd_reconfig_device_queue(res->port_id, 1, 0);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexmask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_director_flexmask,
+				 "flow_director_flex_mask");
+cmdline_parse_token_num_t cmd_flow_director_flexmask_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow, "flow");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_flow_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 flow_type,
+				"ip4#ip4-frag#tcp4#udp4#sctp4#"
+				"ip6#ip6-frag#tcp6#udp6#sctp6#all");
+cmdline_parse_token_string_t cmd_flow_director_flexmask_mask =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flex_mask_result,
+				 mask, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_mask = {
+	.f = cmd_flow_director_flex_mask_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex mask on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexmask,
+		(void *)&cmd_flow_director_flexmask_port_id,
+		(void *)&cmd_flow_director_flexmask_flow,
+		(void *)&cmd_flow_director_flexmask_flow_type,
+		(void *)&cmd_flow_director_flexmask_mask,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8304,6 +8397,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_udp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_mask,
 	NULL,
 };
 
diff --git a/app/test-pmd/config.c b/app/test-pmd/config.c
index b7e4412..e1ac901 100644
--- a/app/test-pmd/config.c
+++ b/app/test-pmd/config.c
@@ -2021,6 +2021,36 @@ fdir_set_masks(portid_t port_id, struct rte_fdir_masks *fdir_masks)
 }
 
 void
+fdir_set_flex_mask(portid_t port_id, struct rte_eth_fdir_flex_mask *cfg)
+{
+	struct rte_port *port;
+	struct rte_eth_fdir_flex_conf *flex_conf;
+	int i, idx = 0;
+
+	port = &ports[port_id];
+	flex_conf = &port->dev_conf.fdir_conf.flex_conf;
+	for (i = 0; i < RTE_ETH_FLOW_TYPE_MAX; i++) {
+		if (cfg->flow_type == flex_conf->flex_mask[i].flow_type) {
+			idx = i;
+			break;
+		}
+	}
+	if (i >= RTE_ETH_FLOW_TYPE_MAX) {
+		if (flex_conf->nb_flexmasks < RTE_DIM(flex_conf->flex_mask)) {
+			idx = flex_conf->nb_flexmasks;
+			flex_conf->nb_flexmasks++;
+		} else {
+			printf("The flex mask table is full. Can not set flex"
+				" mask for flow_type(%u).", cfg->flow_type);
+			return;
+		}
+	}
+	(void)rte_memcpy(&flex_conf->flex_mask[idx],
+			 cfg,
+			 sizeof(struct rte_eth_fdir_flex_mask));
+}
+
+void
 set_vf_traffic(portid_t port_id, uint8_t is_rx, uint16_t vf, uint8_t on)
 {
 	int diag;
diff --git a/app/test-pmd/testpmd.h b/app/test-pmd/testpmd.h
index 9cbfeac..05a65d4 100644
--- a/app/test-pmd/testpmd.h
+++ b/app/test-pmd/testpmd.h
@@ -532,7 +532,8 @@ void fdir_update_perfect_filter(portid_t port_id, uint16_t soft_id,
 void fdir_remove_perfect_filter(portid_t port_id, uint16_t soft_id,
 				struct rte_fdir_filter *fdir_filter);
 void fdir_set_masks(portid_t port_id, struct rte_fdir_masks *fdir_masks);
-
+void fdir_set_flex_mask(portid_t port_id,
+			   struct rte_eth_fdir_flex_mask *cfg);
 void port_rss_reta_info(portid_t port_id, struct rte_eth_rss_reta *reta_conf);
 
 void set_vf_traffic(portid_t port_id, uint8_t is_rx, uint16_t vf, uint8_t on);
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* [dpdk-dev] [PATCH v6 22/22] testpmd: add test command to configure flexible payload
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (20 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 21/22] testpmd: add test command to configure flexible mask Jingjing Wu
@ 2014-11-21  0:46       ` Jingjing Wu
  2014-11-21 11:34       ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Ananyev, Konstantin
  22 siblings, 0 replies; 123+ messages in thread
From: Jingjing Wu @ 2014-11-21  0:46 UTC (permalink / raw)
  To: dev

Test command is added to configure flexible payload

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 app/test-pmd/cmdline.c | 120 +++++++++++++++++++++++++++++++++++++++++++++++++
 app/test-pmd/config.c  |  31 +++++++++++++
 app/test-pmd/testpmd.h |   2 +
 3 files changed, 153 insertions(+)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index bb10b9f..eed28b7 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -714,6 +714,10 @@ static void cmd_help_long_parsed(void *parsed_result,
 			" flow (ip4|ip4-frag|tcp4|udp4|sctp4|ip6|ip6-frag|tcp6|udp6|sctp6|all)"
 			" (mask)\n"
 			"    Configure mask of flex payload.\n\n"
+
+			"flow_director_flex_payload (port_id)"
+			" (l2|l3|l4) (config)\n"
+			"    Configure flex payload selection.\n\n"
 		);
 	}
 }
@@ -8264,6 +8268,121 @@ cmdline_parse_inst_t cmd_set_flow_director_flex_mask = {
 	},
 };
 
+/* *** deal with flow director flexible payload configuration *** */
+struct cmd_flow_director_flexpayload_result {
+	cmdline_fixed_string_t flow_director_flexpayload;
+	uint8_t port_id;
+	cmdline_fixed_string_t payload_layer;
+	cmdline_fixed_string_t payload_cfg;
+};
+
+static inline int
+parse_offsets(const char *q_arg, uint16_t *offsets, uint16_t max_num)
+{
+	char s[256];
+	const char *p, *p0 = q_arg;
+	char *end;
+	unsigned long int_fld;
+	char *str_fld[max_num];
+	int i;
+	unsigned size;
+	int ret = -1;
+
+	p = strchr(p0, '(');
+	if (p == NULL)
+		return -1;
+	++p;
+	p0 = strchr(p, ')');
+	if (p0 == NULL)
+		return -1;
+
+	size = p0 - p;
+	if (size >= sizeof(s))
+		return -1;
+
+	snprintf(s, sizeof(s), "%.*s", size, p);
+	ret = rte_strsplit(s, sizeof(s), str_fld, max_num, ',');
+	if (ret < 0 || ret > max_num)
+		return -1;
+	for (i = 0; i < ret; i++) {
+		errno = 0;
+		int_fld = strtoul(str_fld[i], &end, 0);
+		if (errno != 0 || *end != '\0' || int_fld > UINT16_MAX)
+			return -1;
+		offsets[i] = (uint16_t)int_fld;
+	}
+	return ret;
+}
+
+static void
+cmd_flow_director_flxpld_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_flow_director_flexpayload_result *res = parsed_result;
+	struct rte_eth_flex_payload_cfg flex_cfg;
+	struct rte_port *port;
+	int ret = 0;
+
+	if (res->port_id > nb_ports) {
+		printf("Invalid port, range is [0, %d]\n", nb_ports - 1);
+		return;
+	}
+
+	port = &ports[res->port_id];
+	/** Check if the port is not started **/
+	if (port->port_status != RTE_PORT_STOPPED) {
+		printf("Please stop port %d first\n", res->port_id);
+		return;
+	}
+
+	memset(&flex_cfg, 0, sizeof(struct rte_eth_flex_payload_cfg));
+
+	if (!strcmp(res->payload_layer, "l2"))
+		flex_cfg.type = RTE_ETH_L2_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l3"))
+		flex_cfg.type = RTE_ETH_L3_PAYLOAD;
+	else if (!strcmp(res->payload_layer, "l4"))
+		flex_cfg.type = RTE_ETH_L4_PAYLOAD;
+
+	ret = parse_offsets(res->payload_cfg, flex_cfg.src_offset,
+			    RTE_ETH_FDIR_MAX_FLEXLEN);
+	if (ret < 0) {
+		printf("error: Cannot parse flex payload input.\n");
+		return;
+	}
+
+	fdir_set_flex_payload(res->port_id, &flex_cfg);
+	cmd_reconfig_device_queue(res->port_id, 1, 0);
+}
+
+cmdline_parse_token_string_t cmd_flow_director_flexpayload =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 flow_director_flexpayload,
+				 "flow_director_flex_payload");
+cmdline_parse_token_num_t cmd_flow_director_flexpayload_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_layer =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_layer, "l2#l3#l4");
+cmdline_parse_token_string_t cmd_flow_director_flexpayload_payload_cfg =
+	TOKEN_STRING_INITIALIZER(struct cmd_flow_director_flexpayload_result,
+				 payload_cfg, NULL);
+
+cmdline_parse_inst_t cmd_set_flow_director_flex_payload = {
+	.f = cmd_flow_director_flxpld_parsed,
+	.data = NULL,
+	.help_str = "set flow director's flex payload on NIC",
+	.tokens = {
+		(void *)&cmd_flow_director_flexpayload,
+		(void *)&cmd_flow_director_flexpayload_port_id,
+		(void *)&cmd_flow_director_flexpayload_payload_layer,
+		(void *)&cmd_flow_director_flexpayload_payload_cfg,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -8398,6 +8517,7 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_add_del_sctp_flow_director,
 	(cmdline_parse_inst_t *)&cmd_flush_flow_director,
 	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_mask,
+	(cmdline_parse_inst_t *)&cmd_set_flow_director_flex_payload,
 	NULL,
 };
 
diff --git a/app/test-pmd/config.c b/app/test-pmd/config.c
index e1ac901..694d630 100644
--- a/app/test-pmd/config.c
+++ b/app/test-pmd/config.c
@@ -2051,6 +2051,37 @@ fdir_set_flex_mask(portid_t port_id, struct rte_eth_fdir_flex_mask *cfg)
 }
 
 void
+fdir_set_flex_payload(portid_t port_id, struct rte_eth_flex_payload_cfg *cfg)
+{
+	struct rte_port *port;
+	struct rte_eth_fdir_flex_conf *flex_conf;
+	int i, idx = 0;
+
+	port = &ports[port_id];
+	flex_conf = &port->dev_conf.fdir_conf.flex_conf;
+	for (i = 0; i < RTE_ETH_PAYLOAD_MAX; i++) {
+		if (cfg->type == flex_conf->flex_set[i].type) {
+			idx = i;
+			break;
+		}
+	}
+	if (i >= RTE_ETH_PAYLOAD_MAX) {
+		if (flex_conf->nb_payloads < RTE_DIM(flex_conf->flex_set)) {
+			idx = flex_conf->nb_payloads;
+			flex_conf->nb_payloads++;
+		} else {
+			printf("The flex payload table is full. Can not set"
+				" flex payload for type(%u).", cfg->type);
+			return;
+		}
+	}
+	(void)rte_memcpy(&flex_conf->flex_set[idx],
+			 cfg,
+			 sizeof(struct rte_eth_flex_payload_cfg));
+
+}
+
+void
 set_vf_traffic(portid_t port_id, uint8_t is_rx, uint16_t vf, uint8_t on)
 {
 	int diag;
diff --git a/app/test-pmd/testpmd.h b/app/test-pmd/testpmd.h
index 05a65d4..072aa57 100644
--- a/app/test-pmd/testpmd.h
+++ b/app/test-pmd/testpmd.h
@@ -534,6 +534,8 @@ void fdir_remove_perfect_filter(portid_t port_id, uint16_t soft_id,
 void fdir_set_masks(portid_t port_id, struct rte_fdir_masks *fdir_masks);
 void fdir_set_flex_mask(portid_t port_id,
 			   struct rte_eth_fdir_flex_mask *cfg);
+void fdir_set_flex_payload(portid_t port_id,
+			   struct rte_eth_flex_payload_cfg *cfg);
 void port_rss_reta_info(portid_t port_id, struct rte_eth_rss_reta *reta_conf);
 
 void set_vf_traffic(portid_t port_id, uint8_t is_rx, uint16_t vf, uint8_t on);
-- 
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville
  2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
                         ` (21 preceding siblings ...)
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 22/22] testpmd: add test command to configure flexible payload Jingjing Wu
@ 2014-11-21 11:34       ` Ananyev, Konstantin
  2014-11-24 23:20         ` Thomas Monjalon
  22 siblings, 1 reply; 123+ messages in thread
From: Ananyev, Konstantin @ 2014-11-21 11:34 UTC (permalink / raw)
  To: Wu, Jingjing, dev



> From: Wu, Jingjing
> Sent: Friday, November 21, 2014 12:47 AM
> To: dev@dpdk.org
> Cc: Wu, Jingjing; Cao, Min; Ananyev, Konstantin
> Subject: [PATCH v6 00/22] Support flow director programming on Fortville
> 
> The patch set supports flow director on fortville.
> It includes:
>  - set up/tear down fortville resources to support flow director, such as queue and vsi.
>  - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6,
> sctpv6.
>  - support flushing flow director table (all filters).
>  - support operation to get flow director information.
>  - match status statistics, FD_ID report.
>  - support operation to configure flexible payload and its mask
>  - support flexible payload involved in comparison and flex bytes report.
> 
> v2 changes:
>  - create real fdir vsi and assign queue 0 pair to it.
>  - check filter status report on the rx queue 0
> 
> v3 changes:
>  - redefine filter APIs to support multi-kind filters
>  - support sctpv4 and sctpv6 type flows
>  - support flexible payload involved in comparison
> 
> v4 changes:
>  - strip the filter APIs definitions from this patch set
>  - extend mbuf field to support flex bytes report.
>  - fix typos.
> 
> v5 changes:
>  - redefine structure rte_eth_fdir_info
>  - add doxygen comments about flexible payload and mbuf extend
>  - fix typos
> 
> v6 changes:
>  - extend structure rte_eth_fdir_info
>  - move the flex payload and mask setting from filter_ctrl api
>    to i40e_fdir_configure when start device
>  - change the structure for flex payload and mask setting, and
>    add verification of those arguments before HW setting is taken.
>  - change flexpayloads from words to bytes format
>  - add two more flow_types
>  - organize duplicate code lines to macro or function
>  - add and correct doxygen comments
>  - fix the merging error in v5
> 
> Jingjing Wu (22):
>   i40e: set up and initialize flow director
>   i40e: tear down flow director
>   i40e: initialize flexible payload setting
>   ethdev: define structures for adding/deleting flow director
>   i40e: define functions for transition between flow_type and pctype
>   i40e: implement operations to add/delete flow director
>   testpmd: add test commands to add/delete flow director filter
>   i40e: match counter for flow director
>   mbuf: extend fdir field
>   i40e: report flow director match info to mbuf
>   testpmd: print extended fdir info in mbuf
>   i40e: implement operation to flush flow director table
>   testpmd: add test command to flush flow director table
>   ethdev: define structures for getting flow director information
>   i40e: implement operations to get fdir info
>   ethdev: define structures for getting flow director statistics
>   i40e: implement operations to get fdir statistics
>   testpmd: display fdir info
>   ethdev: add flexible payload setting in eth_conf
>   i40e: take flow director flexible payload configuration
>   testpmd: add test command to configure flexible mask
>   testpmd: add test command to configure flexible payload
> 
>  app/test-pmd/cmdline.c            |  644 ++++++++++++++++++
>  app/test-pmd/config.c             |  202 +++++-
>  app/test-pmd/rxonly.c             |   14 +-
>  app/test-pmd/testpmd.h            |    5 +-
>  lib/librte_ether/rte_eth_ctrl.h   |  279 +++++++-
>  lib/librte_ether/rte_ethdev.h     |   11 +-
>  lib/librte_mbuf/rte_mbuf.h        |   17 +-
>  lib/librte_pmd_i40e/Makefile      |    2 +
>  lib/librte_pmd_i40e/i40e_ethdev.c |  175 ++++-
>  lib/librte_pmd_i40e/i40e_ethdev.h |   93 ++-
>  lib/librte_pmd_i40e/i40e_fdir.c   | 1362 +++++++++++++++++++++++++++++++++++++
>  lib/librte_pmd_i40e/i40e_rxtx.c   |  207 +++++-
>  12 files changed, 2965 insertions(+), 46 deletions(-)
>  create mode 100644 lib/librte_pmd_i40e/i40e_fdir.c
> 
> --
> 1.8.1.4

Acked-by: Konstantin Ananyev <konstantin.ananyev@intel.com>

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
  2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field Jingjing Wu
@ 2014-11-21 17:03         ` Chilikin, Andrey
  2014-11-21 19:34           ` Ananyev, Konstantin
  0 siblings, 1 reply; 123+ messages in thread
From: Chilikin, Andrey @ 2014-11-21 17:03 UTC (permalink / raw)
  To: Wu, Jingjing, dev

This patch adds extra 32bits to rte_mbuf::hash - so 'uint32_t usr' will move to the second cache line?

Regards,
Andrey

-----Original Message-----
From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
Sent: Friday, November 21, 2014 12:47 AM
To: dev@dpdk.org
Subject: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field

fdir field in rte_mbuf is extened to support flex bytes reported when fdir match.
8 flex bytes can be reported in maximum.
The reported flex bytes are part of flexible payload.

Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
---
 lib/librte_mbuf/rte_mbuf.h | 17 ++++++++++++++---
 1 file changed, 14 insertions(+), 3 deletions(-)

diff --git a/lib/librte_mbuf/rte_mbuf.h b/lib/librte_mbuf/rte_mbuf.h index f5f8658..5899e5c 100644
--- a/lib/librte_mbuf/rte_mbuf.h
+++ b/lib/librte_mbuf/rte_mbuf.h
@@ -77,7 +77,7 @@ extern "C" {
  */
 #define PKT_RX_VLAN_PKT      (1ULL << 0)  /**< RX packet is a 802.1q VLAN packet. */
 #define PKT_RX_RSS_HASH      (1ULL << 1)  /**< RX packet with RSS hash result. */
-#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR infos. */
+#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR match indicate. */
 #define PKT_RX_L4_CKSUM_BAD  (1ULL << 3)  /**< L4 cksum of RX pkt. is not OK. */  #define PKT_RX_IP_CKSUM_BAD  (1ULL << 4)  /**< IP cksum of RX pkt. is not OK. */  #define PKT_RX_EIP_CKSUM_BAD (0ULL << 0)  /**< External IP header checksum error. */ @@ -93,6 +93,8 @@ extern "C" {  #define PKT_RX_IEEE1588_TMST (1ULL << 10) /**< RX IEEE1588 L2/L4 timestamped packet.*/  #define PKT_RX_TUNNEL_IPV4_HDR (1ULL << 11) /**< RX tunnel packet with IPv4 header.*/  #define PKT_RX_TUNNEL_IPV6_HDR (1ULL << 12) /**< RX tunnel packet with IPv6 header. */
+#define PKT_RX_FDIR_ID       (1ULL << 13) /**< FD id reported if FDIR match. */
+#define PKT_RX_FDIR_FLX      (1ULL << 14) /**< Flexible bytes reported if FDIR match. */
 
 #define PKT_TX_VLAN_PKT      (1ULL << 55) /**< TX packet is a 802.1q VLAN packet. */
 #define PKT_TX_IP_CKSUM      (1ULL << 54) /**< IP cksum of TX pkt. computed by NIC. */
@@ -181,8 +183,17 @@ struct rte_mbuf {
 	union {
 		uint32_t rss;     /**< RSS hash result if RSS enabled */
 		struct {
-			uint16_t hash;
-			uint16_t id;
+			union {
+				struct {
+					uint16_t hash;
+					uint16_t id;
+				};
+				uint32_t lo;
+				/**< Second 4 flexible bytes */
+			};
+			uint32_t hi;
+			/**< First 4 flexible bytes or FD ID, dependent on
+			     PKT_RX_FDIR_* flag in ol_flags. */
 		} fdir;           /**< Filter identifier if FDIR enabled */
 		uint32_t sched;   /**< Hierarchical scheduler */
 		uint32_t usr;	  /**< User defined tags. See @rte_distributor_process */
--
1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
  2014-11-21 17:03         ` Chilikin, Andrey
@ 2014-11-21 19:34           ` Ananyev, Konstantin
  2014-11-21 19:37             ` Chilikin, Andrey
  0 siblings, 1 reply; 123+ messages in thread
From: Ananyev, Konstantin @ 2014-11-21 19:34 UTC (permalink / raw)
  To: Chilikin, Andrey, Wu, Jingjing, dev

Hi Andrey,

> -----Original Message-----
> From: Chilikin, Andrey
> Sent: Friday, November 21, 2014 5:03 PM
> To: Wu, Jingjing; dev@dpdk.org
> Cc: Ananyev, Konstantin
> Subject: RE: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
> 
> This patch adds extra 32bits to rte_mbuf::hash 

Yes.

>- so 'uint32_t usr' will move to the second cache line?
>

Why is that?
hash is a union, so:
offsetof(struct rte_mbuf, hash.rss) == offsetof(struct rte_mbuf, hash.usr) == 44
before and after patch.

As there still exists free space before rte_mbuf::userdata, whole rte_mbuf::hash stays on the first cache line.
Konstantin
    
 
> Regards,
> Andrey
> 
> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Friday, November 21, 2014 12:47 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
> 
> fdir field in rte_mbuf is extened to support flex bytes reported when fdir match.
> 8 flex bytes can be reported in maximum.
> The reported flex bytes are part of flexible payload.
> 
> Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
> ---
>  lib/librte_mbuf/rte_mbuf.h | 17 ++++++++++++++---
>  1 file changed, 14 insertions(+), 3 deletions(-)
> 
> diff --git a/lib/librte_mbuf/rte_mbuf.h b/lib/librte_mbuf/rte_mbuf.h index f5f8658..5899e5c 100644
> --- a/lib/librte_mbuf/rte_mbuf.h
> +++ b/lib/librte_mbuf/rte_mbuf.h
> @@ -77,7 +77,7 @@ extern "C" {
>   */
>  #define PKT_RX_VLAN_PKT      (1ULL << 0)  /**< RX packet is a 802.1q VLAN packet. */
>  #define PKT_RX_RSS_HASH      (1ULL << 1)  /**< RX packet with RSS hash result. */
> -#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR infos. */
> +#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR match indicate. */
>  #define PKT_RX_L4_CKSUM_BAD  (1ULL << 3)  /**< L4 cksum of RX pkt. is not OK. */  #define PKT_RX_IP_CKSUM_BAD  (1ULL << 4)
> /**< IP cksum of RX pkt. is not OK. */  #define PKT_RX_EIP_CKSUM_BAD (0ULL << 0)  /**< External IP header checksum error. */ @@
> -93,6 +93,8 @@ extern "C" {  #define PKT_RX_IEEE1588_TMST (1ULL << 10) /**< RX IEEE1588 L2/L4 timestamped packet.*/  #define
> PKT_RX_TUNNEL_IPV4_HDR (1ULL << 11) /**< RX tunnel packet with IPv4 header.*/  #define PKT_RX_TUNNEL_IPV6_HDR (1ULL <<
> 12) /**< RX tunnel packet with IPv6 header. */
> +#define PKT_RX_FDIR_ID       (1ULL << 13) /**< FD id reported if FDIR match. */
> +#define PKT_RX_FDIR_FLX      (1ULL << 14) /**< Flexible bytes reported if FDIR match. */
> 
>  #define PKT_TX_VLAN_PKT      (1ULL << 55) /**< TX packet is a 802.1q VLAN packet. */
>  #define PKT_TX_IP_CKSUM      (1ULL << 54) /**< IP cksum of TX pkt. computed by NIC. */
> @@ -181,8 +183,17 @@ struct rte_mbuf {
>  	union {
>  		uint32_t rss;     /**< RSS hash result if RSS enabled */
>  		struct {
> -			uint16_t hash;
> -			uint16_t id;
> +			union {
> +				struct {
> +					uint16_t hash;
> +					uint16_t id;
> +				};
> +				uint32_t lo;
> +				/**< Second 4 flexible bytes */
> +			};
> +			uint32_t hi;
> +			/**< First 4 flexible bytes or FD ID, dependent on
> +			     PKT_RX_FDIR_* flag in ol_flags. */
>  		} fdir;           /**< Filter identifier if FDIR enabled */
>  		uint32_t sched;   /**< Hierarchical scheduler */
>  		uint32_t usr;	  /**< User defined tags. See @rte_distributor_process */
> --
> 1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
  2014-11-21 19:34           ` Ananyev, Konstantin
@ 2014-11-21 19:37             ` Chilikin, Andrey
  0 siblings, 0 replies; 123+ messages in thread
From: Chilikin, Andrey @ 2014-11-21 19:37 UTC (permalink / raw)
  To: Ananyev, Konstantin, Wu, Jingjing, dev

Me bad, missed wrapping union  :)

Thanks,
Andrey

-----Original Message-----
From: Ananyev, Konstantin 
Sent: Friday, November 21, 2014 7:35 PM
To: Chilikin, Andrey; Wu, Jingjing; dev@dpdk.org
Subject: RE: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field

Hi Andrey,

> -----Original Message-----
> From: Chilikin, Andrey
> Sent: Friday, November 21, 2014 5:03 PM
> To: Wu, Jingjing; dev@dpdk.org
> Cc: Ananyev, Konstantin
> Subject: RE: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
> 
> This patch adds extra 32bits to rte_mbuf::hash

Yes.

>- so 'uint32_t usr' will move to the second cache line?
>

Why is that?
hash is a union, so:
offsetof(struct rte_mbuf, hash.rss) == offsetof(struct rte_mbuf, hash.usr) == 44 before and after patch.

As there still exists free space before rte_mbuf::userdata, whole rte_mbuf::hash stays on the first cache line.
Konstantin
    
 
> Regards,
> Andrey
> 
> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Friday, November 21, 2014 12:47 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field
> 
> fdir field in rte_mbuf is extened to support flex bytes reported when fdir match.
> 8 flex bytes can be reported in maximum.
> The reported flex bytes are part of flexible payload.
> 
> Signed-off-by: jingjing.wu <jingjing.wu@intel.com>
> ---
>  lib/librte_mbuf/rte_mbuf.h | 17 ++++++++++++++---
>  1 file changed, 14 insertions(+), 3 deletions(-)
> 
> diff --git a/lib/librte_mbuf/rte_mbuf.h b/lib/librte_mbuf/rte_mbuf.h 
> index f5f8658..5899e5c 100644
> --- a/lib/librte_mbuf/rte_mbuf.h
> +++ b/lib/librte_mbuf/rte_mbuf.h
> @@ -77,7 +77,7 @@ extern "C" {
>   */
>  #define PKT_RX_VLAN_PKT      (1ULL << 0)  /**< RX packet is a 802.1q VLAN packet. */
>  #define PKT_RX_RSS_HASH      (1ULL << 1)  /**< RX packet with RSS hash result. */
> -#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR infos. */
> +#define PKT_RX_FDIR          (1ULL << 2)  /**< RX packet with FDIR match indicate. */
>  #define PKT_RX_L4_CKSUM_BAD  (1ULL << 3)  /**< L4 cksum of RX pkt. is 
> not OK. */  #define PKT_RX_IP_CKSUM_BAD  (1ULL << 4) /**< IP cksum of 
> RX pkt. is not OK. */  #define PKT_RX_EIP_CKSUM_BAD (0ULL << 0)  /**< 
> External IP header checksum error. */ @@
> -93,6 +93,8 @@ extern "C" {  #define PKT_RX_IEEE1588_TMST (1ULL << 10) 
> /**< RX IEEE1588 L2/L4 timestamped packet.*/  #define 
> PKT_RX_TUNNEL_IPV4_HDR (1ULL << 11) /**< RX tunnel packet with IPv4 
> header.*/  #define PKT_RX_TUNNEL_IPV6_HDR (1ULL <<
> 12) /**< RX tunnel packet with IPv6 header. */
> +#define PKT_RX_FDIR_ID       (1ULL << 13) /**< FD id reported if FDIR match. */
> +#define PKT_RX_FDIR_FLX      (1ULL << 14) /**< Flexible bytes reported if FDIR match. */
> 
>  #define PKT_TX_VLAN_PKT      (1ULL << 55) /**< TX packet is a 802.1q VLAN packet. */
>  #define PKT_TX_IP_CKSUM      (1ULL << 54) /**< IP cksum of TX pkt. computed by NIC. */
> @@ -181,8 +183,17 @@ struct rte_mbuf {
>  	union {
>  		uint32_t rss;     /**< RSS hash result if RSS enabled */
>  		struct {
> -			uint16_t hash;
> -			uint16_t id;
> +			union {
> +				struct {
> +					uint16_t hash;
> +					uint16_t id;
> +				};
> +				uint32_t lo;
> +				/**< Second 4 flexible bytes */
> +			};
> +			uint32_t hi;
> +			/**< First 4 flexible bytes or FD ID, dependent on
> +			     PKT_RX_FDIR_* flag in ol_flags. */
>  		} fdir;           /**< Filter identifier if FDIR enabled */
>  		uint32_t sched;   /**< Hierarchical scheduler */
>  		uint32_t usr;	  /**< User defined tags. See @rte_distributor_process */
> --
> 1.8.1.4

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville
  2014-11-21 11:34       ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Ananyev, Konstantin
@ 2014-11-24 23:20         ` Thomas Monjalon
  2014-11-25  4:51           ` Wu, Jingjing
  0 siblings, 1 reply; 123+ messages in thread
From: Thomas Monjalon @ 2014-11-24 23:20 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

> > The patch set supports flow director on fortville.
> > It includes:
> >  - set up/tear down fortville resources to support flow director, such as queue and vsi.
> >  - support operation to add or delete 8 flow types of the flow director filters, they are ipv4, tcpv4, udpv4, sctpv4, ipv6, tcpv6, udpv6,
> > sctpv6.
> >  - support flushing flow director table (all filters).
> >  - support operation to get flow director information.
> >  - match status statistics, FD_ID report.
> >  - support operation to configure flexible payload and its mask
> >  - support flexible payload involved in comparison and flex bytes report.
> > 
> > v2 changes:
> >  - create real fdir vsi and assign queue 0 pair to it.
> >  - check filter status report on the rx queue 0
> > 
> > v3 changes:
> >  - redefine filter APIs to support multi-kind filters
> >  - support sctpv4 and sctpv6 type flows
> >  - support flexible payload involved in comparison
> > 
> > v4 changes:
> >  - strip the filter APIs definitions from this patch set
> >  - extend mbuf field to support flex bytes report.
> >  - fix typos.
> > 
> > v5 changes:
> >  - redefine structure rte_eth_fdir_info
> >  - add doxygen comments about flexible payload and mbuf extend
> >  - fix typos
> > 
> > v6 changes:
> >  - extend structure rte_eth_fdir_info
> >  - move the flex payload and mask setting from filter_ctrl api
> >    to i40e_fdir_configure when start device
> >  - change the structure for flex payload and mask setting, and
> >    add verification of those arguments before HW setting is taken.
> >  - change flexpayloads from words to bytes format
> >  - add two more flow_types
> >  - organize duplicate code lines to macro or function
> >  - add and correct doxygen comments
> >  - fix the merging error in v5
> > 
> > Jingjing Wu (22):
> >   i40e: set up and initialize flow director
> >   i40e: tear down flow director
> >   i40e: initialize flexible payload setting
> >   ethdev: define structures for adding/deleting flow director
> >   i40e: define functions for transition between flow_type and pctype
> >   i40e: implement operations to add/delete flow director
> >   testpmd: add test commands to add/delete flow director filter
> >   i40e: match counter for flow director
> >   mbuf: extend fdir field
> >   i40e: report flow director match info to mbuf
> >   testpmd: print extended fdir info in mbuf
> >   i40e: implement operation to flush flow director table
> >   testpmd: add test command to flush flow director table
> >   ethdev: define structures for getting flow director information
> >   i40e: implement operations to get fdir info
> >   ethdev: define structures for getting flow director statistics
> >   i40e: implement operations to get fdir statistics
> >   testpmd: display fdir info
> >   ethdev: add flexible payload setting in eth_conf
> >   i40e: take flow director flexible payload configuration
> >   testpmd: add test command to configure flexible mask
> >   testpmd: add test command to configure flexible payload
> 
> Acked-by: Konstantin Ananyev <konstantin.ananyev@intel.com>

I feel the flow director features could be better explained,
and probably the API won't be enough generic for the next driver implementing
flow director. But no comment from the community means it's OK to integrate.

Now we move on this API and the old one must be removed.
Converting ixgbe to this new API must be the top priority.
It must be clear to everyone that no new Fortville feature will be accepted
until a full clean-up of the old filtering API.

Thank you Jingjing for the big work. Step done.
Applied
-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville
  2014-11-24 23:20         ` Thomas Monjalon
@ 2014-11-25  4:51           ` Wu, Jingjing
  2014-11-25  9:23             ` Thomas Monjalon
  0 siblings, 1 reply; 123+ messages in thread
From: Wu, Jingjing @ 2014-11-25  4:51 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

Thanks a lot.

> 
> I feel the flow director features could be better explained, and probably the
> API won't be enough generic for the next driver implementing flow director.
> But no comment from the community means it's OK to integrate.
> 
> Now we move on this API and the old one must be removed.
> Converting ixgbe to this new API must be the top priority.
> It must be clear to everyone that no new Fortville feature will be accepted
> until a full clean-up of the old filtering API.

If I understand correctly, what you mean is:
If the new patch is using new filter_ctrl API while the similar feature for
Igb and ixgbe are using the old filtering API, we need to clean-up the old filtering
API and promote them to new filtering APIs at first.
For example, if we want to enable ethertype filter on Fortville, we need to move
the igb/ixgbe's ether_type filter to new API at the same patchset.

What you said is not for others features which has no relationship with filter API. 
Correct? 
 
> 
> Thank you Jingjing for the big work. Step done.
> Applied
> --
> Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

* Re: [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville
  2014-11-25  4:51           ` Wu, Jingjing
@ 2014-11-25  9:23             ` Thomas Monjalon
  0 siblings, 0 replies; 123+ messages in thread
From: Thomas Monjalon @ 2014-11-25  9:23 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

2014-11-25 04:51, Wu, Jingjing:
> > Now we move on this API and the old one must be removed.
> > Converting ixgbe to this new API must be the top priority.
> > It must be clear to everyone that no new Fortville feature will be accepted
> > until a full clean-up of the old filtering API.
> 
> If I understand correctly, what you mean is:
> If the new patch is using new filter_ctrl API while the similar feature for
> Igb and ixgbe are using the old filtering API, we need to clean-up the old filtering
> API and promote them to new filtering APIs at first.
> For example, if we want to enable ethertype filter on Fortville, we need to move
> the igb/ixgbe's ether_type filter to new API at the same patchset.
> 
> What you said is not for others features which has no relationship with filter API. 
> Correct? 

No, let me explain the situation to everyone.
In DPDK 1.8, some features will have 2 different API. The old API works for ixgbe
but don't allow to use i40e. The new API works only for i40e.
It's really not convenient and, as a general rule, this kind of breaking
is forbidden. But the development of the release 1.8 was especially difficult
and we made some trade-offs that we never should do again.

This situation is due to i40e developments. So it's the responsibility of the
i40e team to fix it by removing the old API.
To be sure it will be done quickly, the integration of i40e features in next
release cycle (2.0) will be blocked until this API problem is fixed.

-- 
Thomas

^ permalink raw reply	[flat|nested] 123+ messages in thread

end of thread, other threads:[~2014-11-25  9:12 UTC | newest]

Thread overview: 123+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2014-09-26  6:03 [dpdk-dev] [PATCH v3 00/20] Support flow director programming on Fortville Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 01/20] i40e: set up and initialize flow director Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 02/20] i40e: tear down " Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 03/20] i40e: initialize flexible payload setting Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 04/20] lib/librte_ether: new filter APIs definition Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 05/20] lib/librte_ether: define structures for adding/deleting flow director Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 06/20] i40e: implement operations to add/delete " Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 07/20] app/test-pmd: add test commands to add/delete flow director filter Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 08/20] i40e: match counter for flow director Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 09/20] i40e: report flow director match info to mbuf Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 10/20] lib/librte_ether: define structures for getting flow director information Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 11/20] i40e: implement operations to get fdir info Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 12/20] app/test-pmd: display fdir statistics Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 13/20] i40e: implement operation to flush flow director table Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 14/20] app/test-pmd: add test command " Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 15/20] lib/librte_ether: define structures for configuring flexible payload Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v316/20] i40e: implement operations to configure " Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 17/20] app/test-pmd: add test command " Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 18/20] lib/librte_ether: define structures for configuring flex masks Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 19/20] i40e: implement operations to configure flexible masks Jingjing Wu
2014-09-26  6:03 ` [dpdk-dev] [PATCH v3 20/20] app/test-pmd: add test command " Jingjing Wu
2014-10-13 15:58   ` De Lara Guarch, Pablo
2014-10-22  1:01 ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 01/21] i40e: set up and initialize flow director Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 02/21] i40e: tear down " Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 03/21] i40e: initialize flexible payload setting Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
2014-10-27 16:57     ` Thomas Monjalon
2014-10-28  1:18       ` Wu, Jingjing
2014-10-28 13:17         ` Thomas Monjalon
2014-10-29  1:29           ` Wu, Jingjing
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 05/21] i40e: implement operations to add/delete " Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
2014-10-28 13:23     ` Thomas Monjalon
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 07/21] i40e: match counter for flow director Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 08/21] mbuf: extend fdir field Jingjing Wu
2014-10-28 13:28     ` Thomas Monjalon
2014-10-29  1:45       ` Wu, Jingjing
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 09/21] i40e: report flow director match info to mbuf Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 10/21] testpmd: print extended fdir info in mbuf Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 11/21] ethdev: define structures for getting flow director information Jingjing Wu
2014-10-28 13:44     ` Thomas Monjalon
2014-10-29  2:10       ` Wu, Jingjing
2014-10-29  9:48         ` Thomas Monjalon
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 12/21] i40e: implement operations to get fdir info Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 13/21] testpmd: display fdir statistics Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 14/21] i40e: implement operation to flush flow director table Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 15/21] testpmd: add test command " Jingjing Wu
2014-10-28 13:53     ` Thomas Monjalon
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
2014-10-28 14:14     ` Thomas Monjalon
2014-10-29  3:21       ` Wu, Jingjing
2014-10-29  9:55         ` Thomas Monjalon
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 17/21] i40e: implement operations to configure " Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 18/21] testpmd: add test command " Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 19/21] ethdev: define structures for configuring flex masks Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 20/21] i40e: implement operations to configure flexible masks Jingjing Wu
2014-10-22  1:01   ` [dpdk-dev] [PATCH v4 21/21] testpmd: add test command " Jingjing Wu
2014-10-28 14:18     ` Thomas Monjalon
2014-10-29  2:35       ` Wu, Jingjing
2014-10-27 15:22   ` [dpdk-dev] [PATCH v4 00/21] Support flow director programming on Fortville Thomas Monjalon
2014-10-28  0:48   ` Zhang, Helin
2014-10-30  7:26   ` [dpdk-dev] [PATCH v5 " Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
2014-10-30  8:25       ` Wu, Jingjing
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 02/21] i40e: tear down " Jingjing Wu
2014-11-19  7:53       ` Cao, Min
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 03/21] i40e: initialize flexible payload setting Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 04/21] ethdev: define structures for adding/deleting flow director Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 05/21] i40e: implement operations to add/delete " Jingjing Wu
2014-11-05 21:18       ` De Lara Guarch, Pablo
2014-11-13  9:50         ` Thomas Monjalon
2014-11-13 11:36           ` Wu, Jingjing
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 06/21] testpmd: add test commands to add/delete flow director filter Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 07/21] i40e: match counter for flow director Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 08/21] mbuf: extend fdir field Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 09/21] i40e: report flow director match info to mbuf Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 10/21] testpmd: print extended fdir info in mbuf Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 11/21] ethdev: define structures for getting flow director information Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 12/21] i40e: implement operations to get fdir info Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 13/21] testpmd: display fdir statistics Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 14/21] i40e: implement operation to flush flow director table Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 15/21] testpmd: add test command " Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 16/21] ethdev: define structures for configuring flexible payload Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 17/21] i40e: implement operations to configure " Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 18/21] testpmd: add test command " Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 19/21] ethdev: define structures for configuring flex masks Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 20/21] i40e: implement operations to configure flexible masks Jingjing Wu
2014-10-30  7:26     ` [dpdk-dev] [PATCH v5 21/21] testpmd: add test command " Jingjing Wu
2014-10-30  8:07     ` [dpdk-dev] [PATCH v5 01/21] i40e: set up and initialize flow director Jingjing Wu
2014-11-21  0:46     ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 01/22] i40e: set up and initialize flow director Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 02/22] i40e: tear down " Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 03/22] i40e: initialize flexible payload setting Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 04/22] ethdev: define structures for adding/deleting flow director Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 05/22] i40e: define functions for transition between flow_type and pctype Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 06/22] i40e: implement operations to add/delete flow director Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 07/22] testpmd: add test commands to add/delete flow director filter Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 08/22] i40e: match counter for flow director Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 09/22] mbuf: extend fdir field Jingjing Wu
2014-11-21 17:03         ` Chilikin, Andrey
2014-11-21 19:34           ` Ananyev, Konstantin
2014-11-21 19:37             ` Chilikin, Andrey
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 10/22] i40e: report flow director match info to mbuf Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 11/22] testpmd: print extended fdir info in mbuf Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 12/22] i40e: implement operation to flush flow director table Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 13/22] testpmd: add test command " Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 14/22] ethdev: define structures for getting flow director information Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 15/22] i40e: implement operations to get fdir info Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 16/22] ethdev: define structures for getting flow director statistics Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 17/22] i40e: implement operations to get fdir statistics Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 18/22] testpmd: display fdir info Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 19/22] ethdev: add flexible payload setting in eth_conf Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 20/22] i40e: take flow director flexible payload configuration Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 21/22] testpmd: add test command to configure flexible mask Jingjing Wu
2014-11-21  0:46       ` [dpdk-dev] [PATCH v6 22/22] testpmd: add test command to configure flexible payload Jingjing Wu
2014-11-21 11:34       ` [dpdk-dev] [PATCH v6 00/22] Support flow director programming on Fortville Ananyev, Konstantin
2014-11-24 23:20         ` Thomas Monjalon
2014-11-25  4:51           ` Wu, Jingjing
2014-11-25  9:23             ` Thomas Monjalon
2014-10-30  7:34   ` [dpdk-dev] [PATCH v4 00/21] " Cao, Min
2014-11-19  7:53   ` Cao, Min
2014-10-30  7:12 ` [dpdk-dev] [PATCH v3 00/20] " Cao, Min

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).