DPDK patches and discussions
 help / color / mirror / Atom feed
* [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville
@ 2014-09-23  3:29 Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 1/5]librte_ether:use new filter framework Jijiang Liu
                   ` (5 more replies)
  0 siblings, 6 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-09-23  3:29 UTC (permalink / raw)
  To: dev

The patch set enhances MACVLAN filter configurability and supports perfect and hash match filter of unicast
and multicast MAC address for VF on Fortville.

It mainly includes:
 - Use new filter mechanism discussed at http://dpdk.org/ml/archives/dev/2014-September/005179.html. 
 - Enhance MACVLAN filter to be configurable. Now the following options are configurable:  
   1. Perfect match of MAC address 
   2. Perfect match of MAC address and VLAN ID 
   3. Hash match of MAC address 
   4. Hash match of MAC address and perfect match of VLAN ID
   5. To Queue: use MAC and VLAN to point to a queue
 - Support perfect and hash match of unicast and multicast MAC address for VF for i40e 


jijiangl (5):
  Use new filter framework
  Add new definations for MACVLAN filter enhancement in rte_eth_ctrl.h file
  Change parameters of MAC/VLAN filter to be configurable
  Add VF MACVLAN filter handle for i40e
  Test VF MACVLAN filter for i40e

 app/test-pmd/cmdline.c            |  115 +++++++++++++-
 lib/librte_ether/Makefile         |    1 +
 lib/librte_ether/rte_eth_ctrl.h   |  104 ++++++++++++
 lib/librte_ether/rte_ethdev.c     |   33 ++++
 lib/librte_ether/rte_ethdev.h     |   48 ++++++-
 lib/librte_pmd_i40e/i40e_ethdev.c |  321 ++++++++++++++++++++++++++++++++-----
 lib/librte_pmd_i40e/i40e_ethdev.h |   18 ++-
 lib/librte_pmd_i40e/i40e_pf.c     |    7 +-
 8 files changed, 601 insertions(+), 46 deletions(-)
 create mode 100644 lib/librte_ether/rte_eth_ctrl.h

-- 
1.7.7.6

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

* [dpdk-dev] [PATCH 1/5]librte_ether:use new filter framework
  2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
@ 2014-09-23  3:29 ` Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 2/5]librte_ether:extend data structures of MACVLAN filter Jijiang Liu
                   ` (4 subsequent siblings)
  5 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-09-23  3:29 UTC (permalink / raw)
  To: dev

Introduce a new filter framewok in librte_ether. As to the implemetation discussion, please refer to 
http://dpdk.org/ml/archives/dev/2014-September/005179.html, and VF MACVLAN filter implementation is based on it.


Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
Acked-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Changchun Ouyang <changchun.ouyang@intel.com>

---
 lib/librte_ether/Makefile       |    1 +
 lib/librte_ether/rte_eth_ctrl.h |   79 +++++++++++++++++++++++++++++++++++++++
 lib/librte_ether/rte_ethdev.c   |   33 ++++++++++++++++
 lib/librte_ether/rte_ethdev.h   |   48 +++++++++++++++++++++++-
 4 files changed, 160 insertions(+), 1 deletions(-)
 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..66745a6
--- /dev/null
+++ b/lib/librte_ether/rte_eth_ctrl.h
@@ -0,0 +1,79 @@
+/*-
+ *   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_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 fd1010a..a3f45a6 100644
--- a/lib/librte_ether/rte_ethdev.c
+++ b/lib/librte_ether/rte_ethdev.c
@@ -3002,3 +3002,36 @@ 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 50df654..1ac5e5c 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.
@@ -1361,6 +1362,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.
  */
@@ -1467,6 +1474,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*/
 };
 
 /**
@@ -2878,7 +2886,7 @@ int rte_eth_dev_rss_reta_query(uint8_t port,
  * @return
  *   - (0) if successful.
  *   - (-ENOTSUP) if hardware doesn't support.
-  *  - (-ENODEV) if *port_id* invalid.
+ *   - (-ENODEV) if *port_id* invalid.
  *   - (-EINVAL) if bad parameter.
  */
 int rte_eth_dev_uc_hash_table_set(uint8_t port,struct ether_addr *addr,
@@ -3557,6 +3565,44 @@ 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.7.7.6

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

* [dpdk-dev] [PATCH 2/5]librte_ether:extend data structures of MACVLAN filter
  2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 1/5]librte_ether:use new filter framework Jijiang Liu
@ 2014-09-23  3:29 ` Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 3/5]i40e:optimize MACVLAN filter implementation Jijiang Liu
                   ` (3 subsequent siblings)
  5 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-09-23  3:29 UTC (permalink / raw)
  To: dev

Add new data definations for MACVLAN filter enhancement in rte_eth_ctrl.h file.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
Acked-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Changchun Ouyang <changchun.ouyang@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h |   25 +++++++++++++++++++++++++
 1 files changed, 25 insertions(+), 0 deletions(-)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index 66745a6..0910376 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_MACVLAN,
 	RTE_ETH_FILTER_MAX,
 };
 
@@ -72,6 +73,30 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_OP_MAX,
 };
 
+/* *** MACVLAN FILTER *** */
+
+/* MAC/VLAN filter type */
+#define RTE_MAC_PERFECT_MATCH      0x0001
+#define RTE_MACVLAN_PERFECT_MATCH  0x0002
+#define RTE_MAC_HASH_MATCH         0x0004
+#define RTE_MACVLAN_HASH_MATCH     0x0008
+#define RTE_MACVLAN_TO_QUEUE       0x0010
+
+/* MACVLAN filter type mask */
+#define RTE_MACVLAN_FILTER_MASK    0x000F
+
+
+/**
+ * MAC filter structure
+ */
+struct rte_eth_mac_filter {
+	uint8_t  pf_vf_flag;  /**< 0 for PF;1 for VF */
+	uint16_t id;          /**< PF ID or VF ID */
+	uint16_t filter_type; /**< MAC/VLAN filter type */
+	uint16_t queue_id;    /**< to queue ID */
+	struct ether_addr mac_addr;
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH 3/5]i40e:optimize MACVLAN filter implementation
  2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 1/5]librte_ether:use new filter framework Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 2/5]librte_ether:extend data structures of MACVLAN filter Jijiang Liu
@ 2014-09-23  3:29 ` Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 4/5]i40e:add VF MACVLAN filter implementation in librte_pmd_i40e Jijiang Liu
                   ` (2 subsequent siblings)
  5 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-09-23  3:29 UTC (permalink / raw)
  To: dev

This patch mainly optimizes i40e_add_macvlan_filters() and i40e_remove_macvlan_filters() functions in order that
we can provide a flexible configuration interface. And another relevant MACVLAN filter codes are changed based on new data structures 

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
Acked-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Changchun Ouyang <changchun.ouyang@intel.com>

---
 lib/librte_pmd_i40e/i40e_ethdev.c |  209 ++++++++++++++++++++++++++++++-------
 lib/librte_pmd_i40e/i40e_ethdev.h |   18 +++-
 lib/librte_pmd_i40e/i40e_pf.c     |    7 +-
 3 files changed, 193 insertions(+), 41 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index a00d6ca..9cc2ece 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -205,6 +205,9 @@ static int i40e_dev_rss_hash_update(struct rte_eth_dev *dev,
 				    struct rte_eth_rss_conf *rss_conf);
 static int i40e_dev_rss_hash_conf_get(struct rte_eth_dev *dev,
 				      struct rte_eth_rss_conf *rss_conf);
+static int i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
+				enum rte_filter_type filter_type,
+				enum rte_filter_op filter_op, void *arg);
 
 /* Default hash key buffer for RSS */
 static uint32_t rss_key_default[I40E_PFQF_HKEY_MAX_INDEX + 1];
@@ -256,6 +259,7 @@ static struct eth_dev_ops i40e_eth_dev_ops = {
 	.reta_query                   = i40e_dev_rss_reta_query,
 	.rss_hash_update              = i40e_dev_rss_hash_update,
 	.rss_hash_conf_get            = i40e_dev_rss_hash_conf_get,
+	.filter_ctrl                  = i40e_dev_filter_ctrl,
 };
 
 static struct eth_driver rte_i40e_pmd = {
@@ -1514,6 +1518,7 @@ i40e_macaddr_add(struct rte_eth_dev *dev,
 {
 	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
 	struct i40e_hw *hw = I40E_DEV_PRIVATE_TO_HW(dev->data->dev_private);
+	struct i40e_mac_filter_info mac_filter;
 	struct i40e_vsi *vsi = pf->main_vsi;
 	struct ether_addr old_mac;
 	int ret;
@@ -1539,8 +1544,10 @@ i40e_macaddr_add(struct rte_eth_dev *dev,
 	(void)rte_memcpy(&old_mac, hw->mac.addr, ETHER_ADDR_LEN);
 	(void)rte_memcpy(hw->mac.addr, mac_addr->addr_bytes,
 			ETHER_ADDR_LEN);
+	(void)rte_memcpy(&mac_filter.mac_addr, mac_addr, ETHER_ADDR_LEN);
+	mac_filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
 
-	ret = i40e_vsi_add_mac(vsi, mac_addr);
+	ret = i40e_vsi_add_mac(vsi, &mac_filter);
 	if (ret != I40E_SUCCESS) {
 		PMD_DRV_LOG(ERR, "Failed to add MACVLAN filter");
 		return;
@@ -2457,6 +2464,7 @@ i40e_update_default_filter_setting(struct i40e_vsi *vsi)
 {
 	struct i40e_hw *hw = I40E_VSI_TO_HW(vsi);
 	struct i40e_aqc_remove_macvlan_element_data def_filter;
+	struct i40e_mac_filter_info filter;
 	int ret;
 
 	if (vsi->type != I40E_VSI_MAIN)
@@ -2470,6 +2478,7 @@ i40e_update_default_filter_setting(struct i40e_vsi *vsi)
 	ret = i40e_aq_remove_macvlan(hw, vsi->seid, &def_filter, 1, NULL);
 	if (ret != I40E_SUCCESS) {
 		struct i40e_mac_filter *f;
+		struct ether_addr *mac;
 
 		PMD_DRV_LOG(WARNING, "Cannot remove the default "
 			    "macvlan filter");
@@ -2479,15 +2488,18 @@ i40e_update_default_filter_setting(struct i40e_vsi *vsi)
 			PMD_DRV_LOG(ERR, "failed to allocate memory");
 			return I40E_ERR_NO_MEMORY;
 		}
-		(void)rte_memcpy(&f->macaddr.addr_bytes, hw->mac.perm_addr,
+		mac = &f->mac_info.mac_addr;
+		(void)rte_memcpy(&mac->addr_bytes, hw->mac.perm_addr,
 				ETH_ADDR_LEN);
 		TAILQ_INSERT_TAIL(&vsi->mac_list, f, next);
 		vsi->mac_num++;
 
 		return ret;
 	}
-
-	return i40e_vsi_add_mac(vsi, (struct ether_addr *)(hw->mac.perm_addr));
+	(void)rte_memcpy(&filter.mac_addr,
+		(struct ether_addr *)(hw->mac.perm_addr), ETH_ADDR_LEN);
+	filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
+	return i40e_vsi_add_mac(vsi, &filter);
 }
 
 static int
@@ -2541,6 +2553,7 @@ i40e_vsi_setup(struct i40e_pf *pf,
 {
 	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
 	struct i40e_vsi *vsi;
+	struct i40e_mac_filter_info filter;
 	int ret;
 	struct i40e_vsi_context ctxt;
 	struct ether_addr broadcast =
@@ -2751,7 +2764,10 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	}
 
 	/* MAC/VLAN configuration */
-	ret = i40e_vsi_add_mac(vsi, &broadcast);
+	(void)rte_memcpy(&filter.mac_addr, &broadcast, ETHER_ADDR_LEN);
+	filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
+
+	ret = i40e_vsi_add_mac(vsi, &filter);
 	if (ret != I40E_SUCCESS) {
 		PMD_DRV_LOG(ERR, "Failed to add MACVLAN filter");
 		goto fail_msix_alloc;
@@ -3454,6 +3470,7 @@ i40e_add_macvlan_filters(struct i40e_vsi *vsi,
 {
 	int ele_num, ele_buff_size;
 	int num, actual_num, i;
+	uint16_t flags;
 	int ret = I40E_SUCCESS;
 	struct i40e_hw *hw = I40E_VSI_TO_HW(vsi);
 	struct i40e_aqc_add_macvlan_element_data *req_list;
@@ -3479,9 +3496,38 @@ i40e_add_macvlan_filters(struct i40e_vsi *vsi,
 				&filter[num + i].macaddr, ETH_ADDR_LEN);
 			req_list[i].vlan_tag =
 				rte_cpu_to_le_16(filter[num + i].vlan_id);
-			req_list[i].flags = rte_cpu_to_le_16(\
-				I40E_AQC_MACVLAN_ADD_PERFECT_MATCH);
-			req_list[i].queue_number = 0;
+
+			switch (filter[num + i].filter_type &
+				RTE_MACVLAN_FILTER_MASK) {
+			case RTE_MAC_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_PERFECT_MATCH |
+					I40E_AQC_MACVLAN_ADD_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_PERFECT_MATCH;
+				break;
+			case RTE_MAC_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_HASH_MATCH |
+					I40E_AQC_MACVLAN_ADD_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_HASH_MATCH;
+				break;
+			default:
+				PMD_DRV_LOG(ERR, "Invalid MAC match type\n");
+				ret = I40E_ERR_PARAM;
+				goto DONE;
+			}
+
+			if (filter[num + i].filter_type &
+				RTE_MACVLAN_TO_QUEUE) {
+				flags |= I40E_AQC_MACVLAN_ADD_TO_QUEUE;
+				req_list[i].queue_number =
+					rte_cpu_to_le_16(filter[num + i].queue_id);
+			} else
+				req_list[i].queue_number = 0;
+
+			req_list[i].flags = rte_cpu_to_le_16(flags);
 		}
 
 		ret = i40e_aq_add_macvlan(hw, vsi->seid, req_list,
@@ -3505,6 +3551,7 @@ i40e_remove_macvlan_filters(struct i40e_vsi *vsi,
 {
 	int ele_num, ele_buff_size;
 	int num, actual_num, i;
+	uint16_t flags;
 	int ret = I40E_SUCCESS;
 	struct i40e_hw *hw = I40E_VSI_TO_HW(vsi);
 	struct i40e_aqc_remove_macvlan_element_data *req_list;
@@ -3531,7 +3578,29 @@ i40e_remove_macvlan_filters(struct i40e_vsi *vsi,
 				&filter[num + i].macaddr, ETH_ADDR_LEN);
 			req_list[i].vlan_tag =
 				rte_cpu_to_le_16(filter[num + i].vlan_id);
-			req_list[i].flags = I40E_AQC_MACVLAN_DEL_PERFECT_MATCH;
+
+			switch (filter[num + i].filter_type &
+					RTE_MACVLAN_FILTER_MASK) {
+			case RTE_MAC_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_PERFECT_MATCH |
+					I40E_AQC_MACVLAN_DEL_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_PERFECT_MATCH;
+				break;
+			case RTE_MAC_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_HASH_MATCH |
+					I40E_AQC_MACVLAN_DEL_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_HASH_MATCH;
+				break;
+			default:
+				PMD_DRV_LOG(ERR, "Invalid MAC filter type\n");
+				ret = I40E_ERR_PARAM;
+				goto DONE;
+			}
+			req_list[i].flags = rte_cpu_to_le_16(flags);
 		}
 
 		ret = i40e_aq_remove_macvlan(hw, vsi->seid, req_list,
@@ -3556,7 +3625,7 @@ i40e_find_mac_filter(struct i40e_vsi *vsi,
 	struct i40e_mac_filter *f;
 
 	TAILQ_FOREACH(f, &vsi->mac_list, next) {
-		if (is_same_ether_addr(macaddr, &(f->macaddr)))
+		if (is_same_ether_addr(macaddr, &f->mac_info.mac_addr))
 			return f;
 	}
 
@@ -3657,8 +3726,11 @@ i40e_find_all_mac_for_vlan(struct i40e_vsi *vsi,
 			PMD_DRV_LOG(ERR, "buffer number not match");
 			return I40E_ERR_PARAM;
 		}
-		(void)rte_memcpy(&mv_f[i].macaddr, &f->macaddr, ETH_ADDR_LEN);
+		(void)rte_memcpy(&mv_f[i].macaddr, &f->mac_info.mac_addr,
+				ETH_ADDR_LEN);
 		mv_f[i].vlan_id = vlan;
+		mv_f[i].queue_id = f->mac_info.queue_id;
+		mv_f[i].filter_type = f->mac_info.filter_type;
 		i++;
 	}
 
@@ -3692,14 +3764,14 @@ i40e_vsi_remove_all_macvlan_filter(struct i40e_vsi *vsi)
 	if (vsi->vlan_num == 0) {
 		TAILQ_FOREACH(f, &vsi->mac_list, next) {
 			(void)rte_memcpy(&mv_f[i].macaddr,
-				&f->macaddr, ETH_ADDR_LEN);
+				&f->mac_info.mac_addr, ETH_ADDR_LEN);
 			mv_f[i].vlan_id = 0;
 			i++;
 		}
 	} else {
 		TAILQ_FOREACH(f, &vsi->mac_list, next) {
 			ret = i40e_find_all_vlan_for_mac(vsi,&mv_f[i],
-					vsi->vlan_num, &f->macaddr);
+					vsi->vlan_num, &f->mac_info.mac_addr);
 			if (ret != I40E_SUCCESS)
 				goto DONE;
 			i += vsi->vlan_num;
@@ -3823,28 +3895,32 @@ DONE:
 }
 
 int
-i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
+i40e_vsi_add_mac(struct i40e_vsi *vsi, struct i40e_mac_filter_info *mac_filter)
 {
 	struct i40e_mac_filter *f;
 	struct i40e_macvlan_filter *mv_f;
-	int vlan_num;
+	int i, vlan_num = 0;
 	int ret = I40E_SUCCESS;
 
 	/* If it's add and we've config it, return */
-	f = i40e_find_mac_filter(vsi, addr);
+	f = i40e_find_mac_filter(vsi, &mac_filter->mac_addr);
 	if (f != NULL)
 		return I40E_SUCCESS;
+	if ((mac_filter->filter_type & RTE_MACVLAN_PERFECT_MATCH) ||
+		(mac_filter->filter_type & RTE_MACVLAN_HASH_MATCH)) {
 
-	/**
-	 * If vlan_num is 0, that's the first time to add mac,
-	 * set mask for vlan_id 0.
-	 */
-	if (vsi->vlan_num == 0) {
-		i40e_set_vlan_filter(vsi, 0, 1);
-		vsi->vlan_num = 1;
-	}
-
-	vlan_num = vsi->vlan_num;
+		/**
+		 * If vlan_num is 0, that's the first time to add mac,
+		 * set mask for vlan_id 0.
+		 */
+		if (vsi->vlan_num == 0) {
+			i40e_set_vlan_filter(vsi, 0, 1);
+			vsi->vlan_num = 1;
+		}
+		vlan_num = vsi->vlan_num;
+	} else if ((mac_filter->filter_type & RTE_MAC_PERFECT_MATCH) ||
+			(mac_filter->filter_type & RTE_MAC_HASH_MATCH))
+		vlan_num = 1;
 
 	mv_f = rte_zmalloc("macvlan_data", vlan_num * sizeof(*mv_f), 0);
 	if (mv_f == NULL) {
@@ -3852,9 +3928,20 @@ i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 		return I40E_ERR_NO_MEMORY;
 	}
 
-	ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num, addr);
-	if (ret != I40E_SUCCESS)
-		goto DONE;
+	for (i = 0; i < vlan_num; i++) {
+		mv_f[i].filter_type = mac_filter->filter_type;
+		mv_f[i].queue_id = mac_filter->queue_id;
+		(void)rte_memcpy(&mv_f[i].macaddr, &mac_filter->mac_addr,
+				ETH_ADDR_LEN);
+	}
+
+	if (mac_filter->filter_type & RTE_MACVLAN_PERFECT_MATCH ||
+		mac_filter->filter_type & RTE_MACVLAN_HASH_MATCH) {
+		ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num,
+					&mac_filter->mac_addr);
+		if (ret != I40E_SUCCESS)
+			goto DONE;
+	}
 
 	ret = i40e_add_macvlan_filters(vsi, mv_f, vlan_num);
 	if (ret != I40E_SUCCESS)
@@ -3867,7 +3954,10 @@ i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 		ret = I40E_ERR_NO_MEMORY;
 		goto DONE;
 	}
-	(void)rte_memcpy(&f->macaddr, addr, ETH_ADDR_LEN);
+	(void)rte_memcpy(&f->mac_info.mac_addr, &mac_filter->mac_addr,
+			ETH_ADDR_LEN);
+	f->mac_info.filter_type = mac_filter->filter_type;
+	f->mac_info.queue_id = mac_filter->queue_id;
 	TAILQ_INSERT_TAIL(&vsi->mac_list, f, next);
 	vsi->mac_num++;
 
@@ -3883,7 +3973,8 @@ i40e_vsi_delete_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 {
 	struct i40e_mac_filter *f;
 	struct i40e_macvlan_filter *mv_f;
-	int vlan_num;
+	int i, vlan_num;
+	uint16_t filter_type;
 	int ret = I40E_SUCCESS;
 
 	/* Can't find it, return an error */
@@ -3892,19 +3983,34 @@ i40e_vsi_delete_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 		return I40E_ERR_PARAM;
 
 	vlan_num = vsi->vlan_num;
-	if (vlan_num == 0) {
-		PMD_DRV_LOG(ERR, "VLAN number shouldn't be 0");
-		return I40E_ERR_PARAM;
-	}
+	filter_type = f->mac_info.filter_type;
+	if (filter_type & RTE_MACVLAN_PERFECT_MATCH ||
+		filter_type & RTE_MACVLAN_HASH_MATCH) {
+		if (vlan_num == 0) {
+			PMD_DRV_LOG(ERR, "VLAN number shouldn't be 0\n");
+			return I40E_ERR_PARAM;
+		}
+	} else if (filter_type & RTE_MAC_PERFECT_MATCH ||
+			filter_type & RTE_MAC_HASH_MATCH)
+		vlan_num = 1;
+
 	mv_f = rte_zmalloc("macvlan_data", vlan_num * sizeof(*mv_f), 0);
 	if (mv_f == NULL) {
 		PMD_DRV_LOG(ERR, "failed to allocate memory");
 		return I40E_ERR_NO_MEMORY;
 	}
 
-	ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num, addr);
-	if (ret != I40E_SUCCESS)
-		goto DONE;
+	for (i = 0; i < vlan_num; i++) {
+		mv_f[i].filter_type = filter_type;
+		(void)rte_memcpy(&mv_f[i].macaddr, &f->mac_info.mac_addr,
+				ETH_ADDR_LEN);
+	}
+	if (filter_type & RTE_MACVLAN_PERFECT_MATCH ||
+			filter_type & RTE_MACVLAN_HASH_MATCH) {
+		ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num, addr);
+		if (ret != I40E_SUCCESS)
+			goto DONE;
+	}
 
 	ret = i40e_remove_macvlan_filters(vsi, mv_f, vlan_num);
 	if (ret != I40E_SUCCESS)
@@ -4115,6 +4221,33 @@ i40e_pf_config_rss(struct i40e_pf *pf)
 	return i40e_hw_rss_hash_set(hw, &rss_conf);
 }
 
+/*
+ * 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) {
+
+	int ret = 0;
+
+	if (dev == NULL)
+		return -EINVAL;
+
+	if (arg == NULL && filter_op != RTE_ETH_FILTER_OP_NONE)
+		return -EINVAL;
+
+	switch (filter_type) {
+	case RTE_ETH_FILTER_MACVLAN:
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unsupported filter type %u\n", filter_type);
+		ret = -EINVAL;
+		break;
+	}
+
+	return ret;
+}
+
 static int
 i40e_pf_config_mq_rx(struct i40e_pf *pf)
 {
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 64deef2..4bbc606 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -34,6 +34,8 @@
 #ifndef _I40E_ETHDEV_H_
 #define _I40E_ETHDEV_H_
 
+#include <rte_eth_ctrl.h>
+
 #define I40E_AQ_LEN               32
 #define I40E_AQ_BUF_SZ            4096
 /* Number of queues per TC should be one of 1, 2, 4, 8, 16, 32, 64 */
@@ -70,12 +72,21 @@
 
 struct i40e_adapter;
 
+/**
+ * MAC filter structure
+ */
+struct i40e_mac_filter_info {
+	uint16_t filter_type;
+	uint16_t queue_id;
+	struct ether_addr mac_addr;
+};
+
 TAILQ_HEAD(i40e_mac_filter_list, i40e_mac_filter);
 
 /* MAC filter list structure */
 struct i40e_mac_filter {
 	TAILQ_ENTRY(i40e_mac_filter) next;
-	struct ether_addr macaddr;
+	struct i40e_mac_filter_info mac_info;
 };
 
 TAILQ_HEAD(i40e_vsi_list_head, i40e_vsi_list);
@@ -104,8 +115,11 @@ struct i40e_veb {
 /* MACVLAN filter structure */
 struct i40e_macvlan_filter {
 	struct ether_addr macaddr;
+	uint16_t filter_type;
+	uint16_t queue_id;
 	uint16_t vlan_id;
 };
+
 /*
  * Structure that defines a VSI, associated with a adapter.
  */
@@ -300,7 +314,7 @@ int i40e_switch_rx_queue(struct i40e_hw *hw, uint16_t q_idx, bool on);
 int i40e_switch_tx_queue(struct i40e_hw *hw, uint16_t q_idx, bool on);
 int i40e_vsi_add_vlan(struct i40e_vsi *vsi, uint16_t vlan);
 int i40e_vsi_delete_vlan(struct i40e_vsi *vsi, uint16_t vlan);
-int i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr);
+int i40e_vsi_add_mac(struct i40e_vsi *vsi, struct i40e_mac_filter_info *filter);
 int i40e_vsi_delete_mac(struct i40e_vsi *vsi, struct ether_addr *addr);
 void i40e_update_vsi_stats(struct i40e_vsi *vsi);
 void i40e_pf_disable_irq0(struct i40e_hw *hw);
diff --git a/lib/librte_pmd_i40e/i40e_pf.c b/lib/librte_pmd_i40e/i40e_pf.c
index 682ff44..f9049e1 100644
--- a/lib/librte_pmd_i40e/i40e_pf.c
+++ b/lib/librte_pmd_i40e/i40e_pf.c
@@ -597,9 +597,12 @@ i40e_pf_host_process_cmd_add_ether_address(struct i40e_pf_vf *vf,
 	int ret = I40E_SUCCESS;
 	struct i40e_virtchnl_ether_addr_list *addr_list =
 			(struct i40e_virtchnl_ether_addr_list *)msg;
+	struct i40e_mac_filter_info filter;
 	int i;
 	struct ether_addr *mac;
 
+	memset(&filter, 0 , sizeof(struct i40e_mac_filter_info));
+
 	if (msg == NULL || msglen <= sizeof(*addr_list)) {
 		PMD_DRV_LOG(ERR, "add_ether_address argument too short");
 		ret = I40E_ERR_PARAM;
@@ -608,8 +611,10 @@ i40e_pf_host_process_cmd_add_ether_address(struct i40e_pf_vf *vf,
 
 	for (i = 0; i < addr_list->num_elements; i++) {
 		mac = (struct ether_addr *)(addr_list->list[i].addr);
+		(void)rte_memcpy(&filter.mac_addr, mac, ETHER_ADDR_LEN);
+		filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
 		if(!is_valid_assigned_ether_addr(mac) ||
-			i40e_vsi_add_mac(vf->vsi, mac)) {
+			i40e_vsi_add_mac(vf->vsi, &filter)) {
 			ret = I40E_ERR_INVALID_MAC_ADDR;
 			goto send_msg;
 		}
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH 4/5]i40e:add VF MACVLAN filter implementation in librte_pmd_i40e
  2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
                   ` (2 preceding siblings ...)
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 3/5]i40e:optimize MACVLAN filter implementation Jijiang Liu
@ 2014-09-23  3:29 ` Jijiang Liu
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 5/5]testpmd:test VF MACVLAN filter for i40e Jijiang Liu
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
  5 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-09-23  3:29 UTC (permalink / raw)
  To: dev

Add i40e_vf_mac_filter_set() function to support perfect match and hash match filter of MAC address and VLAN ID for a VF.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
Acked-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Changchun Ouyang <changchun.ouyang@intel.com>

---
 lib/librte_pmd_i40e/i40e_ethdev.c |  117 ++++++++++++++++++++++++++++++++++++-
 1 files changed, 114 insertions(+), 3 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index bdab17c..66ad3bb 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1591,6 +1591,118 @@ i40e_macaddr_remove(struct rte_eth_dev *dev, uint32_t index)
 		memset(&pf->dev_addr, 0, sizeof(struct ether_addr));
 }
 
+/* Set perfect match or hash match of MAC and VLAN for a VF */
+static int
+i40e_vf_mac_filter_set(struct i40e_pf *pf,
+		 struct rte_eth_mac_filter *filter,
+		 bool add)
+{
+	struct i40e_hw *hw;
+	struct i40e_mac_filter_info mac_filter;
+	struct ether_addr old_mac;
+	struct ether_addr *new_mac;
+	struct i40e_pf_vf *vf = NULL;
+	uint16_t vf_id;
+	int ret;
+
+	if (pf == NULL) {
+		PMD_DRV_LOG(ERR, "Invalid PF argument\n");
+		return -EINVAL;
+	}
+	hw = I40E_PF_TO_HW(pf);
+
+	if (filter == NULL) {
+		PMD_DRV_LOG(ERR, "Invalid mac filter argument\n");
+		return -EINVAL;
+	}
+
+	new_mac = &filter->mac_addr;
+
+	if (is_zero_ether_addr(new_mac)) {
+		PMD_DRV_LOG(ERR, "Invalid ethernet address\n");
+		return -EINVAL;
+	}
+
+	vf_id = filter->id;
+
+	if (vf_id > pf->vf_num - 1 || !pf->vfs) {
+		PMD_DRV_LOG(ERR, "Invalid argument\n");
+		return -EINVAL;
+	}
+	vf = &pf->vfs[vf_id];
+
+	if (add && is_same_ether_addr(new_mac, &(pf->dev_addr))) {
+		PMD_DRV_LOG(INFO, "Ignore adding permanent MAC address\n");
+		return -EINVAL;
+	}
+
+	if (add) {
+		(void)rte_memcpy(&old_mac, hw->mac.addr, ETHER_ADDR_LEN);
+		(void)rte_memcpy(hw->mac.addr, new_mac->addr_bytes,
+				ETHER_ADDR_LEN);
+		(void)rte_memcpy(&mac_filter.mac_addr, &filter->mac_addr,
+				 ETHER_ADDR_LEN);
+
+		mac_filter.filter_type = filter->filter_type;
+		mac_filter.queue_id = filter->queue_id;
+		ret = i40e_vsi_add_mac(vf->vsi, &mac_filter);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to add MAC filter\n");
+			return -1;
+		}
+		ether_addr_copy(new_mac, &pf->dev_addr);
+	} else {
+		(void)rte_memcpy(hw->mac.addr, hw->mac.perm_addr,
+				ETHER_ADDR_LEN);
+		ret = i40e_vsi_delete_mac(vf->vsi, &filter->mac_addr);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to delete MAC filter\n");
+			return -1;
+		}
+
+		/* Clear device address as it has been removed */
+		if (is_same_ether_addr(&(pf->dev_addr), new_mac))
+			memset(&pf->dev_addr, 0, sizeof(struct ether_addr));
+	}
+
+	return 0;
+}
+
+static int
+i40e_mac_filter_handle(struct i40e_pf *pf, enum rte_filter_op filter_op,
+		void *arg)
+{
+	struct rte_eth_mac_filter *filter;
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	int ret = I40E_NOT_SUPPORTED;
+
+	filter = (struct rte_eth_mac_filter *)(arg);
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_OP_NONE:
+		ret = I40E_SUCCESS;
+		break;
+	case RTE_ETH_FILTER_OP_ADD:
+		i40e_pf_disable_irq0(hw);
+		if (!filter->pf_vf_flag)
+			ret = i40e_vf_mac_filter_set(pf, filter, 1);
+		i40e_pf_enable_irq0(hw);
+		break;
+	case RTE_ETH_FILTER_OP_DELETE:
+		i40e_pf_disable_irq0(hw);
+		if (!filter->pf_vf_flag)
+			ret = i40e_vf_mac_filter_set(pf, filter, 0);
+		i40e_pf_enable_irq0(hw);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown operation %u\n", filter_op);
+		ret = I40E_ERR_PARAM;
+		break;
+	}
+
+	return ret;
+}
+
 static int
 i40e_dev_rss_reta_update(struct rte_eth_dev *dev,
 			 struct rte_eth_rss_reta *reta_conf)
@@ -4224,16 +4336,15 @@ 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;
 
-	if (dev == NULL)
-		return -EINVAL;
-
 	if (arg == NULL && filter_op != RTE_ETH_FILTER_OP_NONE)
 		return -EINVAL;
 
 	switch (filter_type) {
 	case RTE_ETH_FILTER_MACVLAN:
+		ret = i40e_mac_filter_handle(pf, filter_op, arg);
 		break;
 	default:
 		PMD_DRV_LOG(ERR, "unsupported filter type %u\n", filter_type);
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH 5/5]testpmd:test VF MACVLAN filter for i40e
  2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
                   ` (3 preceding siblings ...)
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 4/5]i40e:add VF MACVLAN filter implementation in librte_pmd_i40e Jijiang Liu
@ 2014-09-23  3:29 ` Jijiang Liu
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
  5 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-09-23  3:29 UTC (permalink / raw)
  To: dev

Add a test command in testpmd to test VF MACVLAN filter feature.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
Acked-by: Helin Zhang <helin.zhang@intel.com>
Acked-by: Jingjing Wu <jingjing.wu@intel.com>
Acked-by: Changchun Ouyang <changchun.ouyang@intel.com>
---
 app/test-pmd/cmdline.c |  115 ++++++++++++++++++++++++++++++++++++++++++++++-
 1 files changed, 112 insertions(+), 3 deletions(-)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index b04a4e8..bfdf265 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -351,9 +351,14 @@ static void cmd_help_long_parsed(void *parsed_result,
 			"    e.g., 'set stat_qmap rx 0 2 5' sets rx queue 2"
 			" on port 0 to mapping 5.\n\n"
 
-			"set port (port_id) vf (vf_id) rx|tx on|off \n"
+			"set port (port_id) vf (vf_id) rx|tx on|off\n"
 			"    Enable/Disable a VF receive/tranmit from a port\n\n"
 
+			"set port (port_id) vf (vf_id) (mac_addr)"
+			" (exact-mac#exact-mac-vlan#hashmac|hashmac-vlan) on|off\n"
+			"   Add/Remove unicast or multicast MAC addr filter"
+			" for a VF.\n\n"
+
 			"set port (port_id) vf (vf_id) rxmode (AUPE|ROPE|BAM"
 			"|MPE) (on|off)\n"
 			"    AUPE:accepts untagged VLAN;"
@@ -5795,6 +5800,108 @@ cmdline_parse_inst_t cmd_set_uc_all_hash_filter = {
 	},
 };
 
+/* *** CONFIGURE MACVLAN FILTER FOR VF(s) *** */
+struct cmd_set_vf_macvlan_filter {
+	cmdline_fixed_string_t set;
+	cmdline_fixed_string_t port;
+	uint8_t port_id;
+	cmdline_fixed_string_t vf;
+	uint8_t vf_id;
+	struct ether_addr address;
+	cmdline_fixed_string_t filter_type;
+	cmdline_fixed_string_t mode;
+};
+
+static void
+cmd_set_vf_macvlan_parsed(void *parsed_result,
+		       __attribute__((unused)) struct cmdline *cl,
+		       __attribute__((unused)) void *data)
+{
+	int is_on, ret = 0;
+	struct cmd_set_vf_macvlan_filter *res = parsed_result;
+	struct rte_eth_mac_filter filter;
+
+	memset(&filter, 0, sizeof(struct rte_eth_mac_filter));
+
+	(void)rte_memcpy(&filter.mac_addr, &res->address, ETHER_ADDR_LEN);
+	filter.id = res->vf_id;
+	filter.pf_vf_flag = 0;
+
+	if (!strcmp(res->filter_type, "exact-mac"))
+		filter.filter_type = RTE_MAC_PERFECT_MATCH;
+	else if (!strcmp(res->filter_type, "exact-mac-vlan"))
+		filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
+	else if (!strcmp(res->filter_type, "hashmac"))
+		filter.filter_type = RTE_MAC_HASH_MATCH;
+	else if (!strcmp(res->filter_type, "hashmac-vlan"))
+		filter.filter_type = RTE_MACVLAN_HASH_MATCH;
+
+	is_on = (strcmp(res->mode, "on") == 0) ? 1 : 0;
+
+	if (is_on)
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+					RTE_ETH_FILTER_MACVLAN,
+					RTE_ETH_FILTER_OP_ADD,
+					 &filter);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+					RTE_ETH_FILTER_MACVLAN,
+					RTE_ETH_FILTER_OP_DELETE,
+					&filter);
+
+	if (ret < 0)
+		printf("bad set MAC hash parameter, return code = %d\n", ret);
+
+}
+
+cmdline_parse_token_string_t cmd_set_vf_macvlan_set =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 set, "set");
+cmdline_parse_token_string_t cmd_set_vf_macvlan_port =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 port, "port");
+cmdline_parse_token_num_t cmd_set_vf_macvlan_portid =
+	TOKEN_NUM_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_set_vf_macvlan_vf =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 vf, "vf");
+cmdline_parse_token_num_t cmd_set_vf_macvlan_vf_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				vf_id, UINT8);
+cmdline_parse_token_etheraddr_t cmd_set_vf_macvlan_mac =
+	TOKEN_ETHERADDR_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				address);
+cmdline_parse_token_string_t cmd_set_vf_macvlan_filter_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				filter_type, "exact-mac#exact-mac-vlan"
+				"#hashmac#hashmac-vlan");
+cmdline_parse_token_string_t cmd_set_vf_macvlan_mode =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 mode, "on#off");
+
+cmdline_parse_inst_t cmd_set_vf_macvlan_filter = {
+	.f = cmd_set_vf_macvlan_parsed,
+	.data = NULL,
+	.help_str = "set port (portid) vf (vfid) (mac-addr) "
+			"(exact-mac|exact-mac-vlan|hashmac|hashmac-vlan) "
+			"on|off\n"
+			"exact match rule:exact match of MAC or MAC and VLAN; "
+			"hash match rule: hash match of MAC and exact match "
+			"of VLAN",
+	.tokens = {
+		(void *)&cmd_set_vf_macvlan_set,
+		(void *)&cmd_set_vf_macvlan_port,
+		(void *)&cmd_set_vf_macvlan_portid,
+		(void *)&cmd_set_vf_macvlan_vf,
+		(void *)&cmd_set_vf_macvlan_vf_id,
+		(void *)&cmd_set_vf_macvlan_mac,
+		(void *)&cmd_set_vf_macvlan_filter_type,
+		(void *)&cmd_set_vf_macvlan_mode,
+		NULL,
+	},
+};
+
 /* *** CONFIGURE VF TRAFFIC CONTROL *** */
 struct cmd_set_vf_traffic {
 	cmdline_fixed_string_t set;
@@ -5843,7 +5950,8 @@ cmdline_parse_token_string_t cmd_setvf_traffic_mode =
 cmdline_parse_inst_t cmd_set_vf_traffic = {
 	.f = cmd_set_vf_traffic_parsed,
 	.data = NULL,
-	.help_str = "set port X vf Y rx|tx on|off (X = port number,Y = vf id)",
+	.help_str = "set port X vf Y rx|tx on|off"
+			"(X = port number,Y = vf id)",
 	.tokens = {
 		(void *)&cmd_setvf_traffic_set,
 		(void *)&cmd_setvf_traffic_port,
@@ -7501,7 +7609,8 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_set_vf_rxmode,
 	(cmdline_parse_inst_t *)&cmd_set_uc_hash_filter,
 	(cmdline_parse_inst_t *)&cmd_set_uc_all_hash_filter,
-	(cmdline_parse_inst_t *)&cmd_vf_mac_addr_filter ,
+	(cmdline_parse_inst_t *)&cmd_vf_mac_addr_filter,
+	(cmdline_parse_inst_t *)&cmd_set_vf_macvlan_filter,
 	(cmdline_parse_inst_t *)&cmd_set_vf_traffic,
 	(cmdline_parse_inst_t *)&cmd_vf_rxvlan_filter,
 	(cmdline_parse_inst_t *)&cmd_queue_rate_limit,
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville
  2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
                   ` (4 preceding siblings ...)
  2014-09-23  3:29 ` [dpdk-dev] [PATCH 5/5]testpmd:test VF MACVLAN filter for i40e Jijiang Liu
@ 2014-10-24  7:58 ` Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 1/4] librte_ether:extend MAC filter data structures Jijiang Liu
                     ` (4 more replies)
  5 siblings, 5 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-10-24  7:58 UTC (permalink / raw)
  To: dev

The patch set enhances configurability of MAC filter and supports VF MAC filter on Fortville.
 
It mainly includes:
 - The following filter type are configurable:
   1. Perfect match of MAC address
   2. Perfect match of MAC address and VLAN ID
   3. Hash match of MAC address
   4. Hash match of MAC address and perfect match of VLAN ID
 - Support perfect and hash match of unicast and multicast MAC address for VF for i40e

 v2 updates:
  * Integrate the v1 patch set into the new filter framework.
  * Optimize MAC filter data structures in rte_eth_ctrl.h file.
 
jijiangl (4):
  Expand data structures of MAC filter in rte_eth_ctrl.h file.
  Expand MAC filter implemantation in i40e. 
  Support VF MAC filter in i40e.
  Test VF MAC filter in testpmd 

 app/test-pmd/cmdline.c            |  119 +++++++++++++++-
 lib/librte_ether/rte_eth_ctrl.h   |   23 +++
 lib/librte_pmd_i40e/i40e_ethdev.c |  283 ++++++++++++++++++++++++++++++++-----
 lib/librte_pmd_i40e/i40e_ethdev.h |   18 ++-
 lib/librte_pmd_i40e/i40e_pf.c     |    7 +-
 5 files changed, 404 insertions(+), 46 deletions(-)

-- 
1.7.7.6

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

* [dpdk-dev] [PATCH v2 1/4] librte_ether:extend MAC filter data structures
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
@ 2014-10-24  7:58   ` Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 2/4] i40e:expand MAC filter implemantation in i40e Jijiang Liu
                     ` (3 subsequent siblings)
  4 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-10-24  7:58 UTC (permalink / raw)
  To: dev

Add the data definations for MAC filter enhancement in rte_eth_ctrl.h file.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
---
 lib/librte_ether/rte_eth_ctrl.h |   23 +++++++++++++++++++++++
 1 files changed, 23 insertions(+), 0 deletions(-)

diff --git a/lib/librte_ether/rte_eth_ctrl.h b/lib/librte_ether/rte_eth_ctrl.h
index df21ac6..699ed2e 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_MACVLAN,
 	RTE_ETH_FILTER_MAX
 };
 
@@ -71,6 +72,28 @@ enum rte_filter_op {
 	RTE_ETH_FILTER_OP_MAX
 };
 
+/**
+ * MAC filter type
+ */
+enum rte_mac_filter_type {
+	RTE_MAC_PERFECT_MATCH = 1, /**< exact match of MAC addr. */
+	RTE_MACVLAN_PERFECT_MATCH,
+	/**< exact match of MAC addr and VLAN ID. */
+	RTE_MAC_HASH_MATCH, /**< hash match of MAC addr. */
+	RTE_MACVLAN_HASH_MATCH,
+	/**< hash match of MAC addr and exact match of VLAN ID. */
+};
+
+/**
+ * MAC filter info
+ */
+struct rte_eth_mac_filter {
+	uint8_t is_vf; /**< 1 for VF, 0 for port dev */
+	uint16_t dst_id; /**<VF ID, available when is_vf is 1*/
+	uint16_t filter_type; /**< MAC filter type */
+	struct ether_addr mac_addr;
+};
+
 #ifdef __cplusplus
 }
 #endif
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH v2 2/4] i40e:expand MAC filter implemantation in i40e
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 1/4] librte_ether:extend MAC filter data structures Jijiang Liu
@ 2014-10-24  7:58   ` Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 3/4] i40e:add VF MAC filter Jijiang Liu
                     ` (2 subsequent siblings)
  4 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-10-24  7:58 UTC (permalink / raw)
  To: dev

This patch mainly optimizes the i40e_add_macvlan_filters() and the i40e_remove_macvlan_filters() functions in order that
we are able to provide filter type configuration. And another relevant MAC filter codes are changed based on new data structures.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  165 ++++++++++++++++++++++++++++--------
 lib/librte_pmd_i40e/i40e_ethdev.h |   18 ++++-
 lib/librte_pmd_i40e/i40e_pf.c     |    7 ++-
 3 files changed, 149 insertions(+), 41 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 3b75f0f..5fae0e1 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1529,6 +1529,7 @@ i40e_macaddr_add(struct rte_eth_dev *dev,
 {
 	struct i40e_pf *pf = I40E_DEV_PRIVATE_TO_PF(dev->data->dev_private);
 	struct i40e_hw *hw = I40E_DEV_PRIVATE_TO_HW(dev->data->dev_private);
+	struct i40e_mac_filter_info mac_filter;
 	struct i40e_vsi *vsi = pf->main_vsi;
 	struct ether_addr old_mac;
 	int ret;
@@ -1554,8 +1555,10 @@ i40e_macaddr_add(struct rte_eth_dev *dev,
 	(void)rte_memcpy(&old_mac, hw->mac.addr, ETHER_ADDR_LEN);
 	(void)rte_memcpy(hw->mac.addr, mac_addr->addr_bytes,
 			ETHER_ADDR_LEN);
+	(void)rte_memcpy(&mac_filter.mac_addr, mac_addr, ETHER_ADDR_LEN);
+	mac_filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
 
-	ret = i40e_vsi_add_mac(vsi, mac_addr);
+	ret = i40e_vsi_add_mac(vsi, &mac_filter);
 	if (ret != I40E_SUCCESS) {
 		PMD_DRV_LOG(ERR, "Failed to add MACVLAN filter");
 		return;
@@ -2472,6 +2475,7 @@ i40e_update_default_filter_setting(struct i40e_vsi *vsi)
 {
 	struct i40e_hw *hw = I40E_VSI_TO_HW(vsi);
 	struct i40e_aqc_remove_macvlan_element_data def_filter;
+	struct i40e_mac_filter_info filter;
 	int ret;
 
 	if (vsi->type != I40E_VSI_MAIN)
@@ -2485,6 +2489,7 @@ i40e_update_default_filter_setting(struct i40e_vsi *vsi)
 	ret = i40e_aq_remove_macvlan(hw, vsi->seid, &def_filter, 1, NULL);
 	if (ret != I40E_SUCCESS) {
 		struct i40e_mac_filter *f;
+		struct ether_addr *mac;
 
 		PMD_DRV_LOG(WARNING, "Cannot remove the default "
 			    "macvlan filter");
@@ -2494,15 +2499,18 @@ i40e_update_default_filter_setting(struct i40e_vsi *vsi)
 			PMD_DRV_LOG(ERR, "failed to allocate memory");
 			return I40E_ERR_NO_MEMORY;
 		}
-		(void)rte_memcpy(&f->macaddr.addr_bytes, hw->mac.perm_addr,
+		mac = &f->mac_info.mac_addr;
+		(void)rte_memcpy(&mac->addr_bytes, hw->mac.perm_addr,
 				ETH_ADDR_LEN);
 		TAILQ_INSERT_TAIL(&vsi->mac_list, f, next);
 		vsi->mac_num++;
 
 		return ret;
 	}
-
-	return i40e_vsi_add_mac(vsi, (struct ether_addr *)(hw->mac.perm_addr));
+	(void)rte_memcpy(&filter.mac_addr,
+		(struct ether_addr *)(hw->mac.perm_addr), ETH_ADDR_LEN);
+	filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
+	return i40e_vsi_add_mac(vsi, &filter);
 }
 
 static int
@@ -2556,6 +2564,7 @@ i40e_vsi_setup(struct i40e_pf *pf,
 {
 	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
 	struct i40e_vsi *vsi;
+	struct i40e_mac_filter_info filter;
 	int ret;
 	struct i40e_vsi_context ctxt;
 	struct ether_addr broadcast =
@@ -2766,7 +2775,10 @@ i40e_vsi_setup(struct i40e_pf *pf,
 	}
 
 	/* MAC/VLAN configuration */
-	ret = i40e_vsi_add_mac(vsi, &broadcast);
+	(void)rte_memcpy(&filter.mac_addr, &broadcast, ETHER_ADDR_LEN);
+	filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
+
+	ret = i40e_vsi_add_mac(vsi, &filter);
 	if (ret != I40E_SUCCESS) {
 		PMD_DRV_LOG(ERR, "Failed to add MACVLAN filter");
 		goto fail_msix_alloc;
@@ -3467,6 +3479,7 @@ i40e_add_macvlan_filters(struct i40e_vsi *vsi,
 {
 	int ele_num, ele_buff_size;
 	int num, actual_num, i;
+	uint16_t flags;
 	int ret = I40E_SUCCESS;
 	struct i40e_hw *hw = I40E_VSI_TO_HW(vsi);
 	struct i40e_aqc_add_macvlan_element_data *req_list;
@@ -3492,9 +3505,31 @@ i40e_add_macvlan_filters(struct i40e_vsi *vsi,
 				&filter[num + i].macaddr, ETH_ADDR_LEN);
 			req_list[i].vlan_tag =
 				rte_cpu_to_le_16(filter[num + i].vlan_id);
-			req_list[i].flags = rte_cpu_to_le_16(\
-				I40E_AQC_MACVLAN_ADD_PERFECT_MATCH);
+
+			switch (filter[num + i].filter_type) {
+			case RTE_MAC_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_PERFECT_MATCH |
+					I40E_AQC_MACVLAN_ADD_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_PERFECT_MATCH;
+				break;
+			case RTE_MAC_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_HASH_MATCH |
+					I40E_AQC_MACVLAN_ADD_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_ADD_HASH_MATCH;
+				break;
+			default:
+				PMD_DRV_LOG(ERR, "Invalid MAC match type\n");
+				ret = I40E_ERR_PARAM;
+				goto DONE;
+			}
+
 			req_list[i].queue_number = 0;
+
+			req_list[i].flags = rte_cpu_to_le_16(flags);
 		}
 
 		ret = i40e_aq_add_macvlan(hw, vsi->seid, req_list,
@@ -3518,6 +3553,7 @@ i40e_remove_macvlan_filters(struct i40e_vsi *vsi,
 {
 	int ele_num, ele_buff_size;
 	int num, actual_num, i;
+	uint16_t flags;
 	int ret = I40E_SUCCESS;
 	struct i40e_hw *hw = I40E_VSI_TO_HW(vsi);
 	struct i40e_aqc_remove_macvlan_element_data *req_list;
@@ -3544,7 +3580,28 @@ i40e_remove_macvlan_filters(struct i40e_vsi *vsi,
 				&filter[num + i].macaddr, ETH_ADDR_LEN);
 			req_list[i].vlan_tag =
 				rte_cpu_to_le_16(filter[num + i].vlan_id);
-			req_list[i].flags = I40E_AQC_MACVLAN_DEL_PERFECT_MATCH;
+
+			switch (filter[num + i].filter_type) {
+			case RTE_MAC_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_PERFECT_MATCH |
+					I40E_AQC_MACVLAN_DEL_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_PERFECT_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_PERFECT_MATCH;
+				break;
+			case RTE_MAC_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_HASH_MATCH |
+					I40E_AQC_MACVLAN_DEL_IGNORE_VLAN;
+				break;
+			case RTE_MACVLAN_HASH_MATCH:
+				flags = I40E_AQC_MACVLAN_DEL_HASH_MATCH;
+				break;
+			default:
+				PMD_DRV_LOG(ERR, "Invalid MAC filter type\n");
+				ret = I40E_ERR_PARAM;
+				goto DONE;
+			}
+			req_list[i].flags = rte_cpu_to_le_16(flags);
 		}
 
 		ret = i40e_aq_remove_macvlan(hw, vsi->seid, req_list,
@@ -3569,7 +3626,7 @@ i40e_find_mac_filter(struct i40e_vsi *vsi,
 	struct i40e_mac_filter *f;
 
 	TAILQ_FOREACH(f, &vsi->mac_list, next) {
-		if (is_same_ether_addr(macaddr, &(f->macaddr)))
+		if (is_same_ether_addr(macaddr, &f->mac_info.mac_addr))
 			return f;
 	}
 
@@ -3670,8 +3727,10 @@ i40e_find_all_mac_for_vlan(struct i40e_vsi *vsi,
 			PMD_DRV_LOG(ERR, "buffer number not match");
 			return I40E_ERR_PARAM;
 		}
-		(void)rte_memcpy(&mv_f[i].macaddr, &f->macaddr, ETH_ADDR_LEN);
+		(void)rte_memcpy(&mv_f[i].macaddr, &f->mac_info.mac_addr,
+				ETH_ADDR_LEN);
 		mv_f[i].vlan_id = vlan;
+		mv_f[i].filter_type = f->mac_info.filter_type;
 		i++;
 	}
 
@@ -3705,14 +3764,14 @@ i40e_vsi_remove_all_macvlan_filter(struct i40e_vsi *vsi)
 	if (vsi->vlan_num == 0) {
 		TAILQ_FOREACH(f, &vsi->mac_list, next) {
 			(void)rte_memcpy(&mv_f[i].macaddr,
-				&f->macaddr, ETH_ADDR_LEN);
+				&f->mac_info.mac_addr, ETH_ADDR_LEN);
 			mv_f[i].vlan_id = 0;
 			i++;
 		}
 	} else {
 		TAILQ_FOREACH(f, &vsi->mac_list, next) {
 			ret = i40e_find_all_vlan_for_mac(vsi,&mv_f[i],
-					vsi->vlan_num, &f->macaddr);
+					vsi->vlan_num, &f->mac_info.mac_addr);
 			if (ret != I40E_SUCCESS)
 				goto DONE;
 			i += vsi->vlan_num;
@@ -3836,28 +3895,32 @@ DONE:
 }
 
 int
-i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
+i40e_vsi_add_mac(struct i40e_vsi *vsi, struct i40e_mac_filter_info *mac_filter)
 {
 	struct i40e_mac_filter *f;
 	struct i40e_macvlan_filter *mv_f;
-	int vlan_num;
+	int i, vlan_num = 0;
 	int ret = I40E_SUCCESS;
 
 	/* If it's add and we've config it, return */
-	f = i40e_find_mac_filter(vsi, addr);
+	f = i40e_find_mac_filter(vsi, &mac_filter->mac_addr);
 	if (f != NULL)
 		return I40E_SUCCESS;
+	if ((mac_filter->filter_type == RTE_MACVLAN_PERFECT_MATCH) ||
+		(mac_filter->filter_type == RTE_MACVLAN_HASH_MATCH)) {
 
-	/**
-	 * If vlan_num is 0, that's the first time to add mac,
-	 * set mask for vlan_id 0.
-	 */
-	if (vsi->vlan_num == 0) {
-		i40e_set_vlan_filter(vsi, 0, 1);
-		vsi->vlan_num = 1;
-	}
-
-	vlan_num = vsi->vlan_num;
+		/**
+		 * If vlan_num is 0, that's the first time to add mac,
+		 * set mask for vlan_id 0.
+		 */
+		if (vsi->vlan_num == 0) {
+			i40e_set_vlan_filter(vsi, 0, 1);
+			vsi->vlan_num = 1;
+		}
+		vlan_num = vsi->vlan_num;
+	} else if ((mac_filter->filter_type == RTE_MAC_PERFECT_MATCH) ||
+			(mac_filter->filter_type == RTE_MAC_HASH_MATCH))
+		vlan_num = 1;
 
 	mv_f = rte_zmalloc("macvlan_data", vlan_num * sizeof(*mv_f), 0);
 	if (mv_f == NULL) {
@@ -3865,9 +3928,19 @@ i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 		return I40E_ERR_NO_MEMORY;
 	}
 
-	ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num, addr);
-	if (ret != I40E_SUCCESS)
-		goto DONE;
+	for (i = 0; i < vlan_num; i++) {
+		mv_f[i].filter_type = mac_filter->filter_type;
+		(void)rte_memcpy(&mv_f[i].macaddr, &mac_filter->mac_addr,
+				ETH_ADDR_LEN);
+	}
+
+	if (mac_filter->filter_type == RTE_MACVLAN_PERFECT_MATCH ||
+		mac_filter->filter_type == RTE_MACVLAN_HASH_MATCH) {
+		ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num,
+					&mac_filter->mac_addr);
+		if (ret != I40E_SUCCESS)
+			goto DONE;
+	}
 
 	ret = i40e_add_macvlan_filters(vsi, mv_f, vlan_num);
 	if (ret != I40E_SUCCESS)
@@ -3880,7 +3953,9 @@ i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 		ret = I40E_ERR_NO_MEMORY;
 		goto DONE;
 	}
-	(void)rte_memcpy(&f->macaddr, addr, ETH_ADDR_LEN);
+	(void)rte_memcpy(&f->mac_info.mac_addr, &mac_filter->mac_addr,
+			ETH_ADDR_LEN);
+	f->mac_info.filter_type = mac_filter->filter_type;
 	TAILQ_INSERT_TAIL(&vsi->mac_list, f, next);
 	vsi->mac_num++;
 
@@ -3896,7 +3971,8 @@ i40e_vsi_delete_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 {
 	struct i40e_mac_filter *f;
 	struct i40e_macvlan_filter *mv_f;
-	int vlan_num;
+	int i, vlan_num;
+	enum rte_mac_filter_type filter_type;
 	int ret = I40E_SUCCESS;
 
 	/* Can't find it, return an error */
@@ -3905,19 +3981,34 @@ i40e_vsi_delete_mac(struct i40e_vsi *vsi, struct ether_addr *addr)
 		return I40E_ERR_PARAM;
 
 	vlan_num = vsi->vlan_num;
-	if (vlan_num == 0) {
-		PMD_DRV_LOG(ERR, "VLAN number shouldn't be 0");
-		return I40E_ERR_PARAM;
-	}
+	filter_type = f->mac_info.filter_type;
+	if (filter_type == RTE_MACVLAN_PERFECT_MATCH ||
+		filter_type == RTE_MACVLAN_HASH_MATCH) {
+		if (vlan_num == 0) {
+			PMD_DRV_LOG(ERR, "VLAN number shouldn't be 0\n");
+			return I40E_ERR_PARAM;
+		}
+	} else if (filter_type == RTE_MAC_PERFECT_MATCH ||
+			filter_type == RTE_MAC_HASH_MATCH)
+		vlan_num = 1;
+
 	mv_f = rte_zmalloc("macvlan_data", vlan_num * sizeof(*mv_f), 0);
 	if (mv_f == NULL) {
 		PMD_DRV_LOG(ERR, "failed to allocate memory");
 		return I40E_ERR_NO_MEMORY;
 	}
 
-	ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num, addr);
-	if (ret != I40E_SUCCESS)
-		goto DONE;
+	for (i = 0; i < vlan_num; i++) {
+		mv_f[i].filter_type = filter_type;
+		(void)rte_memcpy(&mv_f[i].macaddr, &f->mac_info.mac_addr,
+				ETH_ADDR_LEN);
+	}
+	if (filter_type == RTE_MACVLAN_PERFECT_MATCH ||
+			filter_type == RTE_MACVLAN_HASH_MATCH) {
+		ret = i40e_find_all_vlan_for_mac(vsi, mv_f, vlan_num, addr);
+		if (ret != I40E_SUCCESS)
+			goto DONE;
+	}
 
 	ret = i40e_remove_macvlan_filters(vsi, mv_f, vlan_num);
 	if (ret != I40E_SUCCESS)
diff --git a/lib/librte_pmd_i40e/i40e_ethdev.h b/lib/librte_pmd_i40e/i40e_ethdev.h
index 1d42cd2..3ea9768 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.h
+++ b/lib/librte_pmd_i40e/i40e_ethdev.h
@@ -34,6 +34,8 @@
 #ifndef _I40E_ETHDEV_H_
 #define _I40E_ETHDEV_H_
 
+#include <rte_eth_ctrl.h>
+
 #define I40E_AQ_LEN               32
 #define I40E_AQ_BUF_SZ            4096
 /* Number of queues per TC should be one of 1, 2, 4, 8, 16, 32, 64 */
@@ -100,12 +102,20 @@
 
 struct i40e_adapter;
 
+/**
+ * MAC filter structure
+ */
+struct i40e_mac_filter_info {
+	enum rte_mac_filter_type filter_type;
+	struct ether_addr mac_addr;
+};
+
 TAILQ_HEAD(i40e_mac_filter_list, i40e_mac_filter);
 
 /* MAC filter list structure */
 struct i40e_mac_filter {
 	TAILQ_ENTRY(i40e_mac_filter) next;
-	struct ether_addr macaddr;
+	struct i40e_mac_filter_info mac_info;
 };
 
 TAILQ_HEAD(i40e_vsi_list_head, i40e_vsi_list);
@@ -131,11 +141,13 @@ struct i40e_veb {
 	struct i40e_eth_stats stats;
 };
 
-/* MACVLAN filter structure */
+/* i40e MACVLAN filter structure */
 struct i40e_macvlan_filter {
 	struct ether_addr macaddr;
+	enum rte_mac_filter_type filter_type;
 	uint16_t vlan_id;
 };
+
 /*
  * Structure that defines a VSI, associated with a adapter.
  */
@@ -332,7 +344,7 @@ int i40e_switch_rx_queue(struct i40e_hw *hw, uint16_t q_idx, bool on);
 int i40e_switch_tx_queue(struct i40e_hw *hw, uint16_t q_idx, bool on);
 int i40e_vsi_add_vlan(struct i40e_vsi *vsi, uint16_t vlan);
 int i40e_vsi_delete_vlan(struct i40e_vsi *vsi, uint16_t vlan);
-int i40e_vsi_add_mac(struct i40e_vsi *vsi, struct ether_addr *addr);
+int i40e_vsi_add_mac(struct i40e_vsi *vsi, struct i40e_mac_filter_info *filter);
 int i40e_vsi_delete_mac(struct i40e_vsi *vsi, struct ether_addr *addr);
 void i40e_update_vsi_stats(struct i40e_vsi *vsi);
 void i40e_pf_disable_irq0(struct i40e_hw *hw);
diff --git a/lib/librte_pmd_i40e/i40e_pf.c b/lib/librte_pmd_i40e/i40e_pf.c
index 682ff44..f9049e1 100644
--- a/lib/librte_pmd_i40e/i40e_pf.c
+++ b/lib/librte_pmd_i40e/i40e_pf.c
@@ -597,9 +597,12 @@ i40e_pf_host_process_cmd_add_ether_address(struct i40e_pf_vf *vf,
 	int ret = I40E_SUCCESS;
 	struct i40e_virtchnl_ether_addr_list *addr_list =
 			(struct i40e_virtchnl_ether_addr_list *)msg;
+	struct i40e_mac_filter_info filter;
 	int i;
 	struct ether_addr *mac;
 
+	memset(&filter, 0 , sizeof(struct i40e_mac_filter_info));
+
 	if (msg == NULL || msglen <= sizeof(*addr_list)) {
 		PMD_DRV_LOG(ERR, "add_ether_address argument too short");
 		ret = I40E_ERR_PARAM;
@@ -608,8 +611,10 @@ i40e_pf_host_process_cmd_add_ether_address(struct i40e_pf_vf *vf,
 
 	for (i = 0; i < addr_list->num_elements; i++) {
 		mac = (struct ether_addr *)(addr_list->list[i].addr);
+		(void)rte_memcpy(&filter.mac_addr, mac, ETHER_ADDR_LEN);
+		filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
 		if(!is_valid_assigned_ether_addr(mac) ||
-			i40e_vsi_add_mac(vf->vsi, mac)) {
+			i40e_vsi_add_mac(vf->vsi, &filter)) {
 			ret = I40E_ERR_INVALID_MAC_ADDR;
 			goto send_msg;
 		}
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH v2 3/4] i40e:add VF MAC filter
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 1/4] librte_ether:extend MAC filter data structures Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 2/4] i40e:expand MAC filter implemantation in i40e Jijiang Liu
@ 2014-10-24  7:58   ` Jijiang Liu
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 4/4] app/testpmd:test " Jijiang Liu
  2014-10-30 22:35   ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Thomas Monjalon
  4 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-10-24  7:58 UTC (permalink / raw)
  To: dev

It mainly add i40e_vf_mac_filter_set() function to support perfect match and hash match of MAC address and VLAN ID for VF.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
---
 lib/librte_pmd_i40e/i40e_ethdev.c |  118 ++++++++++++++++++++++++++++++++++++-
 1 files changed, 116 insertions(+), 2 deletions(-)

diff --git a/lib/librte_pmd_i40e/i40e_ethdev.c b/lib/librte_pmd_i40e/i40e_ethdev.c
index 5fae0e1..f9e3aa8 100644
--- a/lib/librte_pmd_i40e/i40e_ethdev.c
+++ b/lib/librte_pmd_i40e/i40e_ethdev.c
@@ -1605,6 +1605,119 @@ i40e_macaddr_remove(struct rte_eth_dev *dev, uint32_t index)
 		memset(&pf->dev_addr, 0, sizeof(struct ether_addr));
 }
 
+/* Set perfect match or hash match of MAC and VLAN for a VF */
+static int
+i40e_vf_mac_filter_set(struct i40e_pf *pf,
+		 struct rte_eth_mac_filter *filter,
+		 bool add)
+{
+	struct i40e_hw *hw;
+	struct i40e_mac_filter_info mac_filter;
+	struct ether_addr old_mac;
+	struct ether_addr *new_mac;
+	struct i40e_pf_vf *vf = NULL;
+	uint16_t vf_id;
+	int ret;
+
+	if (pf == NULL) {
+		PMD_DRV_LOG(ERR, "Invalid PF argument\n");
+		return -EINVAL;
+	}
+	hw = I40E_PF_TO_HW(pf);
+
+	if (filter == NULL) {
+		PMD_DRV_LOG(ERR, "Invalid mac filter argument\n");
+		return -EINVAL;
+	}
+
+	new_mac = &filter->mac_addr;
+
+	if (is_zero_ether_addr(new_mac)) {
+		PMD_DRV_LOG(ERR, "Invalid ethernet address\n");
+		return -EINVAL;
+	}
+
+	vf_id = filter->dst_id;
+
+	if (vf_id > pf->vf_num - 1 || !pf->vfs) {
+		PMD_DRV_LOG(ERR, "Invalid argument\n");
+		return -EINVAL;
+	}
+	vf = &pf->vfs[vf_id];
+
+	if (add && is_same_ether_addr(new_mac, &(pf->dev_addr))) {
+		PMD_DRV_LOG(INFO, "Ignore adding permanent MAC address\n");
+		return -EINVAL;
+	}
+
+	if (add) {
+		(void)rte_memcpy(&old_mac, hw->mac.addr, ETHER_ADDR_LEN);
+		(void)rte_memcpy(hw->mac.addr, new_mac->addr_bytes,
+				ETHER_ADDR_LEN);
+		(void)rte_memcpy(&mac_filter.mac_addr, &filter->mac_addr,
+				 ETHER_ADDR_LEN);
+
+		mac_filter.filter_type = filter->filter_type;
+		ret = i40e_vsi_add_mac(vf->vsi, &mac_filter);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to add MAC filter\n");
+			return -1;
+		}
+		ether_addr_copy(new_mac, &pf->dev_addr);
+	} else {
+		(void)rte_memcpy(hw->mac.addr, hw->mac.perm_addr,
+				ETHER_ADDR_LEN);
+		ret = i40e_vsi_delete_mac(vf->vsi, &filter->mac_addr);
+		if (ret != I40E_SUCCESS) {
+			PMD_DRV_LOG(ERR, "Failed to delete MAC filter\n");
+			return -1;
+		}
+
+		/* Clear device address as it has been removed */
+		if (is_same_ether_addr(&(pf->dev_addr), new_mac))
+			memset(&pf->dev_addr, 0, sizeof(struct ether_addr));
+	}
+
+	return 0;
+}
+
+/* MAC filter handle */
+static int
+i40e_mac_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);
+	struct rte_eth_mac_filter *filter;
+	struct i40e_hw *hw = I40E_PF_TO_HW(pf);
+	int ret = I40E_NOT_SUPPORTED;
+
+	filter = (struct rte_eth_mac_filter *)(arg);
+
+	switch (filter_op) {
+	case RTE_ETH_FILTER_NONE:
+		ret = I40E_SUCCESS;
+		break;
+	case RTE_ETH_FILTER_ADD:
+		i40e_pf_disable_irq0(hw);
+		if (filter->is_vf)
+			ret = i40e_vf_mac_filter_set(pf, filter, 1);
+		i40e_pf_enable_irq0(hw);
+		break;
+	case RTE_ETH_FILTER_DELETE:
+		i40e_pf_disable_irq0(hw);
+		if (filter->is_vf)
+			ret = i40e_vf_mac_filter_set(pf, filter, 0);
+		i40e_pf_enable_irq0(hw);
+		break;
+	default:
+		PMD_DRV_LOG(ERR, "unknown operation %u\n", filter_op);
+		ret = I40E_ERR_PARAM;
+		break;
+	}
+
+	return ret;
+}
+
 static int
 i40e_dev_rss_reta_update(struct rte_eth_dev *dev,
 			 struct rte_eth_rss_reta *reta_conf)
@@ -4243,13 +4356,14 @@ i40e_dev_filter_ctrl(struct rte_eth_dev *dev,
 		     void *arg)
 {
 	int ret = 0;
-	(void)filter_op;
-	(void)arg;
 
 	if (dev == NULL)
 		return -EINVAL;
 
 	switch (filter_type) {
+	case RTE_ETH_FILTER_MACVLAN:
+		ret = i40e_mac_filter_handle(dev, filter_op, arg);
+		 break;
 	default:
 		PMD_DRV_LOG(WARNING, "Filter type (%d) not supported",
 							filter_type);
-- 
1.7.7.6

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

* [dpdk-dev] [PATCH v2 4/4] app/testpmd:test VF MAC filter
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
                     ` (2 preceding siblings ...)
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 3/4] i40e:add VF MAC filter Jijiang Liu
@ 2014-10-24  7:58   ` Jijiang Liu
  2014-10-30 22:35   ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Thomas Monjalon
  4 siblings, 0 replies; 14+ messages in thread
From: Jijiang Liu @ 2014-10-24  7:58 UTC (permalink / raw)
  To: dev

Add a test command in testpmd to test VF MAC filter feature.

Signed-off-by: Jijiang Liu <jijiang.liu@intel.com>
---
 app/test-pmd/cmdline.c |  119 ++++++++++++++++++++++++++++++++++++++++++++++-
 1 files changed, 116 insertions(+), 3 deletions(-)

diff --git a/app/test-pmd/cmdline.c b/app/test-pmd/cmdline.c
index 0b972f9..baa968b 100644
--- a/app/test-pmd/cmdline.c
+++ b/app/test-pmd/cmdline.c
@@ -351,9 +351,14 @@ static void cmd_help_long_parsed(void *parsed_result,
 			"    e.g., 'set stat_qmap rx 0 2 5' sets rx queue 2"
 			" on port 0 to mapping 5.\n\n"
 
-			"set port (port_id) vf (vf_id) rx|tx on|off \n"
+			"set port (port_id) vf (vf_id) rx|tx on|off\n"
 			"    Enable/Disable a VF receive/tranmit from a port\n\n"
 
+			"set port (port_id) vf (vf_id) (mac_addr)"
+			" (exact-mac#exact-mac-vlan#hashmac|hashmac-vlan) on|off\n"
+			"   Add/Remove unicast or multicast MAC addr filter"
+			" for a VF.\n\n"
+
 			"set port (port_id) vf (vf_id) rxmode (AUPE|ROPE|BAM"
 			"|MPE) (on|off)\n"
 			"    AUPE:accepts untagged VLAN;"
@@ -5809,6 +5814,112 @@ cmdline_parse_inst_t cmd_set_uc_all_hash_filter = {
 	},
 };
 
+/* *** CONFIGURE MACVLAN FILTER FOR VF(s) *** */
+struct cmd_set_vf_macvlan_filter {
+	cmdline_fixed_string_t set;
+	cmdline_fixed_string_t port;
+	uint8_t port_id;
+	cmdline_fixed_string_t vf;
+	uint8_t vf_id;
+	struct ether_addr address;
+	cmdline_fixed_string_t filter_type;
+	cmdline_fixed_string_t mode;
+};
+
+static void
+cmd_set_vf_macvlan_parsed(void *parsed_result,
+		       __attribute__((unused)) struct cmdline *cl,
+		       __attribute__((unused)) void *data)
+{
+	int is_on, ret = 0;
+	struct cmd_set_vf_macvlan_filter *res = parsed_result;
+	struct rte_eth_mac_filter filter;
+
+	memset(&filter, 0, sizeof(struct rte_eth_mac_filter));
+
+	(void)rte_memcpy(&filter.mac_addr, &res->address, ETHER_ADDR_LEN);
+
+	/* set VF MAC filter */
+	filter.is_vf = 1;
+
+	/* set VF ID */
+	filter.dst_id = res->vf_id;
+
+	if (!strcmp(res->filter_type, "exact-mac"))
+		filter.filter_type = RTE_MAC_PERFECT_MATCH;
+	else if (!strcmp(res->filter_type, "exact-mac-vlan"))
+		filter.filter_type = RTE_MACVLAN_PERFECT_MATCH;
+	else if (!strcmp(res->filter_type, "hashmac"))
+		filter.filter_type = RTE_MAC_HASH_MATCH;
+	else if (!strcmp(res->filter_type, "hashmac-vlan"))
+		filter.filter_type = RTE_MACVLAN_HASH_MATCH;
+
+	is_on = (strcmp(res->mode, "on") == 0) ? 1 : 0;
+
+	if (is_on)
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+					RTE_ETH_FILTER_MACVLAN,
+					RTE_ETH_FILTER_ADD,
+					 &filter);
+	else
+		ret = rte_eth_dev_filter_ctrl(res->port_id,
+					RTE_ETH_FILTER_MACVLAN,
+					RTE_ETH_FILTER_DELETE,
+					&filter);
+
+	if (ret < 0)
+		printf("bad set MAC hash parameter, return code = %d\n", ret);
+
+}
+
+cmdline_parse_token_string_t cmd_set_vf_macvlan_set =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 set, "set");
+cmdline_parse_token_string_t cmd_set_vf_macvlan_port =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 port, "port");
+cmdline_parse_token_num_t cmd_set_vf_macvlan_portid =
+	TOKEN_NUM_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+			      port_id, UINT8);
+cmdline_parse_token_string_t cmd_set_vf_macvlan_vf =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 vf, "vf");
+cmdline_parse_token_num_t cmd_set_vf_macvlan_vf_id =
+	TOKEN_NUM_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				vf_id, UINT8);
+cmdline_parse_token_etheraddr_t cmd_set_vf_macvlan_mac =
+	TOKEN_ETHERADDR_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				address);
+cmdline_parse_token_string_t cmd_set_vf_macvlan_filter_type =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				filter_type, "exact-mac#exact-mac-vlan"
+				"#hashmac#hashmac-vlan");
+cmdline_parse_token_string_t cmd_set_vf_macvlan_mode =
+	TOKEN_STRING_INITIALIZER(struct cmd_set_vf_macvlan_filter,
+				 mode, "on#off");
+
+cmdline_parse_inst_t cmd_set_vf_macvlan_filter = {
+	.f = cmd_set_vf_macvlan_parsed,
+	.data = NULL,
+	.help_str = "set port (portid) vf (vfid) (mac-addr) "
+			"(exact-mac|exact-mac-vlan|hashmac|hashmac-vlan) "
+			"on|off\n"
+			"exact match rule:exact match of MAC or MAC and VLAN; "
+			"hash match rule: hash match of MAC and exact match "
+			"of VLAN",
+	.tokens = {
+		(void *)&cmd_set_vf_macvlan_set,
+		(void *)&cmd_set_vf_macvlan_port,
+		(void *)&cmd_set_vf_macvlan_portid,
+		(void *)&cmd_set_vf_macvlan_vf,
+		(void *)&cmd_set_vf_macvlan_vf_id,
+		(void *)&cmd_set_vf_macvlan_mac,
+		(void *)&cmd_set_vf_macvlan_filter_type,
+		(void *)&cmd_set_vf_macvlan_mode,
+		NULL,
+	},
+};
+
 /* *** CONFIGURE VF TRAFFIC CONTROL *** */
 struct cmd_set_vf_traffic {
 	cmdline_fixed_string_t set;
@@ -5857,7 +5968,8 @@ cmdline_parse_token_string_t cmd_setvf_traffic_mode =
 cmdline_parse_inst_t cmd_set_vf_traffic = {
 	.f = cmd_set_vf_traffic_parsed,
 	.data = NULL,
-	.help_str = "set port X vf Y rx|tx on|off (X = port number,Y = vf id)",
+	.help_str = "set port X vf Y rx|tx on|off"
+			"(X = port number,Y = vf id)",
 	.tokens = {
 		(void *)&cmd_setvf_traffic_set,
 		(void *)&cmd_setvf_traffic_port,
@@ -7513,7 +7625,8 @@ cmdline_parse_ctx_t main_ctx[] = {
 	(cmdline_parse_inst_t *)&cmd_set_vf_rxmode,
 	(cmdline_parse_inst_t *)&cmd_set_uc_hash_filter,
 	(cmdline_parse_inst_t *)&cmd_set_uc_all_hash_filter,
-	(cmdline_parse_inst_t *)&cmd_vf_mac_addr_filter ,
+	(cmdline_parse_inst_t *)&cmd_vf_mac_addr_filter,
+	(cmdline_parse_inst_t *)&cmd_set_vf_macvlan_filter,
 	(cmdline_parse_inst_t *)&cmd_set_vf_traffic,
 	(cmdline_parse_inst_t *)&cmd_vf_rxvlan_filter,
 	(cmdline_parse_inst_t *)&cmd_queue_rate_limit,
-- 
1.7.7.6

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

* Re: [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville
  2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
                     ` (3 preceding siblings ...)
  2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 4/4] app/testpmd:test " Jijiang Liu
@ 2014-10-30 22:35   ` Thomas Monjalon
  4 siblings, 0 replies; 14+ messages in thread
From: Thomas Monjalon @ 2014-10-30 22:35 UTC (permalink / raw)
  To: Jijiang Liu; +Cc: dev

2014-10-24 15:58, Jijiang Liu:
> The patch set enhances configurability of MAC filter and supports VF MAC filter on Fortville.
>  
> It mainly includes:
>  - The following filter type are configurable:
>    1. Perfect match of MAC address
>    2. Perfect match of MAC address and VLAN ID
>    3. Hash match of MAC address
>    4. Hash match of MAC address and perfect match of VLAN ID
>  - Support perfect and hash match of unicast and multicast MAC address for VF for i40e
> 
>  v2 updates:
>   * Integrate the v1 patch set into the new filter framework.
>   * Optimize MAC filter data structures in rte_eth_ctrl.h file.
>  
> jijiangl (4):
>   Expand data structures of MAC filter in rte_eth_ctrl.h file.
>   Expand MAC filter implemantation in i40e. 
>   Support VF MAC filter in i40e.
>   Test VF MAC filter in testpmd 

Applied

Thanks
-- 
Thomas

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

* Re: [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville
  2014-09-25  8:17 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF " Liu, Yong
@ 2014-10-13  2:28 ` Liu, Jijiang
  0 siblings, 0 replies; 14+ messages in thread
From: Liu, Jijiang @ 2014-10-13  2:28 UTC (permalink / raw)
  To: thomas.monjalon; +Cc: dev

Hi Thomas,

Any comments on this patch set?

Thanks
Jijiang Liu

> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Liu, Yong
> Sent: Thursday, September 25, 2014 4:18 PM
> To: dev@dpdk.org
> Subject: Re: [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC
> address for VF on Fortville
> 
> Tested-by: Liu Yong <yong.liu at intel.com>
> 
> This patch set has been tested by Intel.
> Please see information as the following:
> 
> Host:
> 	OS           : Fedora 20 x86_64
> 	Kernel   : 3.11.10-301
> 	GCC        : 4.8.3
> 	CPU        : Intel Xeon CPU E5-2680 v2 @ 2.80GHz
> 	NIC         : 2*40G (8086:1583)
> 	Qemu    : 1.6.2
> 	libvirt     : 1.1.3
> Guest:
> 	OS          : Fedora 20 x86_64
> 	Kernel   : 3.11.10-301
> 	GCC       : 4.8.3
> 
> We verified perfect and hash match filter of unicast and multicast MAC address
> for VF work normally on FVL.
> 
> > -----Original Message-----
> > From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jijiang Liu
> > Sent: Tuesday, September 23, 2014 11:30 AM
> > To: dev@dpdk.org
> > Subject: [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast
> > MAC address for VF on Fortville
> >
> > The patch set enhances MACVLAN filter configurability and supports
> > perfect and hash match filter of unicast and multicast MAC address for
> > VF on Fortville.
> >
> > It mainly includes:
> >  - Use new filter mechanism discussed at
> > http://dpdk.org/ml/archives/dev/2014-September/005179.html.
> >  - Enhance MACVLAN filter to be configurable. Now the following
> > options are
> > configurable:
> >    1. Perfect match of MAC address
> >    2. Perfect match of MAC address and VLAN ID
> >    3. Hash match of MAC address
> >    4. Hash match of MAC address and perfect match of VLAN ID
> >    5. To Queue: use MAC and VLAN to point to a queue
> >  - Support perfect and hash match of unicast and multicast MAC address
> > for VF for i40e
> >
> >
> > jijiangl (5):
> >   Use new filter framework
> >   Add new definations for MACVLAN filter enhancement in rte_eth_ctrl.h
> file
> >   Change parameters of MAC/VLAN filter to be configurable
> >   Add VF MACVLAN filter handle for i40e
> >   Test VF MACVLAN filter for i40e
> >
> >  app/test-pmd/cmdline.c            |  115 +++++++++++++-
> >  lib/librte_ether/Makefile         |    1 +
> >  lib/librte_ether/rte_eth_ctrl.h   |  104 ++++++++++++
> >  lib/librte_ether/rte_ethdev.c     |   33 ++++
> >  lib/librte_ether/rte_ethdev.h     |   48 ++++++-
> >  lib/librte_pmd_i40e/i40e_ethdev.c |  321
> > ++++++++++++++++++++++++++++++++-----
> >  lib/librte_pmd_i40e/i40e_ethdev.h |   18 ++-
> >  lib/librte_pmd_i40e/i40e_pf.c     |    7 +-
> >  8 files changed, 601 insertions(+), 46 deletions(-)  create mode
> > 100644 lib/librte_ether/rte_eth_ctrl.h
> >
> > --
> > 1.7.7.6

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

* Re: [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville
@ 2014-09-25  8:17 Liu, Yong
  2014-10-13  2:28 ` Liu, Jijiang
  0 siblings, 1 reply; 14+ messages in thread
From: Liu, Yong @ 2014-09-25  8:17 UTC (permalink / raw)
  To: dev

Tested-by: Liu Yong <yong.liu at intel.com>

This patch set has been tested by Intel.
Please see information as the following:

Host:
	OS           : Fedora 20 x86_64
	Kernel   : 3.11.10-301
	GCC        : 4.8.3
	CPU        : Intel Xeon CPU E5-2680 v2 @ 2.80GHz
	NIC         : 2*40G (8086:1583)
	Qemu    : 1.6.2
	libvirt     : 1.1.3
Guest:
	OS          : Fedora 20 x86_64
	Kernel   : 3.11.10-301
	GCC       : 4.8.3

We verified perfect and hash match filter of unicast and multicast MAC address for VF work normally on FVL.

> -----Original Message-----
> From: dev [mailto:dev-bounces@dpdk.org] On Behalf Of Jijiang Liu
> Sent: Tuesday, September 23, 2014 11:30 AM
> To: dev@dpdk.org
> Subject: [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC
> address for VF on Fortville
> 
> The patch set enhances MACVLAN filter configurability and supports perfect
> and hash match filter of unicast
> and multicast MAC address for VF on Fortville.
> 
> It mainly includes:
>  - Use new filter mechanism discussed at
> http://dpdk.org/ml/archives/dev/2014-September/005179.html.
>  - Enhance MACVLAN filter to be configurable. Now the following options are
> configurable:
>    1. Perfect match of MAC address
>    2. Perfect match of MAC address and VLAN ID
>    3. Hash match of MAC address
>    4. Hash match of MAC address and perfect match of VLAN ID
>    5. To Queue: use MAC and VLAN to point to a queue
>  - Support perfect and hash match of unicast and multicast MAC address for
> VF for i40e
> 
> 
> jijiangl (5):
>   Use new filter framework
>   Add new definations for MACVLAN filter enhancement in rte_eth_ctrl.h file
>   Change parameters of MAC/VLAN filter to be configurable
>   Add VF MACVLAN filter handle for i40e
>   Test VF MACVLAN filter for i40e
> 
>  app/test-pmd/cmdline.c            |  115 +++++++++++++-
>  lib/librte_ether/Makefile         |    1 +
>  lib/librte_ether/rte_eth_ctrl.h   |  104 ++++++++++++
>  lib/librte_ether/rte_ethdev.c     |   33 ++++
>  lib/librte_ether/rte_ethdev.h     |   48 ++++++-
>  lib/librte_pmd_i40e/i40e_ethdev.c |  321
> ++++++++++++++++++++++++++++++++-----
>  lib/librte_pmd_i40e/i40e_ethdev.h |   18 ++-
>  lib/librte_pmd_i40e/i40e_pf.c     |    7 +-
>  8 files changed, 601 insertions(+), 46 deletions(-)
>  create mode 100644 lib/librte_ether/rte_eth_ctrl.h
> 
> --
> 1.7.7.6

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

end of thread, other threads:[~2014-10-30 22:26 UTC | newest]

Thread overview: 14+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2014-09-23  3:29 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF on Fortville Jijiang Liu
2014-09-23  3:29 ` [dpdk-dev] [PATCH 1/5]librte_ether:use new filter framework Jijiang Liu
2014-09-23  3:29 ` [dpdk-dev] [PATCH 2/5]librte_ether:extend data structures of MACVLAN filter Jijiang Liu
2014-09-23  3:29 ` [dpdk-dev] [PATCH 3/5]i40e:optimize MACVLAN filter implementation Jijiang Liu
2014-09-23  3:29 ` [dpdk-dev] [PATCH 4/5]i40e:add VF MACVLAN filter implementation in librte_pmd_i40e Jijiang Liu
2014-09-23  3:29 ` [dpdk-dev] [PATCH 5/5]testpmd:test VF MACVLAN filter for i40e Jijiang Liu
2014-10-24  7:58 ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Jijiang Liu
2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 1/4] librte_ether:extend MAC filter data structures Jijiang Liu
2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 2/4] i40e:expand MAC filter implemantation in i40e Jijiang Liu
2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 3/4] i40e:add VF MAC filter Jijiang Liu
2014-10-24  7:58   ` [dpdk-dev] [PATCH v2 4/4] app/testpmd:test " Jijiang Liu
2014-10-30 22:35   ` [dpdk-dev] [PATCH v2 0/4] support VF MAC filter on Fortville Thomas Monjalon
2014-09-25  8:17 [dpdk-dev] [PATCH 0/5]support filter of unicast and multicast MAC address for VF " Liu, Yong
2014-10-13  2:28 ` Liu, Jijiang

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