DPDK patches and discussions
 help / color / mirror / Atom feed
* [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
@ 2014-09-25  6:59 Jingjing Wu
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition Jingjing Wu
                   ` (8 more replies)
  0 siblings, 9 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-09-25  6:59 UTC (permalink / raw)
  To: dev

The patch set enables control packet filter on Fortville.
Control packet filter can assign packet to specific destination by filtering with mac address and ethertype or only ethertype.

It mainly includes:
 - Use new filter mechanism discussed at http://dpdk.org/ml/archives/dev/2014-September/005179.html. 
 - control packet filter implementation in i40e pmd driver 

jingjing.wu (4):
  new filter APIs definition
  define CTRL_PKT filter type and its structure
  ctrl_pkt filter implementation in i40e pmd driver
  add commands for control packet filter

 app/test-pmd/cmdline.c            | 149 +++++++++++++++++++++++++++++++++++
 lib/librte_ether/Makefile         |   1 +
 lib/librte_ether/rte_eth_ctrl.h   | 102 ++++++++++++++++++++++++
 lib/librte_ether/rte_ethdev.c     |  32 ++++++++
 lib/librte_ether/rte_ethdev.h     |  44 +++++++++++
 lib/librte_pmd_i40e/i40e_ethdev.c | 161 ++++++++++++++++++++++++++++++++++++++
 6 files changed, 489 insertions(+)
 create mode 100644 lib/librte_ether/rte_eth_ctrl.h

-- 
1.8.1.4

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

* [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
@ 2014-09-25  6:59 ` Jingjing Wu
  2014-10-09 15:34   ` De Lara Guarch, Pablo
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 2/4] lib/librte_ether: define CTRL_PKT filter type and its structure Jingjing Wu
                   ` (7 subsequent siblings)
  8 siblings, 1 reply; 30+ messages in thread
From: Jingjing Wu @ 2014-09-25  6:59 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

As to the implemetation discussion, please refer to http://dpdk.org/ml/archives/dev/2014-September/005179.html, and control packet filter implementation is based on it.

Signed-off-by: Jingjing Wu <jingjing.wu@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] 30+ messages in thread

* [dpdk-dev] [PATCH 2/4] lib/librte_ether: define CTRL_PKT filter type and its structure
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition Jingjing Wu
@ 2014-09-25  6:59 ` Jingjing Wu
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 3/4] i40e: ctrl_pkt filter implementation in i40e pmd driver Jingjing Wu
                   ` (6 subsequent siblings)
  8 siblings, 0 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-09-25  6:59 UTC (permalink / raw)
  To: dev

define new filter type and its structure
 - RTE_ETH_FILTER_CTRL_PKT
 - struct rte_ctrl_pkt_filter

Signed-off-by: Jingjing Wu <jingjing.wu@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 34ab278..ff686be 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_RSS,
 	RTE_ETH_FILTER_FDIR,
+	RTE_ETH_FILTER_CTRL_PKT,
 	RTE_ETH_FILTER_MAX,
 };
 
@@ -71,6 +72,29 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_OP_MAX,
 };
 
+/**
+ * Define all structures for Control Packet Filter type corresponding with specific operations.
+ */
+
+#define RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC    0x0001
+#define RTE_CONTROL_PACKET_FLAGS_DROP          0x0002
+#define RTE_CONTROL_PACKET_FLAGS_TO_QUEUE      0x0004
+#define RTE_CONTROL_PACKET_FLAGS_TX            0x0008
+#define RTE_CONTROL_PACKET_FLAGS_RX            0x0000
+
+/**
+ * A structure used to define the control packet filter entry
+ * to support RTE_ETH_FILTER_CTRL_PKT with RTE_ETH_FILTER_OP_ADD
+ * and RTE_ETH_FILTER_OP_DELETE operations.
+ */
+struct rte_ctrl_pkt_filter {
+	struct ether_addr mac_addr;   /**< mac address to match. */
+	uint16_t ether_type;          /**< ether type to match */
+	uint16_t flags;               /**< options for filter's behavior*/
+	uint16_t dest_id;             /**< destination vsi id or pool id*/
+	uint16_t queue;               /**< queue assign to if TO QUEUE flag is set */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

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

* [dpdk-dev] [PATCH 3/4] i40e: ctrl_pkt filter implementation in i40e pmd driver
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition Jingjing Wu
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 2/4] lib/librte_ether: define CTRL_PKT filter type and its structure Jingjing Wu
@ 2014-09-25  6:59 ` Jingjing Wu
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 4/4] app/test-pmd: add commands for control packet filter Jingjing Wu
                   ` (5 subsequent siblings)
  8 siblings, 0 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-09-25  6:59 UTC (permalink / raw)
  To: dev

Implement control packet filter, support add and delete operations.
It can assign packets to specific queue or vsi by filtering with mac address and ethertype or only
 ethertype on both rx and tx directions.

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

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index a00d6ca..ab662ff 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -205,6 +205,15 @@ 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_ctrl_pkt_filter_set(struct i40e_pf *pf,
+			struct rte_ctrl_pkt_filter *cp_filter,
+			bool add);
+static int i40e_ctrl_pkt_filter_handle(struct i40e_pf *pf,
+				enum rte_filter_op filter_op,
+				void *arg);
+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 +265,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 = {
@@ -4131,3 +4141,154 @@ i40e_pf_config_mq_rx(struct i40e_pf *pf)
 
 	return 0;
 }
+
+/* Look up vsi by vsi_id */
+static struct i40e_vsi *
+i40e_vsi_lookup_by_id(struct i40e_vsi *uplink_vsi, uint16_t id)
+{
+	struct i40e_vsi *vsi = NULL;
+	struct i40e_vsi_list *vsi_list;
+
+	if (uplink_vsi == NULL)
+		return NULL;
+
+	if (uplink_vsi->vsi_id == id)
+		return vsi;
+
+	/* if VSI has child to attach*/
+	if (uplink_vsi->veb) {
+		TAILQ_FOREACH(vsi_list, &uplink_vsi->veb->head, list) {
+			vsi = i40e_vsi_lookup_by_id(vsi_list->vsi, id);
+			if (vsi)
+				return vsi;
+		}
+	}
+	return NULL;
+}
+
+/*
+ * Configure control packet filter, which can director packet by filtering
+ * with mac address and ether_type or only ether_type
+ */
+static int
+i40e_ctrl_pkt_filter_set(struct i40e_pf *pf,
+			struct rte_ctrl_pkt_filter *cp_filter,
+			bool add)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_control_filter_stats stats;
+	struct i40e_vsi *vsi = NULL;
+	uint16_t seid;
+	uint16_t flags = 0;
+	int ret;
+
+	if (cp_filter->ether_type == ETHER_TYPE_IPv4 ||
+		cp_filter->ether_type == ETHER_TYPE_IPv6) {
+		PMD_DRV_LOG(ERR, "unsupported ether_type(0x%04x) in"
+			" control packet filter.", cp_filter->ether_type);
+		return -EINVAL;
+	}
+	if (cp_filter->ether_type == ETHER_TYPE_VLAN)
+		PMD_DRV_LOG(WARNING, "filter vlan ether_type in first tag is"
+			" not supported.");
+
+	if (cp_filter->dest_id == 0)
+		/* Use LAN VSI Id if not programmed by user */
+		vsi = pf->main_vsi;
+	else {
+		vsi = i40e_vsi_lookup_by_id(pf->main_vsi, cp_filter->dest_id);
+		if (vsi == NULL || vsi->type == I40E_VSI_FDIR) {
+			PMD_DRV_LOG(ERR, "VSI arg is invalid\n");
+			return -EINVAL;
+		}
+	}
+
+	seid = vsi->seid;
+	memset(&stats, 0, sizeof(stats));
+
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_TX)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_TX;
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_IGNORE_MAC;
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_TO_QUEUE)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_TO_QUEUE;
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_DROP)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_DROP;
+
+	ret = i40e_aq_add_rem_control_packet_filter(hw,
+			cp_filter->mac_addr.addr_bytes,
+			cp_filter->ether_type, flags,
+			seid, cp_filter->queue, add, &stats, NULL);
+
+	PMD_DRV_LOG(INFO, "add/rem control packet filter, return %d,"
+			 " mac_etype_used = %u, etype_used = %u,"
+			 " mac_etype_free = %u, etype_free = %u\n",
+			 ret, stats.mac_etype_used, stats.etype_used,
+			 stats.mac_etype_free, stats.etype_free);
+	if (ret < 0)
+		return -ENOSYS;
+	return 0;
+}
+
+/*
+ * Handle operations for control packte filter type.
+ */
+static int
+i40e_ctrl_pkt_filter_handle(struct i40e_pf *pf,
+				enum rte_filter_op filter_op,
+				void *arg)
+{
+	int ret = 0;
+
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_OP_NONE) {
+		PMD_DRV_LOG(ERR, "arg shouldn't be NULL for operation %u\n",
+			    filter_op);
+		return -EINVAL;
+	}
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_OP_NONE:
+		ret = 0;
+		break;
+	case RTE_ETH_FILTER_OP_ADD:
+		ret = i40e_ctrl_pkt_filter_set(pf,
+			(struct rte_ctrl_pkt_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_OP_DELETE:
+		ret = i40e_ctrl_pkt_filter_set(pf,
+			(struct rte_ctrl_pkt_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unsupported operation %u\n", filter_op);
+		ret = -ENOSYS;
+		break;
+	}
+	return ret;
+}
+
+/*
+ * 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_CTRL_PKT:
+		ret = i40e_ctrl_pkt_filter_handle(pf, filter_op, arg);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unsupported filter type %u.", filter_type);
+		ret = -EINVAL;
+		break;
+	}
+	return ret;
+}
-- 
1.8.1.4

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

* [dpdk-dev] [PATCH 4/4] app/test-pmd: add commands for control packet filter
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
                   ` (2 preceding siblings ...)
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 3/4] i40e: ctrl_pkt filter implementation in i40e pmd driver Jingjing Wu
@ 2014-09-25  6:59 ` Jingjing Wu
  2014-09-25  7:54 ` [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Zhang, Helin
                   ` (4 subsequent siblings)
  8 siblings, 0 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-09-25  6:59 UTC (permalink / raw)
  To: dev

Add command to test control packet filter
 - add/delete control packet filter

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

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 225f669..1354230 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -660,6 +660,12 @@ 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"
+
+			"ctrl_pkt_filter (port_id) (add|del)"
+			"mac_addr (mac_address) ethertype (ether_type)"
+			"(none|options) queue (queue_id)\n"
+			"    Add/Del a control packet filter.\n\n"
+
 		);
 	}
 }
@@ -7411,6 +7417,148 @@ cmdline_parse_inst_t cmd_get_flex_filter = {
 	},
 };
 
+/* *** Filters Control *** */
+
+static inline int
+parse_ctrl_pkt_filter_options(const char *q_arg,
+			     uint16_t *flags)
+{
+#define MAX_NUM_OPTIONS 3
+	char s[256];
+	char *str_fld[MAX_NUM_OPTIONS];
+	int i;
+	int num_options = -1;
+	unsigned size;
+
+	*flags = 0;
+	if (!strcmp(q_arg, "none"))
+		return 0;
+
+	size = strnlen(q_arg, sizeof(s));
+	snprintf(s, sizeof(s), "%.*s", size, q_arg);
+	num_options = rte_strsplit(s, sizeof(s), str_fld, MAX_NUM_OPTIONS, '-');
+	/* multi-options are combined by - */
+	if (num_options < 0 || num_options > MAX_NUM_OPTIONS)
+		return -1;
+	for (i = 0; i < num_options; i++) {
+		if (!strcmp(str_fld[i], "tx"))
+			*flags |= RTE_CONTROL_PACKET_FLAGS_TX;
+		if (!strcmp(str_fld[i], "mac_ignr"))
+			*flags |= RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC;
+		if (!strcmp(str_fld[i], "drop"))
+			*flags |= RTE_CONTROL_PACKET_FLAGS_DROP;
+	}
+	return num_options;
+}
+
+struct cmd_ctrl_pkt_filter_result {
+	cmdline_fixed_string_t filter;
+	uint8_t port_id;
+	cmdline_fixed_string_t ops;
+	cmdline_fixed_string_t mac_addr;
+	struct ether_addr mac_addr_value;
+	cmdline_fixed_string_t ethertype;
+	uint16_t ethertype_value;
+	cmdline_fixed_string_t options;
+	cmdline_fixed_string_t queue;
+	uint16_t  queue_id;
+};
+
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_filter =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 filter, "ctrl_pkt_filter");
+cmdline_parse_token_num_t cmd_ctrl_pkt_filter_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_ops =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 ops, "add#del");
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_mac_addr =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 mac_addr, "mac_addr");
+cmdline_parse_token_etheraddr_t cmd_ctrl_pkt_filter_mac_addr_value =
+	TOKEN_ETHERADDR_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				     mac_addr_value);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_ethertype =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 ethertype, "ethertype");
+cmdline_parse_token_num_t cmd_ctrl_pkt_filter_ethertype_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+			      ethertype_value, UINT16);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_options =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 options, NULL);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_queue =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 queue, "queue");
+cmdline_parse_token_num_t cmd_ctrl_pkt_filter_queue_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+			      queue_id, UINT16);
+
+static void
+cmd_ctrl_pkt_filter_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_ctrl_pkt_filter_result *res = parsed_result;
+	struct rte_ctrl_pkt_filter filter;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_CTRL_PKT);
+	if (ret < 0) {
+		printf("control packet filter is not supported on port %u. \n",
+			res->port_id);
+		return;
+	}
+
+	memset(&filter, 0, sizeof(filter));
+
+	(void)rte_memcpy(&filter.mac_addr, &res->mac_addr_value,
+		sizeof(struct ether_addr));
+	filter.ether_type = res->ethertype_value;
+
+	ret = parse_ctrl_pkt_filter_options(res->options, &filter.flags);
+	if (ret < 0) {
+		printf("options input is invalid. \n");
+		return;
+	}
+	if (!(filter.flags & RTE_CONTROL_PACKET_FLAGS_DROP)) {
+		filter.flags |= RTE_CONTROL_PACKET_FLAGS_TO_QUEUE;
+		filter.queue = res->queue_id;
+	}
+	if (!strcmp(res->ops, "add"))
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+				RTE_ETH_FILTER_CTRL_PKT,
+				RTE_ETH_FILTER_OP_ADD,
+				&filter);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+				RTE_ETH_FILTER_CTRL_PKT,
+				RTE_ETH_FILTER_OP_DELETE,
+				&filter);
+	if (ret < 0)
+		printf("control packet filter programming error: (%s)\n", strerror(-ret));
+}
+
+cmdline_parse_inst_t cmd_ctrl_pkt_filter = {
+	.f = cmd_ctrl_pkt_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a control packet filter entry",
+	.tokens = {
+		(void *)&cmd_ctrl_pkt_filter_filter,
+		(void *)&cmd_ctrl_pkt_filter_port_id,
+		(void *)&cmd_ctrl_pkt_filter_ops,
+		(void *)&cmd_ctrl_pkt_filter_mac_addr,
+		(void *)&cmd_ctrl_pkt_filter_mac_addr_value,
+		(void *)&cmd_ctrl_pkt_filter_ethertype,
+		(void *)&cmd_ctrl_pkt_filter_ethertype_value,
+		(void *)&cmd_ctrl_pkt_filter_options,
+		(void *)&cmd_ctrl_pkt_filter_queue,
+		(void *)&cmd_ctrl_pkt_filter_queue_id,
+		NULL,
+	},
+};
+
 /* ******************************************************************************** */
 
 /* list of instructions */
@@ -7537,6 +7685,7 @@ 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_ctrl_pkt_filter,
 	NULL,
 };
 
-- 
1.8.1.4

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

* Re: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
                   ` (3 preceding siblings ...)
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 4/4] app/test-pmd: add commands for control packet filter Jingjing Wu
@ 2014-09-25  7:54 ` Zhang, Helin
  2014-10-11  7:23 ` Chen, Jing D
                   ` (3 subsequent siblings)
  8 siblings, 0 replies; 30+ messages in thread
From: Zhang, Helin @ 2014-09-25  7:54 UTC (permalink / raw)
  To: Wu, Jingjing, dev

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

Great to have these patches!

> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, September 25, 2014 2:59 PM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
> 
> The patch set enables control packet filter on Fortville.
> Control packet filter can assign packet to specific destination by filtering with
> mac address and ethertype or only ethertype.
> 
> It mainly includes:
>  - Use new filter mechanism discussed at
> http://dpdk.org/ml/archives/dev/2014-September/005179.html.
>  - control packet filter implementation in i40e pmd driver
> 
> jingjing.wu (4):
>   new filter APIs definition
>   define CTRL_PKT filter type and its structure
>   ctrl_pkt filter implementation in i40e pmd driver
>   add commands for control packet filter
> 
>  app/test-pmd/cmdline.c            | 149
> +++++++++++++++++++++++++++++++++++
>  lib/librte_ether/Makefile         |   1 +
>  lib/librte_ether/rte_eth_ctrl.h   | 102 ++++++++++++++++++++++++
>  lib/librte_ether/rte_ethdev.c     |  32 ++++++++
>  lib/librte_ether/rte_ethdev.h     |  44 +++++++++++
>  lib/librte_pmd_i40e/i40e_ethdev.c | 161
> ++++++++++++++++++++++++++++++++++++++
>  6 files changed, 489 insertions(+)
>  create mode 100644 lib/librte_ether/rte_eth_ctrl.h
> 
> --
> 1.8.1.4

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

* Re: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
  2014-09-25  6:59 ` [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition Jingjing Wu
@ 2014-10-09 15:34   ` De Lara Guarch, Pablo
  2014-10-10  1:19     ` Wu, Jingjing
  2014-10-10  3:34     ` Wu, Jingjing
  0 siblings, 2 replies; 30+ messages in thread
From: De Lara Guarch, Pablo @ 2014-10-09 15:34 UTC (permalink / raw)
  To: Wu, Jingjing, dev

Hi,

> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, September 25, 2014 7:59 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
> 
> Define new APIs to support configure multi-kind filters using same APIs
>  - rte_eth_dev_filter_supported
>  - rte_eth_dev_filter_ctrl
> 
> As to the implemetation discussion, please refer to
> http://dpdk.org/ml/archives/dev/2014-September/005179.html, and control
> packet filter implementation is based on it.

This patch is also present on the patchset Support flow director programming on Fortville.
Should this patchset be rejected then or just this patch? In second case, could you send a v2 without this patch?

Thanks,
Pablo
> 
> Signed-off-by: Jingjing Wu <jingjing.wu@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] 30+ messages in thread

* Re: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
  2014-10-09 15:34   ` De Lara Guarch, Pablo
@ 2014-10-10  1:19     ` Wu, Jingjing
  2014-10-10  3:34     ` Wu, Jingjing
  1 sibling, 0 replies; 30+ messages in thread
From: Wu, Jingjing @ 2014-10-10  1:19 UTC (permalink / raw)
  To: De Lara Guarch, Pablo, dev

Hi

> -----Original Message-----
> From: De Lara Guarch, Pablo
> Sent: Thursday, October 09, 2014 11:35 PM
> To: Wu, Jingjing; dev@dpdk.org
> Subject: RE: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> definition
> 
> Hi,
> 
> > -----Original Message-----
> > From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> > Sent: Thursday, September 25, 2014 7:59 AM
> > To: dev@dpdk.org
> > Subject: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> > definition
> >
> > Define new APIs to support configure multi-kind filters using same
> > APIs
> >  - rte_eth_dev_filter_supported
> >  - rte_eth_dev_filter_ctrl
> >
> > As to the implemetation discussion, please refer to
> > http://dpdk.org/ml/archives/dev/2014-September/005179.html, and
> > control packet filter implementation is based on it.
> 
> This patch is also present on the patchset Support flow director programming
> on Fortville.
> Should this patchset be rejected then or just this patch? In second case,
> could you send a v2 without this patch?

I think this patch does not only present on the flow director patchset, but also on mac vlan support patchset, vxlan patchset, and so on. All of them are using the same new filter APIs. If any patchset is applied, others may require some modification (just as you said to remove this pacth).

> 
> Thanks,
> Pablo
> >
> > Signed-off-by: Jingjing Wu <jingjing.wu@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] 30+ messages in thread

* Re: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
  2014-10-09 15:34   ` De Lara Guarch, Pablo
  2014-10-10  1:19     ` Wu, Jingjing
@ 2014-10-10  3:34     ` Wu, Jingjing
  2014-10-10  7:28       ` De Lara Guarch, Pablo
  1 sibling, 1 reply; 30+ messages in thread
From: Wu, Jingjing @ 2014-10-10  3:34 UTC (permalink / raw)
  To: De Lara Guarch, Pablo, dev



> -----Original Message-----
> From: Wu, Jingjing
> Sent: Friday, October 10, 2014 9:20 AM
> To: De Lara Guarch, Pablo; dev@dpdk.org
> Subject: RE: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> definition
> 
> Hi
> 
> > -----Original Message-----
> > From: De Lara Guarch, Pablo
> > Sent: Thursday, October 09, 2014 11:35 PM
> > To: Wu, Jingjing; dev@dpdk.org
> > Subject: RE: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> > definition
> >
> > Hi,
> >
> > > -----Original Message-----
> > > From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> > > Sent: Thursday, September 25, 2014 7:59 AM
> > > To: dev@dpdk.org
> > > Subject: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> > > definition
> > >
> > > Define new APIs to support configure multi-kind filters using same
> > > APIs
> > >  - rte_eth_dev_filter_supported
> > >  - rte_eth_dev_filter_ctrl
> > >
> > > As to the implemetation discussion, please refer to
> > > http://dpdk.org/ml/archives/dev/2014-September/005179.html, and
> > > control packet filter implementation is based on it.
> >
> > This patch is also present on the patchset Support flow director
> > programming on Fortville.
> > Should this patchset be rejected then or just this patch? In second
> > case, could you send a v2 without this patch?
> 
> I think this patch does not only present on the flow director patchset, but
> also on mac vlan support patchset, vxlan patchset, and so on. All of them are
> using the same new filter APIs. If any patchset is applied, others may require
> some modification (just as you said to remove this pacth).
> 
Additional, without the patch, this patchset cannot work separately. More than one features depend on the new filter APIs, but none patchset contains the new filter APIs is applied currently.  That's why each patchset has such patch.

Thanks 
JIngjing
> >
> > Thanks,
> > Pablo
> > >
> > > Signed-off-by: Jingjing Wu <jingjing.wu@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] 30+ messages in thread

* Re: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
  2014-10-10  3:34     ` Wu, Jingjing
@ 2014-10-10  7:28       ` De Lara Guarch, Pablo
  2014-10-16 15:11         ` Thomas Monjalon
  0 siblings, 1 reply; 30+ messages in thread
From: De Lara Guarch, Pablo @ 2014-10-10  7:28 UTC (permalink / raw)
  To: Wu, Jingjing, dev



> -----Original Message-----
> From: Wu, Jingjing
> Sent: Friday, October 10, 2014 4:34 AM
> To: De Lara Guarch, Pablo; dev@dpdk.org
> Subject: RE: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> definition
> 
> 
> 
> > -----Original Message-----
> > From: Wu, Jingjing
> > Sent: Friday, October 10, 2014 9:20 AM
> > To: De Lara Guarch, Pablo; dev@dpdk.org
> > Subject: RE: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> > definition
> >
> > Hi
> >
> > > -----Original Message-----
> > > From: De Lara Guarch, Pablo
> > > Sent: Thursday, October 09, 2014 11:35 PM
> > > To: Wu, Jingjing; dev@dpdk.org
> > > Subject: RE: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> > > definition
> > >
> > > Hi,
> > >
> > > > -----Original Message-----
> > > > From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> > > > Sent: Thursday, September 25, 2014 7:59 AM
> > > > To: dev@dpdk.org
> > > > Subject: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs
> > > > definition
> > > >
> > > > Define new APIs to support configure multi-kind filters using same
> > > > APIs
> > > >  - rte_eth_dev_filter_supported
> > > >  - rte_eth_dev_filter_ctrl
> > > >
> > > > As to the implemetation discussion, please refer to
> > > > http://dpdk.org/ml/archives/dev/2014-September/005179.html, and
> > > > control packet filter implementation is based on it.
> > >
> > > This patch is also present on the patchset Support flow director
> > > programming on Fortville.
> > > Should this patchset be rejected then or just this patch? In second
> > > case, could you send a v2 without this patch?
> >
> > I think this patch does not only present on the flow director patchset, but
> > also on mac vlan support patchset, vxlan patchset, and so on. All of them
> are
> > using the same new filter APIs. If any patchset is applied, others may
> require
> > some modification (just as you said to remove this pacth).
> >
> Additional, without the patch, this patchset cannot work separately. More
> than one features depend on the new filter APIs, but none patchset contains
> the new filter APIs is applied currently.  That's why each patchset has such
> patch.

I see, then probably the best idea would have been send this patch separately,
 and just say that these patchsets depend on this patch, basically because
 if you try to apply all these patches, you are going to get failures.

Anyway, good to know. Thanks,
Pablo
> 
> Thanks
> JIngjing
> > >
> > > Thanks,
> > > Pablo
> > > >
> > > > Signed-off-by: Jingjing Wu <jingjing.wu@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] 30+ messages in thread

* Re: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
                   ` (4 preceding siblings ...)
  2014-09-25  7:54 ` [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Zhang, Helin
@ 2014-10-11  7:23 ` Chen, Jing D
  2014-10-11  7:23 ` Liu, Jijiang
                   ` (2 subsequent siblings)
  8 siblings, 0 replies; 30+ messages in thread
From: Chen, Jing D @ 2014-10-11  7:23 UTC (permalink / raw)
  To: Wu, Jingjing, dev



> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, September 25, 2014 2:59 PM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
> 
> The patch set enables control packet filter on Fortville.
> Control packet filter can assign packet to specific destination by filtering with
> mac address and ethertype or only ethertype.
> 
> It mainly includes:
>  - Use new filter mechanism discussed at
> http://dpdk.org/ml/archives/dev/2014-September/005179.html.
>  - control packet filter implementation in i40e pmd driver
> 
> jingjing.wu (4):
>   new filter APIs definition
>   define CTRL_PKT filter type and its structure
>   ctrl_pkt filter implementation in i40e pmd driver
>   add commands for control packet filter
> 
>  app/test-pmd/cmdline.c            | 149
> +++++++++++++++++++++++++++++++++++
>  lib/librte_ether/Makefile         |   1 +
>  lib/librte_ether/rte_eth_ctrl.h   | 102 ++++++++++++++++++++++++
>  lib/librte_ether/rte_ethdev.c     |  32 ++++++++
>  lib/librte_ether/rte_ethdev.h     |  44 +++++++++++
>  lib/librte_pmd_i40e/i40e_ethdev.c | 161
> ++++++++++++++++++++++++++++++++++++++
>  6 files changed, 489 insertions(+)
>  create mode 100644 lib/librte_ether/rte_eth_ctrl.h
> 
> --
> 1.8.1.4

Acked-by: Jing Chen <jing.d.chen@intel.com>

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

* Re: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
                   ` (5 preceding siblings ...)
  2014-10-11  7:23 ` Chen, Jing D
@ 2014-10-11  7:23 ` Liu, Jijiang
  2014-10-11  7:53 ` Zhang, Helin
  2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
  8 siblings, 0 replies; 30+ messages in thread
From: Liu, Jijiang @ 2014-10-11  7:23 UTC (permalink / raw)
  To: Wu, Jingjing, dev


> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, September 25, 2014 2:59 PM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
> 
> The patch set enables control packet filter on Fortville.
> Control packet filter can assign packet to specific destination by filtering with
> mac address and ethertype or only ethertype.
> 
> It mainly includes:
>  - Use new filter mechanism discussed at
> http://dpdk.org/ml/archives/dev/2014-September/005179.html.
>  - control packet filter implementation in i40e pmd driver
> 
> jingjing.wu (4):
>   new filter APIs definition
>   define CTRL_PKT filter type and its structure
>   ctrl_pkt filter implementation in i40e pmd driver
>   add commands for control packet filter
> 
>  app/test-pmd/cmdline.c            | 149
> +++++++++++++++++++++++++++++++++++
>  lib/librte_ether/Makefile         |   1 +
>  lib/librte_ether/rte_eth_ctrl.h   | 102 ++++++++++++++++++++++++
>  lib/librte_ether/rte_ethdev.c     |  32 ++++++++
>  lib/librte_ether/rte_ethdev.h     |  44 +++++++++++
>  lib/librte_pmd_i40e/i40e_ethdev.c | 161
> ++++++++++++++++++++++++++++++++++++++
>  6 files changed, 489 insertions(+)
>  create mode 100644 lib/librte_ether/rte_eth_ctrl.h
> 
> --
> 1.8.1.4

Acked-by: Jijiang Liu <Jijiang.liu@intel.com>

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

* Re: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
                   ` (6 preceding siblings ...)
  2014-10-11  7:23 ` Liu, Jijiang
@ 2014-10-11  7:53 ` Zhang, Helin
  2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
  8 siblings, 0 replies; 30+ messages in thread
From: Zhang, Helin @ 2014-10-11  7:53 UTC (permalink / raw)
  To: Wu, Jingjing, dev

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

> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, September 25, 2014 2:59 PM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville
> 
> The patch set enables control packet filter on Fortville.
> Control packet filter can assign packet to specific destination by filtering with
> mac address and ethertype or only ethertype.
> 
> It mainly includes:
>  - Use new filter mechanism discussed at
> http://dpdk.org/ml/archives/dev/2014-September/005179.html.
>  - control packet filter implementation in i40e pmd driver
> 
> jingjing.wu (4):
>   new filter APIs definition
>   define CTRL_PKT filter type and its structure
>   ctrl_pkt filter implementation in i40e pmd driver
>   add commands for control packet filter
> 
>  app/test-pmd/cmdline.c            | 149
> +++++++++++++++++++++++++++++++++++
>  lib/librte_ether/Makefile         |   1 +
>  lib/librte_ether/rte_eth_ctrl.h   | 102 ++++++++++++++++++++++++
>  lib/librte_ether/rte_ethdev.c     |  32 ++++++++
>  lib/librte_ether/rte_ethdev.h     |  44 +++++++++++
>  lib/librte_pmd_i40e/i40e_ethdev.c | 161
> ++++++++++++++++++++++++++++++++++++++
>  6 files changed, 489 insertions(+)
>  create mode 100644 lib/librte_ether/rte_eth_ctrl.h
> 
> --
> 1.8.1.4

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

* Re: [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition
  2014-10-10  7:28       ` De Lara Guarch, Pablo
@ 2014-10-16 15:11         ` Thomas Monjalon
  0 siblings, 0 replies; 30+ messages in thread
From: Thomas Monjalon @ 2014-10-16 15:11 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

2014-10-10 07:28, De Lara Guarch, Pablo:
> > > > > Define new APIs to support configure multi-kind filters using same
> > > > > APIs
> > > > >  - rte_eth_dev_filter_supported
> > > > >  - rte_eth_dev_filter_ctrl
> > > > >
> > > > > As to the implemetation discussion, please refer to
> > > > > http://dpdk.org/ml/archives/dev/2014-September/005179.html, and
> > > > > control packet filter implementation is based on it.
> > > >
> > > > This patch is also present on the patchset Support flow director
> > > > programming on Fortville.
> > > > Should this patchset be rejected then or just this patch? In second
> > > > case, could you send a v2 without this patch?
> > >
> > > I think this patch does not only present on the flow director patchset, but
> > > also on mac vlan support patchset, vxlan patchset, and so on. All of them
> > are
> > > using the same new filter APIs. If any patchset is applied, others may
> > require
> > > some modification (just as you said to remove this pacth).
> > >
> > Additional, without the patch, this patchset cannot work separately. More
> > than one features depend on the new filter APIs, but none patchset contains
> > the new filter APIs is applied currently.  That's why each patchset has such
> > patch.
> 
> I see, then probably the best idea would have been send this patch separately,
>  and just say that these patchsets depend on this patch, basically because
>  if you try to apply all these patches, you are going to get failures.

Yes, sending a separated patch and explicitly base your patch on this one
would be really easier to understand. And more generally, it's easier when
things are explained. You won't have to pay for the extra words you put in
your cover letter ;)

There is another problem with this patch: there are many versions around with
different logs and even different authors!

-- 
Thomas

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

* [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville
  2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
                   ` (7 preceding siblings ...)
  2014-10-11  7:53 ` Zhang, Helin
@ 2014-10-22  8:19 ` Jingjing Wu
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure Jingjing Wu
                     ` (3 more replies)
  8 siblings, 4 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-10-22  8:19 UTC (permalink / raw)
  To: dev

The patch set enables control packet filter on Fortville.
Control packet filter can assign packet to specific destination
by filtering with mac address and ethertype or only ethertype.

v2 changes:
 - strip the filter APIs definitions from this patch set

Jingjing Wu (3):
  ethdev: define ctrl_pkt filter type and its structure
  i40e: ctrl_pkt filter implementation in i40e pmd driver
  testpmd: Commands to test ctrl_pkt filter

 app/test-pmd/cmdline.c            | 149 ++++++++++++++++++++++++++++++++++++++
 lib/librte_ether/rte_eth_ctrl.h   |  24 ++++++
 lib/librte_pmd_i40e/i40e_ethdev.c | 138 ++++++++++++++++++++++++++++++++++-
 3 files changed, 309 insertions(+), 2 deletions(-)

-- 
1.8.1.4

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

* [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
@ 2014-10-22  8:19   ` Jingjing Wu
  2014-10-30 22:47     ` Thomas Monjalon
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 2/3] i40e: ctrl_pkt filter implementation in i40e pmd driver Jingjing Wu
                     ` (2 subsequent siblings)
  3 siblings, 1 reply; 30+ messages in thread
From: Jingjing Wu @ 2014-10-22  8:19 UTC (permalink / raw)
  To: dev

define new filter type and its structure
 - RTE_ETH_FILTER_CTRL_PKT
 - struct rte_ctrl_pkt_filter

Signed-off-by: Jingjing Wu <jingjing.wu@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 df21ac6..8d3dba9 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_CTRL_PKT,
 	RTE_ETH_FILTER_MAX
 };
 
@@ -71,6 +72,29 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_OP_MAX
 };
 
+/**
+ * Define all structures for Control Packet Filter type corresponding with specific operations.
+ */
+
+#define RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC    0x0001
+#define RTE_CONTROL_PACKET_FLAGS_DROP          0x0002
+#define RTE_CONTROL_PACKET_FLAGS_TO_QUEUE      0x0004
+#define RTE_CONTROL_PACKET_FLAGS_TX            0x0008
+#define RTE_CONTROL_PACKET_FLAGS_RX            0x0000
+
+/**
+ * A structure used to define the control packet filter entry
+ * to support RTE_ETH_FILTER_CTRL_PKT with RTE_ETH_FILTER_ADD
+ * and RTE_ETH_FILTER_DELETE operations.
+ */
+struct rte_ctrl_pkt_filter {
+	struct ether_addr mac_addr;   /**< mac address to match. */
+	uint16_t ether_type;          /**< ether type to match */
+	uint16_t flags;               /**< options for filter's behavior*/
+	uint16_t dest_id;             /**< destination vsi id or pool id*/
+	uint16_t queue;               /**< queue assign to if TO QUEUE flag is set */
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

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

* [dpdk-dev] [PATCH v2 2/3] i40e: ctrl_pkt filter implementation in i40e pmd driver
  2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure Jingjing Wu
@ 2014-10-22  8:19   ` Jingjing Wu
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 3/3] testpmd: Commands to test ctrl_pkt filter Jingjing Wu
  2014-11-13 12:49   ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Jingjing Wu
  3 siblings, 0 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-10-22  8:19 UTC (permalink / raw)
  To: dev

implement control packet filter, support add and delete operations.
It can assign packets to specific queue or vsi by filtering with mac
address and ethertype or only ethertype on both rx and tx directions.

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

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 3b75f0f..943b01a 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -186,6 +186,12 @@ 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_ctrl_pkt_filter_set(struct i40e_pf *pf,
+			struct rte_ctrl_pkt_filter *cp_filter,
+			bool add);
+static int i40e_ctrl_pkt_filter_handle(struct i40e_pf *pf,
+				enum rte_filter_op filter_op,
+				void *arg);
 static int i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 				enum rte_filter_type filter_type,
 				enum rte_filter_op filter_op,
@@ -4145,20 +4151,148 @@ i40e_pf_config_mq_rx(struct i40e_pf *pf)
 	return 0;
 }
 
+/* Look up vsi by vsi_id */
+static struct i40e_vsi *
+i40e_vsi_lookup_by_id(struct i40e_vsi *uplink_vsi, uint16_t id)
+{
+	struct i40e_vsi *vsi = NULL;
+	struct i40e_vsi_list *vsi_list;
+
+	if (uplink_vsi == NULL)
+		return NULL;
+
+	if (uplink_vsi->vsi_id == id)
+		return vsi;
+
+	/* if VSI has child to attach*/
+	if (uplink_vsi->veb) {
+		TAILQ_FOREACH(vsi_list, &uplink_vsi->veb->head, list) {
+			vsi = i40e_vsi_lookup_by_id(vsi_list->vsi, id);
+			if (vsi)
+				return vsi;
+		}
+	}
+	return NULL;
+}
+
+/*
+ * Configure control packet filter, which can director packet by filtering
+ * with mac address and ether_type or only ether_type
+ */
+static int
+i40e_ctrl_pkt_filter_set(struct i40e_pf *pf,
+			struct rte_ctrl_pkt_filter *cp_filter,
+			bool add)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_control_filter_stats stats;
+	struct i40e_vsi *vsi = NULL;
+	uint16_t seid;
+	uint16_t flags = 0;
+	int ret;
+
+	if (cp_filter->ether_type == ETHER_TYPE_IPv4 ||
+		cp_filter->ether_type == ETHER_TYPE_IPv6) {
+		PMD_DRV_LOG(ERR, "unsupported ether_type(0x%04x) in"
+			" control packet filter.", cp_filter->ether_type);
+		return -EINVAL;
+	}
+	if (cp_filter->ether_type == ETHER_TYPE_VLAN)
+		PMD_DRV_LOG(WARNING, "filter vlan ether_type in first tag is"
+			" not supported.");
+
+	if (cp_filter->dest_id == 0)
+		/* Use LAN VSI Id if not programmed by user */
+		vsi = pf->main_vsi;
+	else {
+		vsi = i40e_vsi_lookup_by_id(pf->main_vsi, cp_filter->dest_id);
+		if (vsi == NULL || vsi->type == I40E_VSI_FDIR) {
+			PMD_DRV_LOG(ERR, "VSI arg is invalid\n");
+			return -EINVAL;
+		}
+	}
+
+	seid = vsi->seid;
+	memset(&stats, 0, sizeof(stats));
+
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_TX)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_TX;
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_IGNORE_MAC;
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_TO_QUEUE)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_TO_QUEUE;
+	if (cp_filter->flags & RTE_CONTROL_PACKET_FLAGS_DROP)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_DROP;
+
+	ret = i40e_aq_add_rem_control_packet_filter(hw,
+			cp_filter->mac_addr.addr_bytes,
+			cp_filter->ether_type, flags,
+			seid, cp_filter->queue, add, &stats, NULL);
+
+	PMD_DRV_LOG(INFO, "add/rem control packet filter, return %d,"
+			 " mac_etype_used = %u, etype_used = %u,"
+			 " mac_etype_free = %u, etype_free = %u\n",
+			 ret, stats.mac_etype_used, stats.etype_used,
+			 stats.mac_etype_free, stats.etype_free);
+	if (ret < 0)
+		return -ENOSYS;
+	return 0;
+}
+
+/*
+ * Handle operations for control packte filter type.
+ */
+static int
+i40e_ctrl_pkt_filter_handle(struct i40e_pf *pf,
+				enum rte_filter_op filter_op,
+				void *arg)
+{
+	int ret = 0;
+
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_NOP) {
+		PMD_DRV_LOG(ERR, "arg shouldn't be NULL for operation %u\n",
+			    filter_op);
+		return -EINVAL;
+	}
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_NOP:
+		ret = 0;
+		break;
+	case RTE_ETH_FILTER_ADD:
+		ret = i40e_ctrl_pkt_filter_set(pf,
+			(struct rte_ctrl_pkt_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_DELETE:
+		ret = i40e_ctrl_pkt_filter_set(pf,
+			(struct rte_ctrl_pkt_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unsupported operation %u\n", filter_op);
+		ret = -ENOSYS;
+		break;
+	}
+	return ret;
+}
+
 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 = 0;
-	(void)filter_op;
-	(void)arg;
 
 	if (dev == NULL)
 		return -EINVAL;
 
 	switch (filter_type) {
+	case RTE_ETH_FILTER_CTRL_PKT:
+		ret = i40e_ctrl_pkt_filter_handle(pf, filter_op, arg);
+		break;
 	default:
 		PMD_DRV_LOG(WARNING, "Filter type (%d) not supported",
 							filter_type);
-- 
1.8.1.4

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

* [dpdk-dev] [PATCH v2 3/3] testpmd: Commands to test ctrl_pkt filter
  2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure Jingjing Wu
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 2/3] i40e: ctrl_pkt filter implementation in i40e pmd driver Jingjing Wu
@ 2014-10-22  8:19   ` Jingjing Wu
  2014-11-13 12:49   ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Jingjing Wu
  3 siblings, 0 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-10-22  8:19 UTC (permalink / raw)
  To: dev

Add commands to test control packet filter
 - add/delete control packet filter

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

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 0b972f9..78a73ac 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -660,6 +660,11 @@ 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"
+
+			"ctrl_pkt_filter (port_id) (add|del)"
+			" mac_addr (mac_address) ethertype (ether_type)"
+			" (none|options) queue (queue_id)\n"
+			"    Add/Del a control packet filter.\n\n"
 		);
 	}
 }
@@ -7414,6 +7419,149 @@ cmdline_parse_inst_t cmd_get_flex_filter = {
 		NULL,
 	},
 };
+/* *** Filters Control *** */
+
+/* *** deal with control packet filter *** */
+struct cmd_ctrl_pkt_filter_result {
+	cmdline_fixed_string_t filter;
+	uint8_t port_id;
+	cmdline_fixed_string_t ops;
+	cmdline_fixed_string_t mac_addr;
+	struct ether_addr mac_addr_value;
+	cmdline_fixed_string_t ethertype;
+	uint16_t ethertype_value;
+	cmdline_fixed_string_t options;
+	cmdline_fixed_string_t queue;
+	uint16_t  queue_id;
+};
+
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_filter =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 filter, "ctrl_pkt_filter");
+cmdline_parse_token_num_t cmd_ctrl_pkt_filter_port_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_ops =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 ops, "add#del");
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_mac_addr =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 mac_addr, "mac_addr");
+cmdline_parse_token_etheraddr_t cmd_ctrl_pkt_filter_mac_addr_value =
+	TOKEN_ETHERADDR_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				     mac_addr_value);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_ethertype =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 ethertype, "ethertype");
+cmdline_parse_token_num_t cmd_ctrl_pkt_filter_ethertype_value =
+	TOKEN_NUM_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+			      ethertype_value, UINT16);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_options =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 options, NULL);
+cmdline_parse_token_string_t cmd_ctrl_pkt_filter_queue =
+	TOKEN_STRING_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+				 queue, "queue");
+cmdline_parse_token_num_t cmd_ctrl_pkt_filter_queue_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_ctrl_pkt_filter_result,
+			      queue_id, UINT16);
+
+static inline int
+parse_ctrl_pkt_filter_options(const char *q_arg,
+			     uint16_t *flags)
+{
+#define MAX_NUM_OPTIONS 3
+	char s[256];
+	char *str_fld[MAX_NUM_OPTIONS];
+	int i;
+	int num_options = -1;
+	unsigned size;
+
+	*flags = 0;
+	if (!strcmp(q_arg, "none"))
+		return 0;
+
+	size = strnlen(q_arg, sizeof(s));
+	snprintf(s, sizeof(s), "%.*s", size, q_arg);
+	num_options = rte_strsplit(s, sizeof(s), str_fld, MAX_NUM_OPTIONS, '-');
+	/* multi-options are combined by - */
+	if (num_options < 0 || num_options > MAX_NUM_OPTIONS)
+		return -1;
+	for (i = 0; i < num_options; i++) {
+		if (!strcmp(str_fld[i], "tx"))
+			*flags |= RTE_CONTROL_PACKET_FLAGS_TX;
+		if (!strcmp(str_fld[i], "mac_ignr"))
+			*flags |= RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC;
+		if (!strcmp(str_fld[i], "drop"))
+			*flags |= RTE_CONTROL_PACKET_FLAGS_DROP;
+	}
+	return num_options;
+}
+
+static void
+cmd_ctrl_pkt_filter_parsed(void *parsed_result,
+			  __attribute__((unused)) struct cmdline *cl,
+			  __attribute__((unused)) void *data)
+{
+	struct cmd_ctrl_pkt_filter_result *res = parsed_result;
+	struct rte_ctrl_pkt_filter filter;
+	int ret = 0;
+
+	ret = rte_eth_dev_filter_supported(res->port_id, RTE_ETH_FILTER_CTRL_PKT);
+	if (ret < 0) {
+		printf("control packet filter is not supported on port %u.\n",
+			res->port_id);
+		return;
+	}
+
+	memset(&filter, 0, sizeof(filter));
+
+	(void)rte_memcpy(&filter.mac_addr, &res->mac_addr_value,
+		sizeof(struct ether_addr));
+	filter.ether_type = res->ethertype_value;
+
+	ret = parse_ctrl_pkt_filter_options(res->options, &filter.flags);
+	if (ret < 0) {
+		printf("options input is invalid.\n");
+		return;
+	}
+	if (!(filter.flags & RTE_CONTROL_PACKET_FLAGS_DROP)) {
+		filter.flags |= RTE_CONTROL_PACKET_FLAGS_TO_QUEUE;
+		filter.queue = res->queue_id;
+	}
+	if (!strcmp(res->ops, "add"))
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+				RTE_ETH_FILTER_CTRL_PKT,
+				RTE_ETH_FILTER_ADD,
+				&filter);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+				RTE_ETH_FILTER_CTRL_PKT,
+				RTE_ETH_FILTER_DELETE,
+				&filter);
+	if (ret < 0)
+		printf("control packet filter programming error: (%s)\n",
+			strerror(-ret));
+}
+
+cmdline_parse_inst_t cmd_ctrl_pkt_filter = {
+	.f = cmd_ctrl_pkt_filter_parsed,
+	.data = NULL,
+	.help_str = "add or delete a control packet filter entry",
+	.tokens = {
+		(void *)&cmd_ctrl_pkt_filter_filter,
+		(void *)&cmd_ctrl_pkt_filter_port_id,
+		(void *)&cmd_ctrl_pkt_filter_ops,
+		(void *)&cmd_ctrl_pkt_filter_mac_addr,
+		(void *)&cmd_ctrl_pkt_filter_mac_addr_value,
+		(void *)&cmd_ctrl_pkt_filter_ethertype,
+		(void *)&cmd_ctrl_pkt_filter_ethertype_value,
+		(void *)&cmd_ctrl_pkt_filter_options,
+		(void *)&cmd_ctrl_pkt_filter_queue,
+		(void *)&cmd_ctrl_pkt_filter_queue_id,
+		NULL,
+	},
+};
 
 /* ******************************************************************************** */
 
@@ -7541,6 +7689,7 @@ 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_ctrl_pkt_filter,
 	NULL,
 };
 
-- 
1.8.1.4

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

* Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure Jingjing Wu
@ 2014-10-30 22:47     ` Thomas Monjalon
  2014-10-31  7:05       ` Wu, Jingjing
  0 siblings, 1 reply; 30+ messages in thread
From: Thomas Monjalon @ 2014-10-30 22:47 UTC (permalink / raw)
  To: Jingjing Wu; +Cc: dev

2014-10-22 16:19, Jingjing Wu:
> +/**
> + * Define all structures for Control Packet Filter type corresponding with specific operations.
> + */

Please explain what is a control packet.

> +
> +#define RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC    0x0001
> +#define RTE_CONTROL_PACKET_FLAGS_DROP          0x0002
> +#define RTE_CONTROL_PACKET_FLAGS_TO_QUEUE      0x0004
> +#define RTE_CONTROL_PACKET_FLAGS_TX            0x0008
> +#define RTE_CONTROL_PACKET_FLAGS_RX            0x0000

Flag RX is 0?

> +/**
> + * A structure used to define the control packet filter entry
> + * to support RTE_ETH_FILTER_CTRL_PKT with RTE_ETH_FILTER_ADD
> + * and RTE_ETH_FILTER_DELETE operations.
> + */
> +struct rte_ctrl_pkt_filter {
> +	struct ether_addr mac_addr;   /**< mac address to match. */
> +	uint16_t ether_type;          /**< ether type to match */
> +	uint16_t flags;               /**< options for filter's behavior*/
> +	uint16_t dest_id;             /**< destination vsi id or pool id*/

vsi id and pool id cannot be understood in a generic context.
Please explain what you mean and why queue is not enough.

> +	uint16_t queue;               /**< queue assign to if TO QUEUE flag is set */

TO QUEUE is not defined. Is it really needed?

Thanks
-- 
Thomas

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

* Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-10-30 22:47     ` Thomas Monjalon
@ 2014-10-31  7:05       ` Wu, Jingjing
  2014-10-31  8:44         ` Thomas Monjalon
  0 siblings, 1 reply; 30+ messages in thread
From: Wu, Jingjing @ 2014-10-31  7:05 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: Friday, October 31, 2014 6:47 AM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type
> and its structure
> 
> 2014-10-22 16:19, Jingjing Wu:
> > +/**
> > + * Define all structures for Control Packet Filter type corresponding with
> specific operations.
> > + */
> 
> Please explain what is a control packet.
A control element in Fortville can be used to receive control packets and control other switching elements. Control packet filter can filter control packet (such as LLDP) to different queues in receive and identify the switch element that should process the packets in transmit.
At the same time, we also can use this filter to route non-control packets to queue or other engine by filtering mac and ether_type. The name "control packet filter" comes from Fortville.

> 
> > +
> > +#define RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC    0x0001
> > +#define RTE_CONTROL_PACKET_FLAGS_DROP          0x0002
> > +#define RTE_CONTROL_PACKET_FLAGS_TO_QUEUE      0x0004
> > +#define RTE_CONTROL_PACKET_FLAGS_TX            0x0008
> > +#define RTE_CONTROL_PACKET_FLAGS_RX            0x0000
> 
> Flag RX is 0?
Yes, RX is default value. Maybe it need to be removed. 
> 
> > +/**
> > + * A structure used to define the control packet filter entry
> > + * to support RTE_ETH_FILTER_CTRL_PKT with RTE_ETH_FILTER_ADD
> > + * and RTE_ETH_FILTER_DELETE operations.
> > + */
> > +struct rte_ctrl_pkt_filter {
> > +	struct ether_addr mac_addr;   /**< mac address to match. */
> > +	uint16_t ether_type;          /**< ether type to match */
> > +	uint16_t flags;               /**< options for filter's behavior*/
> > +	uint16_t dest_id;             /**< destination vsi id or pool id*/
> 
> vsi id and pool id cannot be understood in a generic context.
> Please explain what you mean and why queue is not enough.
If queue is not specified, dest_id defines which element (vsi) will get the packet.
If queue is specified, the queue need belong to the destination element.
> 
> > +	uint16_t queue;               /**< queue assign to if TO QUEUE flag is set
> */
> 
> TO QUEUE is not defined. Is it really needed?
> 
TO QUEUE is just the flag RTE_CONTROL_PACKET_FLAGS_TO_QUEUE above.

> Thanks
> --
> Thomas

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

* Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-10-31  7:05       ` Wu, Jingjing
@ 2014-10-31  8:44         ` Thomas Monjalon
  2014-11-13  5:44           ` Wu, Jingjing
  0 siblings, 1 reply; 30+ messages in thread
From: Thomas Monjalon @ 2014-10-31  8:44 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

Hi Jingjing,

I'm sorry, but your explanations are not sufficient.
Please keep in mind that the user of the API don't know i40e internals.

2014-10-31 07:05, Wu, Jingjing:
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> > 2014-10-22 16:19, Jingjing Wu:
> > > +/**
> > > + * Define all structures for Control Packet Filter type corresponding with
> > specific operations.
> > > + */
> > 
> > Please explain what is a control packet.
> 
> A control element in Fortville can be used to receive control packets and control other switching elements. Control packet filter can filter control packet (such as LLDP) to different queues in receive and identify the switch element that should process the packets in transmit.
> At the same time, we also can use this filter to route non-control packets to queue or other engine by filtering mac and ether_type. The name "control packet filter" comes from Fortville.

I still don't know what is a control packet.

> > > +#define RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC    0x0001
> > > +#define RTE_CONTROL_PACKET_FLAGS_DROP          0x0002
> > > +#define RTE_CONTROL_PACKET_FLAGS_TO_QUEUE      0x0004
> > > +#define RTE_CONTROL_PACKET_FLAGS_TX            0x0008
> > > +#define RTE_CONTROL_PACKET_FLAGS_RX            0x0000
> > 
> > Flag RX is 0?
> 
> Yes, RX is default value. Maybe it need to be removed.

No, it doesn't need to be removed. But a flag must not be 0.
0 means none.
It's impossible to disable this flag.

Moreover, you should comment each flag.

> > > +/**
> > > + * A structure used to define the control packet filter entry
> > > + * to support RTE_ETH_FILTER_CTRL_PKT with RTE_ETH_FILTER_ADD
> > > + * and RTE_ETH_FILTER_DELETE operations.
> > > + */
> > > +struct rte_ctrl_pkt_filter {
> > > +	struct ether_addr mac_addr;   /**< mac address to match. */
> > > +	uint16_t ether_type;          /**< ether type to match */
> > > +	uint16_t flags;               /**< options for filter's behavior*/
> > > +	uint16_t dest_id;             /**< destination vsi id or pool id*/
> > 
> > vsi id and pool id cannot be understood in a generic context.
> > Please explain what you mean and why queue is not enough.
> 
> If queue is not specified, dest_id defines which element (vsi) will get the packet.
> If queue is specified, the queue need belong to the destination element.

You really need to define what is a vsi id and pool id. These notions are not
known in the API layer.

> > > +	uint16_t queue;               /**< queue assign to if TO QUEUE flag is set
> > */
> > 
> > TO QUEUE is not defined. Is it really needed?
> > 
> TO QUEUE is just the flag RTE_CONTROL_PACKET_FLAGS_TO_QUEUE above.

OK, please use the same wording or users will get lost.

-- 
Thomas

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

* Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-10-31  8:44         ` Thomas Monjalon
@ 2014-11-13  5:44           ` Wu, Jingjing
  2014-11-13  8:41             ` Thomas Monjalon
  0 siblings, 1 reply; 30+ messages in thread
From: Wu, Jingjing @ 2014-11-13  5:44 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

The input set of control packet filter are dst_mac and ethertype in Ethernet head.
To be clear, I think it's better to use the name ethertype filter.

While there is already ethertype filter existing in igb and ixgbe driver. I will rename
The patchset to ethertype filter and also integrate igb and ixgbe's ethertype filter
To the filter_ctrl API.

What do you think?
  
Jingjing

> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Friday, October 31, 2014 4:45 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type
> and its structure
> 
> Hi Jingjing,
> 
> I'm sorry, but your explanations are not sufficient.
> Please keep in mind that the user of the API don't know i40e internals.
> 
> 2014-10-31 07:05, Wu, Jingjing:
> > From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> > > 2014-10-22 16:19, Jingjing Wu:
> > > > +/**
> > > > + * Define all structures for Control Packet Filter type
> > > > +corresponding with
> > > specific operations.
> > > > + */
> > >
> > > Please explain what is a control packet.
> >
> > A control element in Fortville can be used to receive control packets and
> control other switching elements. Control packet filter can filter control
> packet (such as LLDP) to different queues in receive and identify the switch
> element that should process the packets in transmit.
> > At the same time, we also can use this filter to route non-control packets to
> queue or other engine by filtering mac and ether_type. The name "control
> packet filter" comes from Fortville.
> 
> I still don't know what is a control packet.
> 
> > > > +#define RTE_CONTROL_PACKET_FLAGS_IGNORE_MAC    0x0001
> > > > +#define RTE_CONTROL_PACKET_FLAGS_DROP          0x0002
> > > > +#define RTE_CONTROL_PACKET_FLAGS_TO_QUEUE      0x0004
> > > > +#define RTE_CONTROL_PACKET_FLAGS_TX            0x0008
> > > > +#define RTE_CONTROL_PACKET_FLAGS_RX            0x0000
> > >
> > > Flag RX is 0?
> >
> > Yes, RX is default value. Maybe it need to be removed.
> 
> No, it doesn't need to be removed. But a flag must not be 0.
> 0 means none.
> It's impossible to disable this flag.
> 
> Moreover, you should comment each flag.
> 
> > > > +/**
> > > > + * A structure used to define the control packet filter entry
> > > > + * to support RTE_ETH_FILTER_CTRL_PKT with RTE_ETH_FILTER_ADD
> > > > + * and RTE_ETH_FILTER_DELETE operations.
> > > > + */
> > > > +struct rte_ctrl_pkt_filter {
> > > > +	struct ether_addr mac_addr;   /**< mac address to match. */
> > > > +	uint16_t ether_type;          /**< ether type to match */
> > > > +	uint16_t flags;               /**< options for filter's behavior*/
> > > > +	uint16_t dest_id;             /**< destination vsi id or pool id*/
> > >
> > > vsi id and pool id cannot be understood in a generic context.
> > > Please explain what you mean and why queue is not enough.
> >
> > If queue is not specified, dest_id defines which element (vsi) will get the
> packet.
> > If queue is specified, the queue need belong to the destination element.
> 
> You really need to define what is a vsi id and pool id. These notions are not
> known in the API layer.
> 
> > > > +	uint16_t queue;               /**< queue assign to if TO QUEUE flag is set
> > > */
> > >
> > > TO QUEUE is not defined. Is it really needed?
> > >
> > TO QUEUE is just the flag RTE_CONTROL_PACKET_FLAGS_TO_QUEUE
> above.
> 
> OK, please use the same wording or users will get lost.
> 
> --
> Thomas

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

* Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-11-13  5:44           ` Wu, Jingjing
@ 2014-11-13  8:41             ` Thomas Monjalon
  2014-11-13  9:00               ` Wu, Jingjing
  0 siblings, 1 reply; 30+ messages in thread
From: Thomas Monjalon @ 2014-11-13  8:41 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

Hi Jingjing,

2014-11-13 05:44, Wu, Jingjing:
> The input set of control packet filter are dst_mac and ethertype in Ethernet head.
> To be clear, I think it's better to use the name ethertype filter.
> 
> While there is already ethertype filter existing in igb and ixgbe driver. I will rename
> The patchset to ethertype filter and also integrate igb and ixgbe's ethertype filter
> To the filter_ctrl API.
> 
> What do you think?

OK, good.
If I understand well, this feature is now planned for release 2.0?

-- 
Thomas

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

* Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
  2014-11-13  8:41             ` Thomas Monjalon
@ 2014-11-13  9:00               ` Wu, Jingjing
  0 siblings, 0 replies; 30+ messages in thread
From: Wu, Jingjing @ 2014-11-13  9:00 UTC (permalink / raw)
  To: Thomas Monjalon; +Cc: dev

Hi, Thomas

Nop.

We target to have it in r1.8. And the whole patch set is almost ready, but lack of review internally.

I have two proposes here:
1. Send a patch set include all the ethdev, i40e, ixgbe, igb and testpmd changes just as my previous mail.

2. send a patch set only include the ethdev, i40e part. Without testpmd changes to support testing it in fortville. And will send remaining changes later. Maybe r2.0?

The second proposal will split the whole task to small patchset. And easy to review.

Which one do you prefer?

Look forward to your reply!
Thanks

Jingjing 


> -----Original Message-----
> From: Thomas Monjalon [mailto:thomas.monjalon@6wind.com]
> Sent: Thursday, November 13, 2014 4:41 PM
> To: Wu, Jingjing
> Cc: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure
> 
> Hi Jingjing,
> 
> 2014-11-13 05:44, Wu, Jingjing:
> > The input set of control packet filter are dst_mac and ethertype in Ethernet head.
> > To be clear, I think it's better to use the name ethertype filter.
> >
> > While there is already ethertype filter existing in igb and ixgbe driver. I will rename
> > The patchset to ethertype filter and also integrate igb and ixgbe's ethertype filter
> > To the filter_ctrl API.
> >
> > What do you think?
> 
> OK, good.
> If I understand well, this feature is now planned for release 2.0?
> 
> --
> Thomas

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

* [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville
  2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
                     ` (2 preceding siblings ...)
  2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 3/3] testpmd: Commands to test ctrl_pkt filter Jingjing Wu
@ 2014-11-13 12:49   ` Jingjing Wu
  2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api Jingjing Wu
                       ` (2 more replies)
  3 siblings, 3 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-11-13 12:49 UTC (permalink / raw)
  To: dev

From: "jingjing.wu" <jingjing.wu@intel.com>

The patch set supports ethertype filter on fortville.
 
v3 changes:
 - redefine the control packet filter to ethertype filter
 
v2 changes:
 - strip the filter APIs definitions from this patch set

jingjing.wu (2):
  ethdev: new structure of Ethertype Filter for filter_ctrl api
  i40e: implement operation to add/delete an ethertype filter

 lib/librte_ether/rte_eth_ctrl.h   | 20 ++++++++
 lib/librte_pmd_i40e/i40e_ethdev.c | 99 +++++++++++++++++++++++++++++++++++++++
 2 files changed, 119 insertions(+)

-- 
1.8.1.4

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

* [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api
  2014-11-13 12:49   ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Jingjing Wu
@ 2014-11-13 12:49     ` Jingjing Wu
  2014-11-27  5:21       ` Qiu, Michael
  2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 2/2] i40e: implement operation to add/delete an ethertype filter Jingjing Wu
  2014-11-18 13:46     ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Liu, Jijiang
  2 siblings, 1 reply; 30+ messages in thread
From: Jingjing Wu @ 2014-11-13 12:49 UTC (permalink / raw)
  To: dev

From: "jingjing.wu" <jingjing.wu@intel.com>

A new structure of ethertype filter is defined in rte_eth_ctrl.h
for filter_ctrl api

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 8dd384d..73bc296 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_ETHERTYPE,
 	RTE_ETH_FILTER_MAX
 };
 
@@ -155,6 +156,25 @@ struct rte_eth_tunnel_filter_conf {
 	uint16_t queue_id;      /** < queue number. */
 };
 
+/**
+ * Define all structures for Ethertype Filter type.
+ */
+
+#define RTE_ETHTYPE_FLAGS_MAC    0x0001 /**< If set, compare mac */
+#define RTE_ETHTYPE_FLAGS_DROP   0x0002 /**< If set, drop packet when match */
+
+/**
+ * A structure used to define the ethertype filter entry
+ * to support RTE_ETH_FILTER_ETHERTYPE with RTE_ETH_FILTER_ADD,
+ * RTE_ETH_FILTER_DELETE and RTE_ETH_FILTER_GET operations.
+ */
+struct rte_eth_ethertype_filter {
+	struct ether_addr mac_addr;   /**< Mac address to match. */
+	uint16_t ether_type;          /**< Ether type to match */
+	uint16_t flags;               /**< Flags from RTE_ETHTYPE_FLAGS_* */
+	uint16_t queue;               /**< Queue assigned to when match*/
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.8.1.4

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

* [dpdk-dev] [PATCH v3 2/2] i40e: implement operation to add/delete an ethertype filter
  2014-11-13 12:49   ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Jingjing Wu
  2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api Jingjing Wu
@ 2014-11-13 12:49     ` Jingjing Wu
  2014-11-18 13:46     ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Liu, Jijiang
  2 siblings, 0 replies; 30+ messages in thread
From: Jingjing Wu @ 2014-11-13 12:49 UTC (permalink / raw)
  To: dev

From: "jingjing.wu" <jingjing.wu@intel.com>

Handle the RTE_ETH_FILTER_ADD and RTE_ETH_FILTER_DELETE operations
on ethertype filter.

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

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 5074262..499270e 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -205,6 +205,12 @@ static int i40e_dev_udp_tunnel_add(struct rte_eth_dev *dev,
 				struct rte_eth_udp_tunnel *udp_tunnel);
 static int i40e_dev_udp_tunnel_del(struct rte_eth_dev *dev,
 				struct rte_eth_udp_tunnel *udp_tunnel);
+static int i40e_ethertype_filter_set(struct i40e_pf *pf,
+			struct rte_eth_ethertype_filter *filter,
+			bool add);
+static int i40e_ethertype_filter_handle(struct rte_eth_dev *dev,
+				enum rte_filter_op filter_op,
+				void *arg);
 static int i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 				enum rte_filter_type filter_type,
 				enum rte_filter_op filter_op,
@@ -4990,6 +4996,96 @@ i40e_pf_config_mq_rx(struct i40e_pf *pf)
 	return ret;
 }
 
+/*
+ * Configure ethertype filter, which can director packet by filtering
+ * with mac address and ether_type or only ether_type
+ */
+static int
+i40e_ethertype_filter_set(struct i40e_pf *pf,
+			struct rte_eth_ethertype_filter *filter,
+			bool add)
+{
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	struct i40e_control_filter_stats stats;
+	uint16_t flags = 0;
+	int ret;
+
+	if (filter->queue >= pf->dev_data->nb_rx_queues) {
+		PMD_DRV_LOG(ERR, "Invalid queue ID");
+		return -EINVAL;
+	}
+	if (filter->ether_type == ETHER_TYPE_IPv4 ||
+		filter->ether_type == ETHER_TYPE_IPv6) {
+		PMD_DRV_LOG(ERR, "unsupported ether_type(0x%04x) in"
+			" control packet filter.", filter->ether_type);
+		return -EINVAL;
+	}
+	if (filter->ether_type == ETHER_TYPE_VLAN)
+		PMD_DRV_LOG(WARNING, "filter vlan ether_type in first tag is"
+			" not supported.");
+
+	if (!(filter->flags & RTE_ETHTYPE_FLAGS_MAC))
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_IGNORE_MAC;
+	if (filter->flags & RTE_ETHTYPE_FLAGS_DROP)
+		flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_DROP;
+	flags |= I40E_AQC_ADD_CONTROL_PACKET_FLAGS_TO_QUEUE;
+
+	memset(&stats, 0, sizeof(stats));
+	ret = i40e_aq_add_rem_control_packet_filter(hw,
+			filter->mac_addr.addr_bytes,
+			filter->ether_type, flags,
+			pf->main_vsi->seid,
+			filter->queue, add, &stats, NULL);
+
+	PMD_DRV_LOG(INFO, "add/rem control packet filter, return %d,"
+			 " mac_etype_used = %u, etype_used = %u,"
+			 " mac_etype_free = %u, etype_free = %u\n",
+			 ret, stats.mac_etype_used, stats.etype_used,
+			 stats.mac_etype_free, stats.etype_free);
+	if (ret < 0)
+		return -ENOSYS;
+	return 0;
+}
+
+/*
+ * Handle operations for ethertype filter.
+ */
+static int
+i40e_ethertype_filter_handle(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)
+		return ret;
+
+	if (arg == NULL) {
+		PMD_DRV_LOG(ERR, "arg shouldn't be NULL for operation %u",
+			    filter_op);
+		return -EINVAL;
+	}
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_ADD:
+		ret = i40e_ethertype_filter_set(pf,
+			(struct rte_eth_ethertype_filter *)arg,
+			TRUE);
+		break;
+	case RTE_ETH_FILTER_DELETE:
+		ret = i40e_ethertype_filter_set(pf,
+			(struct rte_eth_ethertype_filter *)arg,
+			FALSE);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unsupported operation %u\n", filter_op);
+		ret = -ENOSYS;
+		break;
+	}
+	return ret;
+}
+
 static int
 i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 		     enum rte_filter_type filter_type,
@@ -5008,6 +5104,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_ETHERTYPE:
+		ret = i40e_ethertype_filter_handle(dev, filter_op, arg);
+		break;
 	default:
 		PMD_DRV_LOG(WARNING, "Filter type (%d) not supported",
 							filter_type);
-- 
1.8.1.4

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

* Re: [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville
  2014-11-13 12:49   ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Jingjing Wu
  2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api Jingjing Wu
  2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 2/2] i40e: implement operation to add/delete an ethertype filter Jingjing Wu
@ 2014-11-18 13:46     ` Liu, Jijiang
  2014-11-26 22:24       ` Thomas Monjalon
  2 siblings, 1 reply; 30+ messages in thread
From: Liu, Jijiang @ 2014-11-18 13:46 UTC (permalink / raw)
  To: Wu, Jingjing, dev



> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jingjing Wu
> Sent: Thursday, November 13, 2014 8:50 PM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville
> 
> From: "jingjing.wu" <jingjing.wu@intel.com>
> 
> The patch set supports ethertype filter on fortville.
> 
> v3 changes:
>  - redefine the control packet filter to ethertype filter
> 
> v2 changes:
>  - strip the filter APIs definitions from this patch set
> 
> jingjing.wu (2):
>   ethdev: new structure of Ethertype Filter for filter_ctrl api
>   i40e: implement operation to add/delete an ethertype filter
> 
>  lib/librte_ether/rte_eth_ctrl.h   | 20 ++++++++
>  lib/librte_pmd_i40e/i40e_ethdev.c | 99
> +++++++++++++++++++++++++++++++++++++++
>  2 files changed, 119 insertions(+)
> 
> --
> 1.8.1.4

Acked-by: Jijiang Liu <Jijiang.liu@intel.com>

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

* Re: [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville
  2014-11-18 13:46     ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Liu, Jijiang
@ 2014-11-26 22:24       ` Thomas Monjalon
  0 siblings, 0 replies; 30+ messages in thread
From: Thomas Monjalon @ 2014-11-26 22:24 UTC (permalink / raw)
  To: Wu, Jingjing; +Cc: dev

> > The patch set supports ethertype filter on fortville.
> > 
> > v3 changes:
> >  - redefine the control packet filter to ethertype filter
> > 
> > v2 changes:
> >  - strip the filter APIs definitions from this patch set
> > 
> > jingjing.wu (2):
> >   ethdev: new structure of Ethertype Filter for filter_ctrl api
> >   i40e: implement operation to add/delete an ethertype filter
> 
> Acked-by: Jijiang Liu <Jijiang.liu@intel.com>

Applied

As for flow director API, it is expected to have this new API applied to other
drivers, as a top priority.

Thanks
-- 
Thomas

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

* Re: [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api
  2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api Jingjing Wu
@ 2014-11-27  5:21       ` Qiu, Michael
  0 siblings, 0 replies; 30+ messages in thread
From: Qiu, Michael @ 2014-11-27  5:21 UTC (permalink / raw)
  To: Wu, Jingjing, dev

On 11/13/2014 8:51 PM, Jingjing Wu wrote:
> From: "jingjing.wu" <jingjing.wu@intel.com>
>
> A new structure of ethertype filter is defined in rte_eth_ctrl.h
> for filter_ctrl api
>
> 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 8dd384d..73bc296 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_ETHERTYPE,
>  	RTE_ETH_FILTER_MAX
>  };
>  
> @@ -155,6 +156,25 @@ struct rte_eth_tunnel_filter_conf {
>  	uint16_t queue_id;      /** < queue number. */
>  };
>  
> +/**
> + * Define all structures for Ethertype Filter type.
> + */
> +
> +#define RTE_ETHTYPE_FLAGS_MAC    0x0001 /**< If set, compare mac */
> +#define RTE_ETHTYPE_FLAGS_DROP   0x0002 /**< If set, drop packet when match */
> +
> +/**
> + * A structure used to define the ethertype filter entry
> + * to support RTE_ETH_FILTER_ETHERTYPE with RTE_ETH_FILTER_ADD,
> + * RTE_ETH_FILTER_DELETE and RTE_ETH_FILTER_GET operations.
> + */
> +struct rte_eth_ethertype_filter {
> +	struct ether_addr mac_addr;   /**< Mac address to match. */
> +	uint16_t ether_type;          /**< Ether type to match */
> +	uint16_t flags;               /**< Flags from RTE_ETHTYPE_FLAGS_* */
> +	uint16_t queue;               /**< Queue assigned to when match*/

Here 'match*/' should be 'match */', ignore this if it is just my email
client's display issue :)

Thanks,
Michael
> +};
> +
>  #ifdef __cplusplus
>  }
>  #endif


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

end of thread, other threads:[~2014-11-27  5:21 UTC | newest]

Thread overview: 30+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2014-09-25  6:59 [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Jingjing Wu
2014-09-25  6:59 ` [dpdk-dev] [PATCH 1/4] lib/librte_ether: new filter APIs definition Jingjing Wu
2014-10-09 15:34   ` De Lara Guarch, Pablo
2014-10-10  1:19     ` Wu, Jingjing
2014-10-10  3:34     ` Wu, Jingjing
2014-10-10  7:28       ` De Lara Guarch, Pablo
2014-10-16 15:11         ` Thomas Monjalon
2014-09-25  6:59 ` [dpdk-dev] [PATCH 2/4] lib/librte_ether: define CTRL_PKT filter type and its structure Jingjing Wu
2014-09-25  6:59 ` [dpdk-dev] [PATCH 3/4] i40e: ctrl_pkt filter implementation in i40e pmd driver Jingjing Wu
2014-09-25  6:59 ` [dpdk-dev] [PATCH 4/4] app/test-pmd: add commands for control packet filter Jingjing Wu
2014-09-25  7:54 ` [dpdk-dev] [PATCH 0/4] support control packet filter on Fortville Zhang, Helin
2014-10-11  7:23 ` Chen, Jing D
2014-10-11  7:23 ` Liu, Jijiang
2014-10-11  7:53 ` Zhang, Helin
2014-10-22  8:19 ` [dpdk-dev] [PATCH v2 0/3] support control packet filter on fortville Jingjing Wu
2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 1/3] ethdev: define ctrl_pkt filter type and its structure Jingjing Wu
2014-10-30 22:47     ` Thomas Monjalon
2014-10-31  7:05       ` Wu, Jingjing
2014-10-31  8:44         ` Thomas Monjalon
2014-11-13  5:44           ` Wu, Jingjing
2014-11-13  8:41             ` Thomas Monjalon
2014-11-13  9:00               ` Wu, Jingjing
2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 2/3] i40e: ctrl_pkt filter implementation in i40e pmd driver Jingjing Wu
2014-10-22  8:19   ` [dpdk-dev] [PATCH v2 3/3] testpmd: Commands to test ctrl_pkt filter Jingjing Wu
2014-11-13 12:49   ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Jingjing Wu
2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 1/2] ethdev: new structure of Ethertype Filter for filter_ctrl api Jingjing Wu
2014-11-27  5:21       ` Qiu, Michael
2014-11-13 12:49     ` [dpdk-dev] [PATCH v3 2/2] i40e: implement operation to add/delete an ethertype filter Jingjing Wu
2014-11-18 13:46     ` [dpdk-dev] [PATCH v3 0/2] support ethertype filter on fortville Liu, Jijiang
2014-11-26 22:24       ` Thomas Monjalon

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).