DPDK patches and discussions
 help / color / mirror / Atom feed
* [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API
@ 2018-08-27 12:52 Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 1/4] net/cxgbe: add API to program hardware layer 2 table Rahul Lakkireddy
                   ` (4 more replies)
  0 siblings, 5 replies; 6+ messages in thread
From: Rahul Lakkireddy @ 2018-08-27 12:52 UTC (permalink / raw)
  To: dev; +Cc: shaguna, indranil, nirranjan

This series of patches add support to offload flows with destination MAC
match item and VLAN push/pop/rewrite actions.

Patch 1 adds API to program and manage hardware Layer 2 Table (L2T).
L2T holds destination node information to be used for VLAN rewrite.

Patch 2 implements offloading VLAN push/pop/rewrite actions.

Patch 3 adds API to program and manage hardware Multi Port Switch (MPS)
table. MPS holds the destination MAC addresses to be matched against
incoming packets.

Patch 4 implements offloading destination MAC match item.

Thanks,
Rahul

Shagun Agrawal (4):
  net/cxgbe: add API to program hardware layer 2 table
  net/cxgbe: add flow operations to offload vlan actions
  net/cxgbe: add API to program hardware MPS table
  net/cxgbe: add flow operations to match based on destination MAC
    address

 doc/guides/rel_notes/release_18_11.rst  |   7 +
 drivers/net/cxgbe/Makefile              |   2 +
 drivers/net/cxgbe/base/adapter.h        |   4 +
 drivers/net/cxgbe/base/common.h         |   7 +
 drivers/net/cxgbe/base/t4_hw.c          | 108 ++++++++++++++
 drivers/net/cxgbe/base/t4_msg.h         |  40 ++++++
 drivers/net/cxgbe/base/t4_regs.h        |   8 ++
 drivers/net/cxgbe/base/t4_tcb.h         |   5 +
 drivers/net/cxgbe/base/t4fw_interface.h |  26 ++++
 drivers/net/cxgbe/cxgbe_ethdev.c        |   4 +-
 drivers/net/cxgbe/cxgbe_filter.c        |  71 +++++++++-
 drivers/net/cxgbe/cxgbe_filter.h        |  11 ++
 drivers/net/cxgbe/cxgbe_flow.c          |  90 +++++++++++-
 drivers/net/cxgbe/cxgbe_flow.h          |   1 +
 drivers/net/cxgbe/cxgbe_main.c          |  43 ++++--
 drivers/net/cxgbe/l2t.c                 | 227 +++++++++++++++++++++++++++++
 drivers/net/cxgbe/l2t.h                 |  57 ++++++++
 drivers/net/cxgbe/meson.build           |   2 +
 drivers/net/cxgbe/mps_tcam.c            | 243 ++++++++++++++++++++++++++++++++
 drivers/net/cxgbe/mps_tcam.h            |  52 +++++++
 20 files changed, 987 insertions(+), 21 deletions(-)
 create mode 100644 drivers/net/cxgbe/l2t.c
 create mode 100644 drivers/net/cxgbe/l2t.h
 create mode 100644 drivers/net/cxgbe/mps_tcam.c
 create mode 100644 drivers/net/cxgbe/mps_tcam.h

-- 
2.14.1

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

* [dpdk-dev] [PATCH 1/4] net/cxgbe: add API to program hardware layer 2 table
  2018-08-27 12:52 [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Rahul Lakkireddy
@ 2018-08-27 12:52 ` Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 2/4] net/cxgbe: add flow operations to offload vlan actions Rahul Lakkireddy
                   ` (3 subsequent siblings)
  4 siblings, 0 replies; 6+ messages in thread
From: Rahul Lakkireddy @ 2018-08-27 12:52 UTC (permalink / raw)
  To: dev; +Cc: shaguna, indranil, nirranjan

From: Shagun Agrawal <shaguna@chelsio.com>

Add API to program and manage hardware Layer 2 Table. L2T holds
information necessary to rewrite specific fields in packet, such
as destination MAC address and vlan id.

Signed-off-by: Shagun Agrawal <shaguna@chelsio.com>
Signed-off-by: Rahul Lakkireddy <rahul.lakkireddy@chelsio.com>
---
 drivers/net/cxgbe/Makefile              |   1 +
 drivers/net/cxgbe/base/adapter.h        |   3 +
 drivers/net/cxgbe/base/t4_msg.h         |  34 +++++
 drivers/net/cxgbe/base/t4fw_interface.h |   2 +
 drivers/net/cxgbe/cxgbe_filter.h        |   1 +
 drivers/net/cxgbe/cxgbe_main.c          |  30 ++++-
 drivers/net/cxgbe/l2t.c                 | 227 ++++++++++++++++++++++++++++++++
 drivers/net/cxgbe/l2t.h                 |  57 ++++++++
 drivers/net/cxgbe/meson.build           |   1 +
 9 files changed, 349 insertions(+), 7 deletions(-)
 create mode 100644 drivers/net/cxgbe/l2t.c
 create mode 100644 drivers/net/cxgbe/l2t.h

diff --git a/drivers/net/cxgbe/Makefile b/drivers/net/cxgbe/Makefile
index 5d66c4b3a..d75b070f3 100644
--- a/drivers/net/cxgbe/Makefile
+++ b/drivers/net/cxgbe/Makefile
@@ -53,6 +53,7 @@ SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += cxgbe_filter.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += cxgbe_flow.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += t4_hw.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += clip_tbl.c
+SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += l2t.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += t4vf_hw.c
 
 include $(RTE_SDK)/mk/rte.lib.mk
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index e98dd2182..9f4a9653c 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -324,7 +324,10 @@ struct adapter {
 
 	unsigned int clipt_start; /* CLIP table start */
 	unsigned int clipt_end;   /* CLIP table end */
+	unsigned int l2t_start;   /* Layer 2 table start */
+	unsigned int l2t_end;     /* Layer 2 table end */
 	struct clip_tbl *clipt;   /* CLIP table */
+	struct l2t_data *l2t;     /* Layer 2 table */
 
 	struct tid_info tids;     /* Info used to access TID related tables */
 };
diff --git a/drivers/net/cxgbe/base/t4_msg.h b/drivers/net/cxgbe/base/t4_msg.h
index 5d433c91c..094a153f2 100644
--- a/drivers/net/cxgbe/base/t4_msg.h
+++ b/drivers/net/cxgbe/base/t4_msg.h
@@ -11,7 +11,9 @@ enum {
 	CPL_SET_TCB_FIELD     = 0x5,
 	CPL_ABORT_REQ         = 0xA,
 	CPL_ABORT_RPL         = 0xB,
+	CPL_L2T_WRITE_REQ     = 0x12,
 	CPL_TID_RELEASE       = 0x1A,
+	CPL_L2T_WRITE_RPL     = 0x23,
 	CPL_ACT_OPEN_RPL      = 0x25,
 	CPL_ABORT_RPL_RSS     = 0x2D,
 	CPL_SET_TCB_RPL       = 0x3A,
@@ -66,6 +68,9 @@ union opcode_tid {
 #define M_TID_TID    0x3fff
 #define G_TID_TID(x) (((x) >> S_TID_TID) & M_TID_TID)
 
+#define S_TID_QID    14
+#define V_TID_QID(x) ((x) << S_TID_QID)
+
 struct rss_header {
 	__u8 opcode;
 #if RTE_BYTE_ORDER == RTE_LITTLE_ENDIAN
@@ -421,6 +426,35 @@ struct cpl_rx_pkt {
 	__be16 err_vec;
 };
 
+struct cpl_l2t_write_req {
+	WR_HDR;
+	union opcode_tid ot;
+	__be16 params;
+	__be16 l2t_idx;
+	__be16 vlan;
+	__u8   dst_mac[6];
+};
+
+/* cpl_l2t_write_req.params fields */
+#define S_L2T_W_PORT    8
+#define V_L2T_W_PORT(x) ((x) << S_L2T_W_PORT)
+
+#define S_L2T_W_LPBK    10
+#define V_L2T_W_LPBK(x) ((x) << S_L2T_W_LPBK)
+
+#define S_L2T_W_ARPMISS         11
+#define V_L2T_W_ARPMISS(x)      ((x) << S_L2T_W_ARPMISS)
+
+#define S_L2T_W_NOREPLY    15
+#define V_L2T_W_NOREPLY(x) ((x) << S_L2T_W_NOREPLY)
+
+struct cpl_l2t_write_rpl {
+	RSS_HDR
+	union opcode_tid ot;
+	__u8 status;
+	__u8 rsvd[3];
+};
+
 /* rx_pkt.l2info fields */
 #define S_RXF_UDP    22
 #define V_RXF_UDP(x) ((x) << S_RXF_UDP)
diff --git a/drivers/net/cxgbe/base/t4fw_interface.h b/drivers/net/cxgbe/base/t4fw_interface.h
index e80b58a32..1c08637bb 100644
--- a/drivers/net/cxgbe/base/t4fw_interface.h
+++ b/drivers/net/cxgbe/base/t4fw_interface.h
@@ -665,6 +665,8 @@ enum fw_params_param_pfvf {
 	FW_PARAMS_PARAM_PFVF_CLIP_END = 0x04,
 	FW_PARAMS_PARAM_PFVF_FILTER_START = 0x05,
 	FW_PARAMS_PARAM_PFVF_FILTER_END = 0x06,
+	FW_PARAMS_PARAM_PFVF_L2T_START = 0x13,
+	FW_PARAMS_PARAM_PFVF_L2T_END = 0x14,
 	FW_PARAMS_PARAM_PFVF_CPLFW4MSG_ENCAP = 0x31,
 	FW_PARAMS_PARAM_PFVF_PORT_CAPS32 = 0x3A
 };
diff --git a/drivers/net/cxgbe/cxgbe_filter.h b/drivers/net/cxgbe/cxgbe_filter.h
index af8fa7529..be12e231a 100644
--- a/drivers/net/cxgbe/cxgbe_filter.h
+++ b/drivers/net/cxgbe/cxgbe_filter.h
@@ -145,6 +145,7 @@ struct filter_entry {
 	u32 pending:1;              /* filter action is pending FW reply */
 	struct filter_ctx *ctx;     /* caller's completion hook */
 	struct clip_entry *clipt;   /* CLIP Table entry for IPv6 */
+	struct l2t_entry *l2t;      /* Layer Two Table entry for dmac */
 	struct rte_eth_dev *dev;    /* Port's rte eth device */
 	void *private;              /* For use by apps using filter_entry */
 
diff --git a/drivers/net/cxgbe/cxgbe_main.c b/drivers/net/cxgbe/cxgbe_main.c
index c3938e8db..be2bc4213 100644
--- a/drivers/net/cxgbe/cxgbe_main.c
+++ b/drivers/net/cxgbe/cxgbe_main.c
@@ -38,6 +38,7 @@
 #include "t4_msg.h"
 #include "cxgbe.h"
 #include "clip_tbl.h"
+#include "l2t.h"
 
 /**
  * Allocate a chunk of memory. The allocated memory is cleared.
@@ -99,6 +100,10 @@ static int fwevtq_handler(struct sge_rspq *q, const __be64 *rsp,
 		const struct cpl_act_open_rpl *p = (const void *)rsp;
 
 		hash_filter_rpl(q->adapter, p);
+	} else if (opcode == CPL_L2T_WRITE_RPL) {
+		const struct cpl_l2t_write_rpl *p = (const void *)rsp;
+
+		do_l2t_write_rpl(q->adapter, p);
 	} else {
 		dev_err(adapter, "unexpected CPL %#x on FW event queue\n",
 			opcode);
@@ -1135,13 +1140,17 @@ static int adap_init0(struct adapter *adap)
 	 V_FW_PARAMS_PARAM_Y(0) | \
 	 V_FW_PARAMS_PARAM_Z(0))
 
-	params[0] = FW_PARAM_PFVF(FILTER_START);
-	params[1] = FW_PARAM_PFVF(FILTER_END);
-	ret = t4_query_params(adap, adap->mbox, adap->pf, 0, 2, params, val);
+	params[0] = FW_PARAM_PFVF(L2T_START);
+	params[1] = FW_PARAM_PFVF(L2T_END);
+	params[2] = FW_PARAM_PFVF(FILTER_START);
+	params[3] = FW_PARAM_PFVF(FILTER_END);
+	ret = t4_query_params(adap, adap->mbox, adap->pf, 0, 4, params, val);
 	if (ret < 0)
 		goto bye;
-	adap->tids.ftid_base = val[0];
-	adap->tids.nftids = val[1] - val[0] + 1;
+	adap->l2t_start = val[0];
+	adap->l2t_end = val[1];
+	adap->tids.ftid_base = val[2];
+	adap->tids.nftids = val[3] - val[2] + 1;
 
 	params[0] = FW_PARAM_PFVF(CLIP_START);
 	params[1] = FW_PARAM_PFVF(CLIP_END);
@@ -1679,10 +1688,11 @@ void cxgbe_close(struct adapter *adapter)
 	int i;
 
 	if (adapter->flags & FULL_INIT_DONE) {
-		if (is_pf4(adapter))
-			t4_intr_disable(adapter);
 		tid_free(&adapter->tids);
 		t4_cleanup_clip_tbl(adapter);
+		t4_cleanup_l2t(adapter);
+		if (is_pf4(adapter))
+			t4_intr_disable(adapter);
 		t4_sge_tx_monitor_stop(adapter);
 		t4_free_sge_resources(adapter);
 		for_each_port(adapter, i) {
@@ -1855,6 +1865,12 @@ int cxgbe_probe(struct adapter *adapter)
 		dev_warn(adapter, "could not allocate CLIP. Continuing\n");
 	}
 
+	adapter->l2t = t4_init_l2t(adapter->l2t_start, adapter->l2t_end);
+	if (!adapter->l2t) {
+		/* We tolerate a lack of L2T, giving up some functionality */
+		dev_warn(adapter, "could not allocate L2T. Continuing\n");
+	}
+
 	if (tid_init(&adapter->tids) < 0) {
 		/* Disable filtering support */
 		dev_warn(adapter, "could not allocate TID table, "
diff --git a/drivers/net/cxgbe/l2t.c b/drivers/net/cxgbe/l2t.c
new file mode 100644
index 000000000..814188fea
--- /dev/null
+++ b/drivers/net/cxgbe/l2t.c
@@ -0,0 +1,227 @@
+/* SPDX-License-Identifier: BSD-3-Clause
+ * Copyright(c) 2018 Chelsio Communications.
+ * All rights reserved.
+ */
+#include "common.h"
+#include "l2t.h"
+
+/**
+ * cxgbe_l2t_release - Release associated L2T entry
+ * @e: L2T entry to release
+ *
+ * Releases ref count and frees up an L2T entry from L2T table
+ */
+void cxgbe_l2t_release(struct l2t_entry *e)
+{
+	if (rte_atomic32_read(&e->refcnt) != 0)
+		rte_atomic32_dec(&e->refcnt);
+}
+
+/**
+ * Process a CPL_L2T_WRITE_RPL. Note that the TID in the reply is really
+ * the L2T index it refers to.
+ */
+void do_l2t_write_rpl(struct adapter *adap, const struct cpl_l2t_write_rpl *rpl)
+{
+	struct l2t_data *d = adap->l2t;
+	unsigned int tid = GET_TID(rpl);
+	unsigned int l2t_idx = tid % L2T_SIZE;
+
+	if (unlikely(rpl->status != CPL_ERR_NONE)) {
+		dev_err(adap,
+			"Unexpected L2T_WRITE_RPL status %u for entry %u\n",
+			rpl->status, l2t_idx);
+		return;
+	}
+
+	if (tid & F_SYNC_WR) {
+		struct l2t_entry *e = &d->l2tab[l2t_idx - d->l2t_start];
+
+		t4_os_lock(&e->lock);
+		if (e->state != L2T_STATE_SWITCHING)
+			e->state = L2T_STATE_VALID;
+		t4_os_unlock(&e->lock);
+	}
+}
+
+/**
+ * Write an L2T entry.  Must be called with the entry locked.
+ * The write may be synchronous or asynchronous.
+ */
+static int write_l2e(struct rte_eth_dev *dev, struct l2t_entry *e, int sync,
+		     bool loopback, bool arpmiss)
+{
+	struct adapter *adap = ethdev2adap(dev);
+	struct l2t_data *d = adap->l2t;
+	struct rte_mbuf *mbuf;
+	struct cpl_l2t_write_req *req;
+	struct sge_ctrl_txq *ctrlq;
+	unsigned int l2t_idx = e->idx + d->l2t_start;
+	unsigned int port_id = ethdev2pinfo(dev)->port_id;
+
+	ctrlq = &adap->sge.ctrlq[port_id];
+	mbuf = rte_pktmbuf_alloc(ctrlq->mb_pool);
+	if (!mbuf)
+		return -ENOMEM;
+
+	mbuf->data_len = sizeof(*req);
+	mbuf->pkt_len = mbuf->data_len;
+
+	req = rte_pktmbuf_mtod(mbuf, struct cpl_l2t_write_req *);
+	INIT_TP_WR(req, 0);
+
+	OPCODE_TID(req) =
+		cpu_to_be32(MK_OPCODE_TID(CPL_L2T_WRITE_REQ,
+					  l2t_idx | V_SYNC_WR(sync) |
+					  V_TID_QID(adap->sge.fw_evtq.abs_id)));
+	req->params = cpu_to_be16(V_L2T_W_PORT(e->lport) |
+				  V_L2T_W_LPBK(loopback) |
+				  V_L2T_W_ARPMISS(arpmiss) |
+				  V_L2T_W_NOREPLY(!sync));
+	req->l2t_idx = cpu_to_be16(l2t_idx);
+	req->vlan = cpu_to_be16(e->vlan);
+	rte_memcpy(req->dst_mac, e->dmac, ETHER_ADDR_LEN);
+
+	if (loopback)
+		memset(req->dst_mac, 0, ETHER_ADDR_LEN);
+
+	t4_mgmt_tx(ctrlq, mbuf);
+
+	if (sync && e->state != L2T_STATE_SWITCHING)
+		e->state = L2T_STATE_SYNC_WRITE;
+
+	return 0;
+}
+
+/**
+ * find_or_alloc_l2e - Find/Allocate a free L2T entry
+ * @d: L2T table
+ * @vlan: VLAN id to compare/add
+ * @port: port id to compare/add
+ * @dmac: Destination MAC address to compare/add
+ * Returns pointer to the L2T entry found/created
+ *
+ * Finds/Allocates an L2T entry to be used by switching rule of a filter.
+ */
+static struct l2t_entry *find_or_alloc_l2e(struct l2t_data *d, u16 vlan,
+					   u8 port, u8 *dmac)
+{
+	struct l2t_entry *end, *e;
+	struct l2t_entry *first_free = NULL;
+
+	for (e = &d->l2tab[0], end = &d->l2tab[d->l2t_size]; e != end; ++e) {
+		if (rte_atomic32_read(&e->refcnt) == 0) {
+			if (!first_free)
+				first_free = e;
+		} else {
+			if (e->state == L2T_STATE_SWITCHING) {
+				if ((!memcmp(e->dmac, dmac, ETHER_ADDR_LEN)) &&
+				    e->vlan == vlan && e->lport == port)
+					goto exists;
+			}
+		}
+	}
+
+	if (first_free) {
+		e = first_free;
+		goto found;
+	}
+
+	return NULL;
+
+found:
+	e->state = L2T_STATE_UNUSED;
+
+exists:
+	return e;
+}
+
+static struct l2t_entry *t4_l2t_alloc_switching(struct rte_eth_dev *dev,
+						u16 vlan, u8 port,
+						u8 *eth_addr)
+{
+	struct adapter *adap = ethdev2adap(dev);
+	struct l2t_data *d = adap->l2t;
+	struct l2t_entry *e;
+	int ret = 0;
+
+	t4_os_write_lock(&d->lock);
+	e = find_or_alloc_l2e(d, vlan, port, eth_addr);
+	if (e) {
+		t4_os_lock(&e->lock);
+		if (!rte_atomic32_read(&e->refcnt)) {
+			e->state = L2T_STATE_SWITCHING;
+			e->vlan = vlan;
+			e->lport = port;
+			rte_memcpy(e->dmac, eth_addr, ETHER_ADDR_LEN);
+			rte_atomic32_set(&e->refcnt, 1);
+			ret = write_l2e(dev, e, 0, !L2T_LPBK, !L2T_ARPMISS);
+			if (ret < 0)
+				dev_debug(adap, "Failed to write L2T entry: %d",
+					  ret);
+		} else {
+			rte_atomic32_inc(&e->refcnt);
+		}
+		t4_os_unlock(&e->lock);
+	}
+	t4_os_write_unlock(&d->lock);
+
+	return ret ? NULL : e;
+}
+
+/**
+ * cxgbe_l2t_alloc_switching - Allocate a L2T entry for switching rule
+ * @dev: rte_eth_dev pointer
+ * @vlan: VLAN Id
+ * @port: Associated port
+ * @dmac: Destination MAC address to add to L2T
+ * Returns pointer to the allocated l2t entry
+ *
+ * Allocates a L2T entry for use by switching rule of a filter
+ */
+struct l2t_entry *cxgbe_l2t_alloc_switching(struct rte_eth_dev *dev, u16 vlan,
+					    u8 port, u8 *dmac)
+{
+	return t4_l2t_alloc_switching(dev, vlan, port, dmac);
+}
+
+/**
+ * Initialize L2 Table
+ */
+struct l2t_data *t4_init_l2t(unsigned int l2t_start, unsigned int l2t_end)
+{
+	unsigned int l2t_size;
+	unsigned int i;
+	struct l2t_data *d;
+
+	if (l2t_start >= l2t_end || l2t_end >= L2T_SIZE)
+		return NULL;
+	l2t_size = l2t_end - l2t_start + 1;
+
+	d = t4_os_alloc(sizeof(*d) + l2t_size * sizeof(struct l2t_entry));
+	if (!d)
+		return NULL;
+
+	d->l2t_start = l2t_start;
+	d->l2t_size = l2t_size;
+
+	t4_os_rwlock_init(&d->lock);
+
+	for (i = 0; i < d->l2t_size; ++i) {
+		d->l2tab[i].idx = i;
+		d->l2tab[i].state = L2T_STATE_UNUSED;
+		t4_os_lock_init(&d->l2tab[i].lock);
+		rte_atomic32_set(&d->l2tab[i].refcnt, 0);
+	}
+
+	return d;
+}
+
+/**
+ * Cleanup L2 Table
+ */
+void t4_cleanup_l2t(struct adapter *adap)
+{
+	if (adap->l2t)
+		t4_os_free(adap->l2t);
+}
diff --git a/drivers/net/cxgbe/l2t.h b/drivers/net/cxgbe/l2t.h
new file mode 100644
index 000000000..22a34e388
--- /dev/null
+++ b/drivers/net/cxgbe/l2t.h
@@ -0,0 +1,57 @@
+/* SPDX-License-Identifier: BSD-3-Clause
+ * Copyright(c) 2018 Chelsio Communications.
+ * All rights reserved.
+ */
+#ifndef _CXGBE_L2T_H_
+#define _CXGBE_L2T_H_
+
+#include "t4_msg.h"
+
+enum {
+	L2T_SIZE = 4096       /* # of L2T entries */
+};
+
+enum {
+	L2T_STATE_VALID,      /* entry is up to date */
+	L2T_STATE_SYNC_WRITE, /* synchronous write of entry underway */
+
+	/* when state is one of the below the entry is not hashed */
+	L2T_STATE_SWITCHING,  /* entry is being used by a switching filter */
+	L2T_STATE_UNUSED      /* entry not in use */
+};
+
+/*
+ * State for the corresponding entry of the HW L2 table.
+ */
+struct l2t_entry {
+	u16 state;                  /* entry state */
+	u16 idx;                    /* entry index within in-memory table */
+	u16 vlan;                   /* VLAN TCI (id: bits 0-11, prio: 13-15 */
+	u8  lport;                  /* destination port */
+	u8  dmac[ETHER_ADDR_LEN];   /* destination MAC address */
+	rte_spinlock_t lock;        /* entry lock */
+	rte_atomic32_t refcnt;      /* entry reference count */
+};
+
+struct l2t_data {
+	unsigned int l2t_start;     /* start index of our piece of the L2T */
+	unsigned int l2t_size;      /* number of entries in l2tab */
+	rte_rwlock_t lock;          /* table rw lock */
+	struct l2t_entry l2tab[0];  /* MUST BE LAST */
+};
+
+#define L2T_LPBK	true
+#define L2T_ARPMISS	true
+
+/* identifies sync vs async L2T_WRITE_REQs */
+#define S_SYNC_WR    12
+#define V_SYNC_WR(x) ((x) << S_SYNC_WR)
+#define F_SYNC_WR    V_SYNC_WR(1)
+
+struct l2t_data *t4_init_l2t(unsigned int l2t_start, unsigned int l2t_end);
+void t4_cleanup_l2t(struct adapter *adap);
+struct l2t_entry *cxgbe_l2t_alloc_switching(struct rte_eth_dev *dev, u16 vlan,
+					    u8 port, u8 *dmac);
+void cxgbe_l2t_release(struct l2t_entry *e);
+void do_l2t_write_rpl(struct adapter *p, const struct cpl_l2t_write_rpl *rpl);
+#endif /* _CXGBE_L2T_H_ */
diff --git a/drivers/net/cxgbe/meson.build b/drivers/net/cxgbe/meson.build
index 7c69a34b1..f6a442cb8 100644
--- a/drivers/net/cxgbe/meson.build
+++ b/drivers/net/cxgbe/meson.build
@@ -9,6 +9,7 @@ sources = files('cxgbe_ethdev.c',
 	'cxgbe_filter.c',
 	'cxgbe_flow.c',
 	'clip_tbl.c',
+	'l2t.c',
 	'base/t4_hw.c',
 	'base/t4vf_hw.c')
 includes += include_directories('base')
-- 
2.14.1

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

* [dpdk-dev] [PATCH 2/4] net/cxgbe: add flow operations to offload vlan actions
  2018-08-27 12:52 [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 1/4] net/cxgbe: add API to program hardware layer 2 table Rahul Lakkireddy
@ 2018-08-27 12:52 ` Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 3/4] net/cxgbe: add API to program hardware MPS table Rahul Lakkireddy
                   ` (2 subsequent siblings)
  4 siblings, 0 replies; 6+ messages in thread
From: Rahul Lakkireddy @ 2018-08-27 12:52 UTC (permalink / raw)
  To: dev; +Cc: shaguna, indranil, nirranjan

From: Shagun Agrawal <shaguna@chelsio.com>

Add flow API operations to offload vlan push, pop, and rewrite actions.
For vlan push or rewrite actions, allocate and program an entry from
L2T table. Use the L2T index to program vlan actions for LETCAM
(maskfull) and HASH (maskless) filters.

Signed-off-by: Shagun Agrawal <shaguna@chelsio.com>
Signed-off-by: Rahul Lakkireddy <rahul.lakkireddy@chelsio.com>
---
 doc/guides/rel_notes/release_18_11.rst |  6 ++++
 drivers/net/cxgbe/base/t4_msg.h        |  6 ++++
 drivers/net/cxgbe/base/t4_tcb.h        |  5 +++
 drivers/net/cxgbe/cxgbe_filter.c       | 62 ++++++++++++++++++++++++++++++++--
 drivers/net/cxgbe/cxgbe_filter.h       |  9 +++++
 drivers/net/cxgbe/cxgbe_flow.c         | 24 +++++++++++++
 6 files changed, 109 insertions(+), 3 deletions(-)

diff --git a/doc/guides/rel_notes/release_18_11.rst b/doc/guides/rel_notes/release_18_11.rst
index 3ae6b3f58..db99518f4 100644
--- a/doc/guides/rel_notes/release_18_11.rst
+++ b/doc/guides/rel_notes/release_18_11.rst
@@ -54,6 +54,12 @@ New Features
      Also, make sure to start the actual text at the margin.
      =========================================================
 
+* **Add support to offload more flow match and actions for CXGBE PMD**
+
+  Flow API support has been enhanced for CXGBE Poll Mode Driver to offload:
+
+  * Action items: push/pop/rewrite vlan header.
+
 
 API Changes
 -----------
diff --git a/drivers/net/cxgbe/base/t4_msg.h b/drivers/net/cxgbe/base/t4_msg.h
index 094a153f2..2128da64f 100644
--- a/drivers/net/cxgbe/base/t4_msg.h
+++ b/drivers/net/cxgbe/base/t4_msg.h
@@ -138,6 +138,12 @@ struct work_request_hdr {
 #define V_TCAM_BYPASS(x) ((__u64)(x) << S_TCAM_BYPASS)
 #define F_TCAM_BYPASS    V_TCAM_BYPASS(1ULL)
 
+#define S_L2T_IDX    36
+#define V_L2T_IDX(x) ((__u64)(x) << S_L2T_IDX)
+
+#define S_NAGLE    49
+#define V_NAGLE(x) ((__u64)(x) << S_NAGLE)
+
 /* option 2 fields */
 #define S_RSS_QUEUE    0
 #define V_RSS_QUEUE(x) ((x) << S_RSS_QUEUE)
diff --git a/drivers/net/cxgbe/base/t4_tcb.h b/drivers/net/cxgbe/base/t4_tcb.h
index 25435f9f4..68cda7730 100644
--- a/drivers/net/cxgbe/base/t4_tcb.h
+++ b/drivers/net/cxgbe/base/t4_tcb.h
@@ -6,6 +6,9 @@
 #ifndef _T4_TCB_DEFS_H
 #define _T4_TCB_DEFS_H
 
+/* 95:32 */
+#define W_TCB_T_FLAGS    1
+
 /* 105:96 */
 #define W_TCB_RSS_INFO    3
 #define S_TCB_RSS_INFO    0
@@ -23,4 +26,6 @@
 #define M_TCB_T_RTT_TS_RECENT_AGE    0xffffffffULL
 #define V_TCB_T_RTT_TS_RECENT_AGE(x) ((x) << S_TCB_T_RTT_TS_RECENT_AGE)
 
+#define S_TF_CCTRL_RFR    62
+
 #endif /* _T4_TCB_DEFS_H */
diff --git a/drivers/net/cxgbe/cxgbe_filter.c b/drivers/net/cxgbe/cxgbe_filter.c
index 7f0d38001..4d3f3ebee 100644
--- a/drivers/net/cxgbe/cxgbe_filter.c
+++ b/drivers/net/cxgbe/cxgbe_filter.c
@@ -8,6 +8,7 @@
 #include "t4_regs.h"
 #include "cxgbe_filter.h"
 #include "clip_tbl.h"
+#include "l2t.h"
 
 /**
  * Initialize Hash Filters
@@ -164,6 +165,16 @@ static void set_tcb_field(struct adapter *adapter, unsigned int ftid,
 	t4_mgmt_tx(ctrlq, mbuf);
 }
 
+/**
+ * Set one of the t_flags bits in the TCB.
+ */
+static void set_tcb_tflag(struct adapter *adap, unsigned int ftid,
+			  unsigned int bit_pos, unsigned int val, int no_reply)
+{
+	set_tcb_field(adap, ftid,  W_TCB_T_FLAGS, 1ULL << bit_pos,
+		      (unsigned long long)val << bit_pos, no_reply);
+}
+
 /**
  * Build a CPL_SET_TCB_FIELD message as payload of a ULP_TX_PKT command.
  */
@@ -425,7 +436,10 @@ static void mk_act_open_req6(struct filter_entry *f, struct rte_mbuf *mbuf,
 	req->local_ip_lo = local_lo;
 	req->peer_ip_hi = peer_hi;
 	req->peer_ip_lo = peer_lo;
-	req->opt0 = cpu_to_be64(V_DELACK(f->fs.hitcnts) |
+	req->opt0 = cpu_to_be64(V_NAGLE(f->fs.newvlan == VLAN_REMOVE ||
+					f->fs.newvlan == VLAN_REWRITE) |
+				V_DELACK(f->fs.hitcnts) |
+				V_L2T_IDX(f->l2t ? f->l2t->idx : 0) |
 				V_SMAC_SEL((cxgbe_port_viid(f->dev) & 0x7F)
 					   << 1) |
 				V_TX_CHAN(f->fs.eport) |
@@ -468,7 +482,10 @@ static void mk_act_open_req(struct filter_entry *f, struct rte_mbuf *mbuf,
 			f->fs.val.lip[2] << 16 | f->fs.val.lip[3] << 24;
 	req->peer_ip = f->fs.val.fip[0] | f->fs.val.fip[1] << 8 |
 			f->fs.val.fip[2] << 16 | f->fs.val.fip[3] << 24;
-	req->opt0 = cpu_to_be64(V_DELACK(f->fs.hitcnts) |
+	req->opt0 = cpu_to_be64(V_NAGLE(f->fs.newvlan == VLAN_REMOVE ||
+					f->fs.newvlan == VLAN_REWRITE) |
+				V_DELACK(f->fs.hitcnts) |
+				V_L2T_IDX(f->l2t ? f->l2t->idx : 0) |
 				V_SMAC_SEL((cxgbe_port_viid(f->dev) & 0x7F)
 					   << 1) |
 				V_TX_CHAN(f->fs.eport) |
@@ -518,6 +535,22 @@ static int cxgbe_set_hash_filter(struct rte_eth_dev *dev,
 	f->dev = dev;
 	f->fs.iq = iq;
 
+	/*
+	 * If the new filter requires loopback Destination MAC and/or VLAN
+	 * rewriting then we need to allocate a Layer 2 Table (L2T) entry for
+	 * the filter.
+	 */
+	if (f->fs.newvlan == VLAN_INSERT ||
+	    f->fs.newvlan == VLAN_REWRITE) {
+		/* allocate L2T entry for new filter */
+		f->l2t = cxgbe_l2t_alloc_switching(dev, f->fs.vlan,
+						   f->fs.eport, f->fs.dmac);
+		if (!f->l2t) {
+			ret = -ENOMEM;
+			goto out_err;
+		}
+	}
+
 	atid = cxgbe_alloc_atid(t, f);
 	if (atid < 0)
 		goto out_err;
@@ -653,6 +686,19 @@ int set_filter_wr(struct rte_eth_dev *dev, unsigned int fidx)
 	unsigned int port_id = ethdev2pinfo(dev)->port_id;
 	int ret;
 
+	/*
+	 * If the new filter requires loopback Destination MAC and/or VLAN
+	 * rewriting then we need to allocate a Layer 2 Table (L2T) entry for
+	 * the filter.
+	 */
+	if (f->fs.newvlan) {
+		/* allocate L2T entry for new filter */
+		f->l2t = cxgbe_l2t_alloc_switching(f->dev, f->fs.vlan,
+						   f->fs.eport, f->fs.dmac);
+		if (!f->l2t)
+			return -ENOMEM;
+	}
+
 	ctrlq = &adapter->sge.ctrlq[port_id];
 	mbuf = rte_pktmbuf_alloc(ctrlq->mb_pool);
 	if (!mbuf) {
@@ -680,9 +726,16 @@ int set_filter_wr(struct rte_eth_dev *dev, unsigned int fidx)
 		cpu_to_be32(V_FW_FILTER_WR_DROP(f->fs.action == FILTER_DROP) |
 			    V_FW_FILTER_WR_DIRSTEER(f->fs.dirsteer) |
 			    V_FW_FILTER_WR_LPBK(f->fs.action == FILTER_SWITCH) |
+			    V_FW_FILTER_WR_INSVLAN
+				(f->fs.newvlan == VLAN_INSERT ||
+				 f->fs.newvlan == VLAN_REWRITE) |
+			    V_FW_FILTER_WR_RMVLAN
+				(f->fs.newvlan == VLAN_REMOVE ||
+				 f->fs.newvlan == VLAN_REWRITE) |
 			    V_FW_FILTER_WR_HITCNTS(f->fs.hitcnts) |
 			    V_FW_FILTER_WR_TXCHAN(f->fs.eport) |
-			    V_FW_FILTER_WR_PRIO(f->fs.prio));
+			    V_FW_FILTER_WR_PRIO(f->fs.prio) |
+			    V_FW_FILTER_WR_L2TIX(f->l2t ? f->l2t->idx : 0));
 	fwr->ethtype = cpu_to_be16(f->fs.val.ethtype);
 	fwr->ethtypem = cpu_to_be16(f->fs.mask.ethtype);
 	fwr->smac_sel = 0;
@@ -1046,6 +1099,9 @@ void hash_filter_rpl(struct adapter *adap, const struct cpl_act_open_rpl *rpl)
 				      V_TCB_TIMESTAMP(0ULL) |
 				      V_TCB_T_RTT_TS_RECENT_AGE(0ULL),
 				      1);
+		if (f->fs.newvlan == VLAN_INSERT ||
+		    f->fs.newvlan == VLAN_REWRITE)
+			set_tcb_tflag(adap, tid, S_TF_CCTRL_RFR, 1, 1);
 		break;
 	}
 	default:
diff --git a/drivers/net/cxgbe/cxgbe_filter.h b/drivers/net/cxgbe/cxgbe_filter.h
index be12e231a..c7d9366a6 100644
--- a/drivers/net/cxgbe/cxgbe_filter.h
+++ b/drivers/net/cxgbe/cxgbe_filter.h
@@ -99,6 +99,9 @@ struct ch_filter_specification {
 	uint32_t iq:10;		/* ingress queue */
 
 	uint32_t eport:2;	/* egress port to switch packet out */
+	uint32_t newvlan:2;     /* rewrite VLAN Tag */
+	uint8_t dmac[ETHER_ADDR_LEN];   /* new destination MAC address */
+	uint16_t vlan;          /* VLAN Tag to insert */
 
 	/* Filter rule value/mask pairs. */
 	struct ch_filter_tuple val;
@@ -111,6 +114,12 @@ enum {
 	FILTER_SWITCH
 };
 
+enum {
+	VLAN_REMOVE = 1,
+	VLAN_INSERT,
+	VLAN_REWRITE
+};
+
 enum filter_type {
 	FILTER_TYPE_IPV4 = 0,
 	FILTER_TYPE_IPV6,
diff --git a/drivers/net/cxgbe/cxgbe_flow.c b/drivers/net/cxgbe/cxgbe_flow.c
index 01c945f1b..89fc68cf0 100644
--- a/drivers/net/cxgbe/cxgbe_flow.c
+++ b/drivers/net/cxgbe/cxgbe_flow.c
@@ -331,9 +331,30 @@ ch_rte_parse_atype_switch(const struct rte_flow_action *a,
 			  struct ch_filter_specification *fs,
 			  struct rte_flow_error *e)
 {
+	const struct rte_flow_action_of_set_vlan_vid *vlanid;
+	const struct rte_flow_action_of_push_vlan *pushvlan;
 	const struct rte_flow_action_phy_port *port;
 
 	switch (a->type) {
+	case RTE_FLOW_ACTION_TYPE_OF_SET_VLAN_VID:
+		vlanid = (const struct rte_flow_action_of_set_vlan_vid *)
+			  a->conf;
+		fs->newvlan = VLAN_REWRITE;
+		fs->vlan = vlanid->vlan_vid;
+		break;
+	case RTE_FLOW_ACTION_TYPE_OF_PUSH_VLAN:
+		pushvlan = (const struct rte_flow_action_of_push_vlan *)
+			    a->conf;
+		if (pushvlan->ethertype != ETHER_TYPE_VLAN)
+			return rte_flow_error_set(e, EINVAL,
+						  RTE_FLOW_ERROR_TYPE_ACTION, a,
+						  "only ethertype 0x8100 "
+						  "supported for push vlan.");
+		fs->newvlan = VLAN_INSERT;
+		break;
+	case RTE_FLOW_ACTION_TYPE_OF_POP_VLAN:
+		fs->newvlan = VLAN_REMOVE;
+		break;
 	case RTE_FLOW_ACTION_TYPE_PHY_PORT:
 		port = (const struct rte_flow_action_phy_port *)a->conf;
 		fs->eport = port->index;
@@ -391,6 +412,9 @@ cxgbe_rtef_parse_actions(struct rte_flow *flow,
 		case RTE_FLOW_ACTION_TYPE_COUNT:
 			fs->hitcnts = 1;
 			break;
+		case RTE_FLOW_ACTION_TYPE_OF_SET_VLAN_VID:
+		case RTE_FLOW_ACTION_TYPE_OF_PUSH_VLAN:
+		case RTE_FLOW_ACTION_TYPE_OF_POP_VLAN:
 		case RTE_FLOW_ACTION_TYPE_PHY_PORT:
 			/* We allow multiple switch actions, but switch is
 			 * not compatible with either queue or drop
-- 
2.14.1

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

* [dpdk-dev] [PATCH 3/4] net/cxgbe: add API to program hardware MPS table
  2018-08-27 12:52 [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 1/4] net/cxgbe: add API to program hardware layer 2 table Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 2/4] net/cxgbe: add flow operations to offload vlan actions Rahul Lakkireddy
@ 2018-08-27 12:52 ` Rahul Lakkireddy
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 4/4] net/cxgbe: add flow operations to match based on destination MAC address Rahul Lakkireddy
  2018-09-13 14:03 ` [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Ferruh Yigit
  4 siblings, 0 replies; 6+ messages in thread
From: Rahul Lakkireddy @ 2018-08-27 12:52 UTC (permalink / raw)
  To: dev; +Cc: shaguna, indranil, nirranjan

From: Shagun Agrawal <shaguna@chelsio.com>

Add API to program and manage hardware Multi Port Switch table. MPS
holds destination MAC addresses to be matched against incoming packets
for further rule processing. Packets not matching any entry in MPS table
will be dropped by default, unless the underlying port is in promiscuous
mode.

Signed-off-by: Shagun Agrawal <shaguna@chelsio.com>
Signed-off-by: Rahul Lakkireddy <rahul.lakkireddy@chelsio.com>
---
 drivers/net/cxgbe/Makefile              |   1 +
 drivers/net/cxgbe/base/adapter.h        |   1 +
 drivers/net/cxgbe/base/common.h         |   6 +
 drivers/net/cxgbe/base/t4_hw.c          | 106 ++++++++++++++
 drivers/net/cxgbe/base/t4_regs.h        |   8 ++
 drivers/net/cxgbe/base/t4fw_interface.h |  24 ++++
 drivers/net/cxgbe/cxgbe_main.c          |   7 +
 drivers/net/cxgbe/meson.build           |   1 +
 drivers/net/cxgbe/mps_tcam.c            | 243 ++++++++++++++++++++++++++++++++
 drivers/net/cxgbe/mps_tcam.h            |  52 +++++++
 10 files changed, 449 insertions(+)
 create mode 100644 drivers/net/cxgbe/mps_tcam.c
 create mode 100644 drivers/net/cxgbe/mps_tcam.h

diff --git a/drivers/net/cxgbe/Makefile b/drivers/net/cxgbe/Makefile
index d75b070f3..68466f13e 100644
--- a/drivers/net/cxgbe/Makefile
+++ b/drivers/net/cxgbe/Makefile
@@ -53,6 +53,7 @@ SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += cxgbe_filter.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += cxgbe_flow.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += t4_hw.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += clip_tbl.c
+SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += mps_tcam.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += l2t.c
 SRCS-$(CONFIG_RTE_LIBRTE_CXGBE_PMD) += t4vf_hw.c
 
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 9f4a9653c..47cfc5f5f 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -328,6 +328,7 @@ struct adapter {
 	unsigned int l2t_end;     /* Layer 2 table end */
 	struct clip_tbl *clipt;   /* CLIP table */
 	struct l2t_data *l2t;     /* Layer 2 table */
+	struct mpstcam_table *mpstcam;
 
 	struct tid_info tids;     /* Info used to access TID related tables */
 };
diff --git a/drivers/net/cxgbe/base/common.h b/drivers/net/cxgbe/base/common.h
index 157201da2..9f5756850 100644
--- a/drivers/net/cxgbe/base/common.h
+++ b/drivers/net/cxgbe/base/common.h
@@ -388,6 +388,12 @@ int t4_free_vi(struct adapter *adap, unsigned int mbox,
 int t4_set_rxmode(struct adapter *adap, unsigned int mbox, unsigned int viid,
 		  int mtu, int promisc, int all_multi, int bcast, int vlanex,
 		  bool sleep_ok);
+int t4_free_raw_mac_filt(struct adapter *adap, unsigned int viid,
+			 const u8 *addr, const u8 *mask, unsigned int idx,
+			 u8 lookup_type, u8 port_id, bool sleep_ok);
+int t4_alloc_raw_mac_filt(struct adapter *adap, unsigned int viid,
+			  const u8 *addr, const u8 *mask, unsigned int idx,
+			  u8 lookup_type, u8 port_id, bool sleep_ok);
 int t4_change_mac(struct adapter *adap, unsigned int mbox, unsigned int viid,
 		  int idx, const u8 *addr, bool persist, bool add_smt);
 int t4_enable_vi_params(struct adapter *adap, unsigned int mbox,
diff --git a/drivers/net/cxgbe/base/t4_hw.c b/drivers/net/cxgbe/base/t4_hw.c
index 31762c9c5..d60894115 100644
--- a/drivers/net/cxgbe/base/t4_hw.c
+++ b/drivers/net/cxgbe/base/t4_hw.c
@@ -4161,6 +4161,112 @@ int t4_set_rxmode(struct adapter *adap, unsigned int mbox, unsigned int viid,
 		return t4vf_wr_mbox(adap, &c, sizeof(c), NULL);
 }
 
+/**
+ *	t4_alloc_raw_mac_filt - Adds a raw mac entry in mps tcam
+ *	@adap: the adapter
+ *	@viid: the VI id
+ *	@mac: the MAC address
+ *	@mask: the mask
+ *	@idx: index at which to add this entry
+ *	@port_id: the port index
+ *	@lookup_type: MAC address for inner (1) or outer (0) header
+ *	@sleep_ok: call is allowed to sleep
+ *
+ *	Adds the mac entry at the specified index using raw mac interface.
+ *
+ *	Returns a negative error number or the allocated index for this mac.
+ */
+int t4_alloc_raw_mac_filt(struct adapter *adap, unsigned int viid,
+			  const u8 *addr, const u8 *mask, unsigned int idx,
+			  u8 lookup_type, u8 port_id, bool sleep_ok)
+{
+	int ret = 0;
+	struct fw_vi_mac_cmd c;
+	struct fw_vi_mac_raw *p = &c.u.raw;
+	u32 val;
+
+	memset(&c, 0, sizeof(c));
+	c.op_to_viid = cpu_to_be32(V_FW_CMD_OP(FW_VI_MAC_CMD) |
+				   F_FW_CMD_REQUEST | F_FW_CMD_WRITE |
+				   V_FW_VI_MAC_CMD_VIID(viid));
+	val = V_FW_CMD_LEN16(1) |
+	      V_FW_VI_MAC_CMD_ENTRY_TYPE(FW_VI_MAC_TYPE_RAW);
+	c.freemacs_to_len16 = cpu_to_be32(val);
+
+	/* Specify that this is an inner mac address */
+	p->raw_idx_pkd = cpu_to_be32(V_FW_VI_MAC_CMD_RAW_IDX(idx));
+
+	/* Lookup Type. Outer header: 0, Inner header: 1 */
+	p->data0_pkd = cpu_to_be32(V_DATALKPTYPE(lookup_type) |
+				   V_DATAPORTNUM(port_id));
+	/* Lookup mask and port mask */
+	p->data0m_pkd = cpu_to_be64(V_DATALKPTYPE(M_DATALKPTYPE) |
+				    V_DATAPORTNUM(M_DATAPORTNUM));
+
+	/* Copy the address and the mask */
+	memcpy((u8 *)&p->data1[0] + 2, addr, ETHER_ADDR_LEN);
+	memcpy((u8 *)&p->data1m[0] + 2, mask, ETHER_ADDR_LEN);
+
+	ret = t4_wr_mbox_meat(adap, adap->mbox, &c, sizeof(c), &c, sleep_ok);
+	if (ret == 0) {
+		ret = G_FW_VI_MAC_CMD_RAW_IDX(be32_to_cpu(p->raw_idx_pkd));
+		if (ret != (int)idx)
+			ret = -ENOMEM;
+	}
+
+	return ret;
+}
+
+/**
+ *	t4_free_raw_mac_filt - Frees a raw mac entry in mps tcam
+ *	@adap: the adapter
+ *	@viid: the VI id
+ *	@addr: the MAC address
+ *	@mask: the mask
+ *	@idx: index of the entry in mps tcam
+ *	@lookup_type: MAC address for inner (1) or outer (0) header
+ *	@port_id: the port index
+ *	@sleep_ok: call is allowed to sleep
+ *
+ *	Removes the mac entry at the specified index using raw mac interface.
+ *
+ *	Returns a negative error number on failure.
+ */
+int t4_free_raw_mac_filt(struct adapter *adap, unsigned int viid,
+			 const u8 *addr, const u8 *mask, unsigned int idx,
+			 u8 lookup_type, u8 port_id, bool sleep_ok)
+{
+	struct fw_vi_mac_cmd c;
+	struct fw_vi_mac_raw *p = &c.u.raw;
+	u32 raw;
+
+	memset(&c, 0, sizeof(c));
+	c.op_to_viid = cpu_to_be32(V_FW_CMD_OP(FW_VI_MAC_CMD) |
+				   F_FW_CMD_REQUEST | F_FW_CMD_WRITE |
+				   V_FW_CMD_EXEC(0) |
+				   V_FW_VI_MAC_CMD_VIID(viid));
+	raw = V_FW_VI_MAC_CMD_ENTRY_TYPE(FW_VI_MAC_TYPE_RAW);
+	c.freemacs_to_len16 = cpu_to_be32(V_FW_VI_MAC_CMD_FREEMACS(0) |
+					  raw |
+					  V_FW_CMD_LEN16(1));
+
+	p->raw_idx_pkd = cpu_to_be32(V_FW_VI_MAC_CMD_RAW_IDX(idx) |
+				     FW_VI_MAC_ID_BASED_FREE);
+
+	/* Lookup Type. Outer header: 0, Inner header: 1 */
+	p->data0_pkd = cpu_to_be32(V_DATALKPTYPE(lookup_type) |
+				   V_DATAPORTNUM(port_id));
+	/* Lookup mask and port mask */
+	p->data0m_pkd = cpu_to_be64(V_DATALKPTYPE(M_DATALKPTYPE) |
+				    V_DATAPORTNUM(M_DATAPORTNUM));
+
+	/* Copy the address and the mask */
+	memcpy((u8 *)&p->data1[0] + 2, addr, ETHER_ADDR_LEN);
+	memcpy((u8 *)&p->data1m[0] + 2, mask, ETHER_ADDR_LEN);
+
+	return t4_wr_mbox_meat(adap, adap->mbox, &c, sizeof(c), &c, sleep_ok);
+}
+
 /**
  * t4_change_mac - modifies the exact-match filter for a MAC address
  * @adap: the adapter
diff --git a/drivers/net/cxgbe/base/t4_regs.h b/drivers/net/cxgbe/base/t4_regs.h
index 6f872edc2..af8c741e2 100644
--- a/drivers/net/cxgbe/base/t4_regs.h
+++ b/drivers/net/cxgbe/base/t4_regs.h
@@ -45,6 +45,14 @@
 #define MPS_T5_CLS_SRAM_H(idx) (A_MPS_T5_CLS_SRAM_H + (idx) * 8)
 #define NUM_MPS_T5_CLS_SRAM_H_INSTANCES 512
 
+#define S_DATAPORTNUM    12
+#define M_DATAPORTNUM    0xfU
+#define V_DATAPORTNUM(x) ((x) << S_DATAPORTNUM)
+
+#define S_DATALKPTYPE    10
+#define M_DATALKPTYPE    0x3U
+#define V_DATALKPTYPE(x) ((x) << S_DATALKPTYPE)
+
 /* registers for module SGE */
 #define SGE_BASE_ADDR 0x1000
 
diff --git a/drivers/net/cxgbe/base/t4fw_interface.h b/drivers/net/cxgbe/base/t4fw_interface.h
index 1c08637bb..e2d2ee897 100644
--- a/drivers/net/cxgbe/base/t4fw_interface.h
+++ b/drivers/net/cxgbe/base/t4fw_interface.h
@@ -1282,12 +1282,17 @@ struct fw_vi_cmd {
 /* Special VI_MAC command index ids */
 #define FW_VI_MAC_ADD_MAC		0x3FF
 #define FW_VI_MAC_ADD_PERSIST_MAC	0x3FE
+#define FW_VI_MAC_ID_BASED_FREE         0x3FC
 
 enum fw_vi_mac_smac {
 	FW_VI_MAC_MPS_TCAM_ENTRY,
 	FW_VI_MAC_SMT_AND_MPSTCAM
 };
 
+enum fw_vi_mac_entry_types {
+	FW_VI_MAC_TYPE_RAW = 0x2,
+};
+
 struct fw_vi_mac_cmd {
 	__be32 op_to_viid;
 	__be32 freemacs_to_len16;
@@ -1299,6 +1304,13 @@ struct fw_vi_mac_cmd {
 		struct fw_vi_mac_hash {
 			__be64 hashvec;
 		} hash;
+		struct fw_vi_mac_raw {
+			__be32 raw_idx_pkd;
+			__be32 data0_pkd;
+			__be32 data1[2];
+			__be64 data0m_pkd;
+			__be32 data1m[2];
+		} raw;
 	} u;
 };
 
@@ -1308,6 +1320,12 @@ struct fw_vi_mac_cmd {
 #define G_FW_VI_MAC_CMD_VIID(x)	\
 	(((x) >> S_FW_VI_MAC_CMD_VIID) & M_FW_VI_MAC_CMD_VIID)
 
+#define S_FW_VI_MAC_CMD_FREEMACS	31
+#define V_FW_VI_MAC_CMD_FREEMACS(x)	((x) << S_FW_VI_MAC_CMD_FREEMACS)
+
+#define S_FW_VI_MAC_CMD_ENTRY_TYPE      23
+#define V_FW_VI_MAC_CMD_ENTRY_TYPE(x)   ((x) << S_FW_VI_MAC_CMD_ENTRY_TYPE)
+
 #define S_FW_VI_MAC_CMD_VALID		15
 #define M_FW_VI_MAC_CMD_VALID		0x1
 #define V_FW_VI_MAC_CMD_VALID(x)	((x) << S_FW_VI_MAC_CMD_VALID)
@@ -1327,6 +1345,12 @@ struct fw_vi_mac_cmd {
 #define G_FW_VI_MAC_CMD_IDX(x)	\
 	(((x) >> S_FW_VI_MAC_CMD_IDX) & M_FW_VI_MAC_CMD_IDX)
 
+#define S_FW_VI_MAC_CMD_RAW_IDX         16
+#define M_FW_VI_MAC_CMD_RAW_IDX         0xffff
+#define V_FW_VI_MAC_CMD_RAW_IDX(x)      ((x) << S_FW_VI_MAC_CMD_RAW_IDX)
+#define G_FW_VI_MAC_CMD_RAW_IDX(x)      \
+	(((x) >> S_FW_VI_MAC_CMD_RAW_IDX) & M_FW_VI_MAC_CMD_RAW_IDX)
+
 struct fw_vi_rxmode_cmd {
 	__be32 op_to_viid;
 	__be32 retval_len16;
diff --git a/drivers/net/cxgbe/cxgbe_main.c b/drivers/net/cxgbe/cxgbe_main.c
index be2bc4213..20d2de442 100644
--- a/drivers/net/cxgbe/cxgbe_main.c
+++ b/drivers/net/cxgbe/cxgbe_main.c
@@ -39,6 +39,7 @@
 #include "cxgbe.h"
 #include "clip_tbl.h"
 #include "l2t.h"
+#include "mps_tcam.h"
 
 /**
  * Allocate a chunk of memory. The allocated memory is cleared.
@@ -1689,6 +1690,7 @@ void cxgbe_close(struct adapter *adapter)
 
 	if (adapter->flags & FULL_INIT_DONE) {
 		tid_free(&adapter->tids);
+		t4_cleanup_mpstcam(adapter);
 		t4_cleanup_clip_tbl(adapter);
 		t4_cleanup_l2t(adapter);
 		if (is_pf4(adapter))
@@ -1877,6 +1879,11 @@ int cxgbe_probe(struct adapter *adapter)
 			 "filter support disabled. Continuing\n");
 	}
 
+	adapter->mpstcam = t4_init_mpstcam(adapter);
+	if (!adapter->mpstcam)
+		dev_warn(adapter, "could not allocate mps tcam table."
+			 " Continuing\n");
+
 	if (is_hashfilter(adapter)) {
 		if (t4_read_reg(adapter, A_LE_DB_CONFIG) & F_HASHEN) {
 			u32 hash_base, hash_reg;
diff --git a/drivers/net/cxgbe/meson.build b/drivers/net/cxgbe/meson.build
index f6a442cb8..c51af26e9 100644
--- a/drivers/net/cxgbe/meson.build
+++ b/drivers/net/cxgbe/meson.build
@@ -9,6 +9,7 @@ sources = files('cxgbe_ethdev.c',
 	'cxgbe_filter.c',
 	'cxgbe_flow.c',
 	'clip_tbl.c',
+	'mps_tcam.c',
 	'l2t.c',
 	'base/t4_hw.c',
 	'base/t4vf_hw.c')
diff --git a/drivers/net/cxgbe/mps_tcam.c b/drivers/net/cxgbe/mps_tcam.c
new file mode 100644
index 000000000..02ec69a92
--- /dev/null
+++ b/drivers/net/cxgbe/mps_tcam.c
@@ -0,0 +1,243 @@
+/* SPDX-License-Identifier: BSD-3-Clause
+ * Copyright(c) 2018 Chelsio Communications.
+ * All rights reserved.
+ */
+
+#include "mps_tcam.h"
+
+static inline bool
+match_entry(struct mps_tcam_entry *entry, const u8 *eth_addr, const u8 *mask)
+{
+	if (!memcmp(eth_addr, entry->eth_addr, ETHER_ADDR_LEN) &&
+	    !memcmp(mask, entry->mask, ETHER_ADDR_LEN))
+		return true;
+	return false;
+}
+
+static int cxgbe_update_free_idx(struct mpstcam_table *t)
+{
+	struct mps_tcam_entry *entry = t->entry;
+	u16 i, next = t->free_idx + 1;
+
+	if (entry[t->free_idx].state == MPS_ENTRY_UNUSED)
+		/* You are already pointing to a free entry !! */
+		return 0;
+
+	/* loop, till we don't rollback to same index where we started */
+	for (i = next; i != t->free_idx; i++) {
+		if (i == t->size)
+			/* rollback and search free entry from start */
+			i = 0;
+
+		if (entry[i].state == MPS_ENTRY_UNUSED) {
+			t->free_idx = i;
+			return 0;
+		}
+	}
+
+	return -1;	/* table is full */
+}
+
+static struct mps_tcam_entry *
+cxgbe_mpstcam_lookup(struct mpstcam_table *t, const u8 *eth_addr,
+		     const u8 *mask)
+{
+	struct mps_tcam_entry *entry = t->entry;
+	int i;
+
+	if (!entry)
+		return NULL;
+
+	for (i = 0; i < t->size; i++) {
+		if (entry[i].state == MPS_ENTRY_UNUSED)
+			continue;	/* entry is not being used */
+		if (match_entry(&entry[i], eth_addr, mask))
+			return &entry[i];
+	}
+
+	return NULL;
+}
+
+int cxgbe_mpstcam_alloc(struct port_info *pi, const u8 *eth_addr,
+			const u8 *mask)
+{
+	struct adapter *adap = pi->adapter;
+	struct mpstcam_table *mpstcam = adap->mpstcam;
+	struct mps_tcam_entry *entry;
+	int ret;
+
+	if (!adap->mpstcam) {
+		dev_err(adap, "mpstcam table is not available\n");
+		return -EOPNOTSUPP;
+	}
+
+	/* If entry already present, return it. */
+	t4_os_write_lock(&mpstcam->lock);
+	entry = cxgbe_mpstcam_lookup(adap->mpstcam, eth_addr, mask);
+	if (entry) {
+		rte_atomic32_add(&entry->refcnt, 1);
+		t4_os_write_unlock(&mpstcam->lock);
+		return entry->idx;
+	}
+
+	if (mpstcam->full) {
+		t4_os_write_unlock(&mpstcam->lock);
+		dev_err(adap, "mps-tcam table is full\n");
+		return -ENOMEM;
+	}
+
+	ret = t4_alloc_raw_mac_filt(adap, pi->viid, eth_addr, mask,
+				    mpstcam->free_idx, 0, pi->port_id, false);
+	if (ret <= 0) {
+		t4_os_write_unlock(&mpstcam->lock);
+		return ret;
+	}
+
+	/* Fill in the new values */
+	entry = &mpstcam->entry[ret];
+	memcpy(entry->eth_addr, eth_addr, ETHER_ADDR_LEN);
+	memcpy(entry->mask, mask, ETHER_ADDR_LEN);
+	rte_atomic32_set(&entry->refcnt, 1);
+	entry->state = MPS_ENTRY_USED;
+
+	if (cxgbe_update_free_idx(mpstcam))
+		mpstcam->full = true;
+
+	t4_os_write_unlock(&mpstcam->lock);
+	return ret;
+}
+
+int cxgbe_mpstcam_modify(struct port_info *pi, int idx, const u8 *addr)
+{
+	struct adapter *adap = pi->adapter;
+	struct mpstcam_table *mpstcam = adap->mpstcam;
+	struct mps_tcam_entry *entry;
+
+	if (!mpstcam)
+		return -EOPNOTSUPP;
+	t4_os_write_lock(&mpstcam->lock);
+	if (idx != -1 && idx >= mpstcam->size) {
+		t4_os_write_unlock(&mpstcam->lock);
+		return -EINVAL;
+	}
+	if (idx >= 0) {
+		entry = &mpstcam->entry[idx];
+		/* user wants to modify an existing entry.
+		 * verify if entry exists
+		 */
+		if (entry->state != MPS_ENTRY_USED) {
+			t4_os_write_unlock(&mpstcam->lock);
+			return -EINVAL;
+		}
+	}
+
+	idx = t4_change_mac(adap, adap->mbox, pi->viid, idx, addr, true, true);
+	if (idx < 0) {
+		t4_os_write_unlock(&mpstcam->lock);
+		return idx;
+	}
+
+	/* idx can now be different from what user provided */
+	entry = &mpstcam->entry[idx];
+	memcpy(entry->eth_addr, addr, ETHER_ADDR_LEN);
+	/* NOTE: we have considered the case that idx returned by t4_change_mac
+	 * will be different from the user provided value only if user
+	 * provided value is -1
+	 */
+	if (entry->state == MPS_ENTRY_UNUSED) {
+		rte_atomic32_set(&entry->refcnt, 1);
+		entry->state = MPS_ENTRY_USED;
+	}
+
+	if (cxgbe_update_free_idx(mpstcam))
+		mpstcam->full = true;
+
+	t4_os_write_unlock(&mpstcam->lock);
+	return idx;
+}
+
+/**
+ * hold appropriate locks while calling this.
+ */
+static inline void reset_mpstcam_entry(struct mps_tcam_entry *entry)
+{
+	memset(entry->eth_addr, 0, ETHER_ADDR_LEN);
+	memset(entry->mask, 0, ETHER_ADDR_LEN);
+	rte_atomic32_clear(&entry->refcnt);
+	entry->state = MPS_ENTRY_UNUSED;
+}
+
+/**
+ * ret < 0: fatal error
+ * ret = 0: entry removed in h/w
+ * ret > 0: updated refcount.
+ */
+int cxgbe_mpstcam_remove(struct port_info *pi, u16 idx)
+{
+	struct adapter *adap = pi->adapter;
+	struct mpstcam_table *t = adap->mpstcam;
+	struct mps_tcam_entry *entry;
+	int ret;
+
+	if (!t)
+		return -EOPNOTSUPP;
+	t4_os_write_lock(&t->lock);
+	entry = &t->entry[idx];
+	if (entry->state == MPS_ENTRY_UNUSED) {
+		t4_os_write_unlock(&t->lock);
+		return -EINVAL;
+	}
+
+	if (rte_atomic32_read(&entry->refcnt) == 1)
+		ret = t4_free_raw_mac_filt(adap, pi->viid, entry->eth_addr,
+					   entry->mask, idx, 1, pi->port_id,
+					   false);
+	else
+		ret = rte_atomic32_sub_return(&entry->refcnt, 1);
+
+	if (ret == 0) {
+		reset_mpstcam_entry(entry);
+		t->full = false;	/* We have atleast 1 free entry */
+		cxgbe_update_free_idx(t);
+	}
+
+	t4_os_write_unlock(&t->lock);
+	return ret;
+}
+
+struct mpstcam_table *t4_init_mpstcam(struct adapter *adap)
+{
+	struct mpstcam_table *t;
+	int i;
+	u16 size = adap->params.arch.mps_tcam_size;
+
+	t =  t4_os_alloc(sizeof(*t) + size * sizeof(struct mps_tcam_entry));
+	if (!t)
+		return NULL;
+
+	t4_os_rwlock_init(&t->lock);
+	t->full = false;
+	t->size = size;
+
+	for (i = 0; i < size; i++) {
+		reset_mpstcam_entry(&t->entry[i]);
+		t->entry[i].mpstcam = t;
+		t->entry[i].idx = i;
+	}
+
+	/* first entry is used by chip. this is overwritten only
+	 * in t4_cleanup_mpstcam()
+	 */
+	t->entry[0].state = MPS_ENTRY_USED;
+	t->free_idx = 1;
+
+	return t;
+}
+
+void t4_cleanup_mpstcam(struct adapter *adap)
+{
+	if (adap->mpstcam) {
+		t4_os_free(adap->mpstcam->entry);
+		t4_os_free(adap->mpstcam);
+	}
+}
diff --git a/drivers/net/cxgbe/mps_tcam.h b/drivers/net/cxgbe/mps_tcam.h
new file mode 100644
index 000000000..c3d6fe0d7
--- /dev/null
+++ b/drivers/net/cxgbe/mps_tcam.h
@@ -0,0 +1,52 @@
+/* SPDX-License-Identifier: BSD-3-Clause
+ * Copyright(c) 2018 Chelsio Communications.
+ * All rights reserved.
+ */
+
+#ifndef _CXGBE_MPSTCAM_H_
+#define _CXGBE_MPSTCAM_H_
+
+#include "common.h"
+
+enum {
+	MPS_ENTRY_UNUSED,	/* Keep this first so memset 0 renders
+				 * the correct state. Other states can
+				 * be added in future like MPS_ENTRY_BUSY
+				 * to reduce contention while mboxing
+				 * the request to f/w or to denote attributes
+				 * for a specific entry
+				 */
+	MPS_ENTRY_USED,
+};
+
+struct mps_tcam_entry {
+	u8 state;
+	u16 idx;
+
+	/* add data here which uniquely defines an entry */
+	u8 eth_addr[ETHER_ADDR_LEN];
+	u8 mask[ETHER_ADDR_LEN];
+
+	struct mpstcam_table *mpstcam; /* backptr */
+	rte_atomic32_t refcnt;
+};
+
+struct mpstcam_table {
+	u16 size;
+	rte_rwlock_t lock;
+	u16 free_idx;	/* next free index */
+	bool full;	/* since free index can be present
+			 * anywhere in the table, size and
+			 * free_idx cannot alone determine
+			 * if the table is full
+			 */
+	struct mps_tcam_entry entry[0];
+};
+
+struct mpstcam_table *t4_init_mpstcam(struct adapter *adap);
+void t4_cleanup_mpstcam(struct adapter *adap);
+int cxgbe_mpstcam_alloc(struct port_info *pi, const u8 *mac, const u8 *mask);
+int cxgbe_mpstcam_remove(struct port_info *pi, u16 idx);
+int cxgbe_mpstcam_modify(struct port_info *pi, int idx, const u8 *addr);
+
+#endif /* _CXGBE_MPSTCAM_H_ */
-- 
2.14.1

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

* [dpdk-dev] [PATCH 4/4] net/cxgbe: add flow operations to match based on destination MAC address
  2018-08-27 12:52 [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Rahul Lakkireddy
                   ` (2 preceding siblings ...)
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 3/4] net/cxgbe: add API to program hardware MPS table Rahul Lakkireddy
@ 2018-08-27 12:52 ` Rahul Lakkireddy
  2018-09-13 14:03 ` [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Ferruh Yigit
  4 siblings, 0 replies; 6+ messages in thread
From: Rahul Lakkireddy @ 2018-08-27 12:52 UTC (permalink / raw)
  To: dev; +Cc: shaguna, indranil, nirranjan

From: Shagun Agrawal <shaguna@chelsio.com>

Add flow operations to match packets based on destination MAC address.
Allocate and program hardware MPS table with the destination MAC
address to be matched against. The returned MPS index is then used while
offloading flows to LETCAM (maskfull) and HASH (maskless) filter regions.

Also update existing mac_addr_set() to use the new MPS table API.

Signed-off-by: Shagun Agrawal <shaguna@chelsio.com>
Signed-off-by: Rahul Lakkireddy <rahul.lakkireddy@chelsio.com>
---
 doc/guides/rel_notes/release_18_11.rst |  1 +
 drivers/net/cxgbe/base/common.h        |  1 +
 drivers/net/cxgbe/base/t4_hw.c         |  2 ++
 drivers/net/cxgbe/cxgbe_ethdev.c       |  4 +--
 drivers/net/cxgbe/cxgbe_filter.c       |  9 +++--
 drivers/net/cxgbe/cxgbe_filter.h       |  1 +
 drivers/net/cxgbe/cxgbe_flow.c         | 66 ++++++++++++++++++++++++++++++++--
 drivers/net/cxgbe/cxgbe_flow.h         |  1 +
 drivers/net/cxgbe/cxgbe_main.c         |  6 ++--
 9 files changed, 80 insertions(+), 11 deletions(-)

diff --git a/doc/guides/rel_notes/release_18_11.rst b/doc/guides/rel_notes/release_18_11.rst
index db99518f4..f7bef95e1 100644
--- a/doc/guides/rel_notes/release_18_11.rst
+++ b/doc/guides/rel_notes/release_18_11.rst
@@ -58,6 +58,7 @@ New Features
 
   Flow API support has been enhanced for CXGBE Poll Mode Driver to offload:
 
+  * Match items: destination MAC address.
   * Action items: push/pop/rewrite vlan header.
 
 
diff --git a/drivers/net/cxgbe/base/common.h b/drivers/net/cxgbe/base/common.h
index 9f5756850..d9f74d995 100644
--- a/drivers/net/cxgbe/base/common.h
+++ b/drivers/net/cxgbe/base/common.h
@@ -157,6 +157,7 @@ struct tp_params {
 	int port_shift;
 	int protocol_shift;
 	int ethertype_shift;
+	int macmatch_shift;
 
 	u64 hash_filter_mask;
 };
diff --git a/drivers/net/cxgbe/base/t4_hw.c b/drivers/net/cxgbe/base/t4_hw.c
index d60894115..701e0b1fe 100644
--- a/drivers/net/cxgbe/base/t4_hw.c
+++ b/drivers/net/cxgbe/base/t4_hw.c
@@ -5251,6 +5251,8 @@ int t4_init_tp_params(struct adapter *adap)
 							       F_PROTOCOL);
 	adap->params.tp.ethertype_shift = t4_filter_field_shift(adap,
 								F_ETHERTYPE);
+	adap->params.tp.macmatch_shift = t4_filter_field_shift(adap,
+							       F_MACMATCH);
 
 	/*
 	 * If TP_INGRESS_CONFIG.VNID == 0, then TP_VLAN_PRI_MAP.VNIC_ID
diff --git a/drivers/net/cxgbe/cxgbe_ethdev.c b/drivers/net/cxgbe/cxgbe_ethdev.c
index 4dcad7a23..f253c2023 100644
--- a/drivers/net/cxgbe/cxgbe_ethdev.c
+++ b/drivers/net/cxgbe/cxgbe_ethdev.c
@@ -1075,11 +1075,9 @@ static int cxgbe_get_regs(struct rte_eth_dev *eth_dev,
 int cxgbe_mac_addr_set(struct rte_eth_dev *dev, struct ether_addr *addr)
 {
 	struct port_info *pi = (struct port_info *)(dev->data->dev_private);
-	struct adapter *adapter = pi->adapter;
 	int ret;
 
-	ret = t4_change_mac(adapter, adapter->mbox, pi->viid,
-			    pi->xact_addr_filt, (u8 *)addr, true, true);
+	ret = cxgbe_mpstcam_modify(pi, (int)pi->xact_addr_filt, (u8 *)addr);
 	if (ret < 0) {
 		dev_err(adapter, "failed to set mac addr; err = %d\n",
 			ret);
diff --git a/drivers/net/cxgbe/cxgbe_filter.c b/drivers/net/cxgbe/cxgbe_filter.c
index 4d3f3ebee..dcb1dd03e 100644
--- a/drivers/net/cxgbe/cxgbe_filter.c
+++ b/drivers/net/cxgbe/cxgbe_filter.c
@@ -66,7 +66,8 @@ int validate_filter(struct adapter *adapter, struct ch_filter_specification *fs)
 #define U(_mask, _field) \
 	(!(fconf & (_mask)) && S(_field))
 
-	if (U(F_PORT, iport) || U(F_ETHERTYPE, ethtype) || U(F_PROTOCOL, proto))
+	if (U(F_PORT, iport) || U(F_ETHERTYPE, ethtype) ||
+	    U(F_PROTOCOL, proto) || U(F_MACMATCH, macidx))
 		return -EOPNOTSUPP;
 
 #undef S
@@ -268,6 +269,8 @@ static u64 hash_filter_ntuple(const struct filter_entry *f)
 
 	if (tp->ethertype_shift >= 0 && f->fs.mask.ethtype)
 		ntuple |= (u64)(f->fs.val.ethtype) << tp->ethertype_shift;
+	if (tp->macmatch_shift >= 0 && f->fs.mask.macidx)
+		ntuple |= (u64)(f->fs.val.macidx) << tp->macmatch_shift;
 
 	if (ntuple != tp->hash_filter_mask)
 		return 0;
@@ -744,7 +747,9 @@ int set_filter_wr(struct rte_eth_dev *dev, unsigned int fidx)
 			    V_FW_FILTER_WR_RX_RPL_IQ(adapter->sge.fw_evtq.abs_id
 						     ));
 	fwr->maci_to_matchtypem =
-		cpu_to_be32(V_FW_FILTER_WR_PORT(f->fs.val.iport) |
+		cpu_to_be32(V_FW_FILTER_WR_MACI(f->fs.val.macidx) |
+			    V_FW_FILTER_WR_MACIM(f->fs.mask.macidx) |
+			    V_FW_FILTER_WR_PORT(f->fs.val.iport) |
 			    V_FW_FILTER_WR_PORTM(f->fs.mask.iport));
 	fwr->ptcl = f->fs.val.proto;
 	fwr->ptclm = f->fs.mask.proto;
diff --git a/drivers/net/cxgbe/cxgbe_filter.h b/drivers/net/cxgbe/cxgbe_filter.h
index c7d9366a6..83d647de6 100644
--- a/drivers/net/cxgbe/cxgbe_filter.h
+++ b/drivers/net/cxgbe/cxgbe_filter.h
@@ -77,6 +77,7 @@ struct ch_filter_tuple {
  * Filter specification
  */
 struct ch_filter_specification {
+	void *private;
 	/* Administrative fields for filter. */
 	uint32_t hitcnts:1;	/* count filter hits in TCB */
 	uint32_t prio:1;	/* filter has priority over active/server */
diff --git a/drivers/net/cxgbe/cxgbe_flow.c b/drivers/net/cxgbe/cxgbe_flow.c
index 89fc68cf0..add4f0f95 100644
--- a/drivers/net/cxgbe/cxgbe_flow.c
+++ b/drivers/net/cxgbe/cxgbe_flow.c
@@ -95,6 +95,8 @@ cxgbe_fill_filter_region(struct adapter *adap,
 		ntuple_mask |= (u64)fs->mask.ethtype << tp->ethertype_shift;
 	if (tp->port_shift >= 0)
 		ntuple_mask |= (u64)fs->mask.iport << tp->port_shift;
+	if (tp->macmatch_shift >= 0)
+		ntuple_mask |= (u64)fs->mask.macidx << tp->macmatch_shift;
 
 	if (ntuple_mask != hash_filter_mask)
 		return;
@@ -102,6 +104,46 @@ cxgbe_fill_filter_region(struct adapter *adap,
 	fs->cap = 1;	/* use hash region */
 }
 
+static int
+ch_rte_parsetype_eth(const void *dmask, const struct rte_flow_item *item,
+		     struct ch_filter_specification *fs,
+		     struct rte_flow_error *e)
+{
+	const struct rte_flow_item_eth *spec = item->spec;
+	const struct rte_flow_item_eth *umask = item->mask;
+	const struct rte_flow_item_eth *mask;
+
+	/* If user has not given any mask, then use chelsio supported mask. */
+	mask = umask ? umask : (const struct rte_flow_item_eth *)dmask;
+
+	/* we don't support SRC_MAC filtering*/
+	if (!is_zero_ether_addr(&mask->src))
+		return rte_flow_error_set(e, ENOTSUP, RTE_FLOW_ERROR_TYPE_ITEM,
+					  item,
+					  "src mac filtering not supported");
+
+	if (!is_zero_ether_addr(&mask->dst)) {
+		const u8 *addr = (const u8 *)&spec->dst.addr_bytes[0];
+		const u8 *m = (const u8 *)&mask->dst.addr_bytes[0];
+		struct rte_flow *flow = (struct rte_flow *)fs->private;
+		struct port_info *pi = (struct port_info *)
+					(flow->dev->data->dev_private);
+		int idx;
+
+		idx = cxgbe_mpstcam_alloc(pi, addr, m);
+		if (idx <= 0)
+			return rte_flow_error_set(e, idx,
+						  RTE_FLOW_ERROR_TYPE_ITEM,
+						  NULL, "unable to allocate mac"
+						  " entry in h/w");
+		CXGBE_FILL_FS(idx, 0x1ff, macidx);
+	}
+
+	CXGBE_FILL_FS(be16_to_cpu(spec->type),
+		      be16_to_cpu(mask->type), ethtype);
+	return 0;
+}
+
 static int
 ch_rte_parsetype_port(const void *dmask, const struct rte_flow_item *item,
 		      struct ch_filter_specification *fs,
@@ -440,7 +482,16 @@ cxgbe_rtef_parse_actions(struct rte_flow *flow,
 }
 
 struct chrte_fparse parseitem[] = {
-		[RTE_FLOW_ITEM_TYPE_PHY_PORT] = {
+	[RTE_FLOW_ITEM_TYPE_ETH] = {
+		.fptr  = ch_rte_parsetype_eth,
+		.dmask = &(const struct rte_flow_item_eth){
+			.dst.addr_bytes = "\xff\xff\xff\xff\xff\xff",
+			.src.addr_bytes = "\x00\x00\x00\x00\x00\x00",
+			.type = 0xffff,
+		}
+	},
+
+	[RTE_FLOW_ITEM_TYPE_PHY_PORT] = {
 		.fptr = ch_rte_parsetype_port,
 		.dmask = &(const struct rte_flow_item_phy_port){
 			.index = 0x7,
@@ -527,7 +578,6 @@ cxgbe_flow_parse(struct rte_flow *flow,
 		 struct rte_flow_error *e)
 {
 	int ret;
-
 	/* parse user request into ch_filter_specification */
 	ret = cxgbe_rtef_parse_attr(flow, attr, e);
 	if (ret)
@@ -606,6 +656,7 @@ cxgbe_flow_create(struct rte_eth_dev *dev,
 
 	flow->item_parser = parseitem;
 	flow->dev = dev;
+	flow->fs.private = (void *)flow;
 
 	if (cxgbe_flow_parse(flow, attr, item, action, e)) {
 		t4_os_free(flow);
@@ -660,6 +711,17 @@ static int __cxgbe_flow_destroy(struct rte_eth_dev *dev, struct rte_flow *flow)
 		return ctx.result;
 	}
 
+	fs = &flow->fs;
+	if (fs->mask.macidx) {
+		struct port_info *pi = (struct port_info *)
+					(dev->data->dev_private);
+		int ret;
+
+		ret = cxgbe_mpstcam_remove(pi, fs->val.macidx);
+		if (!ret)
+			return ret;
+	}
+
 	return 0;
 }
 
diff --git a/drivers/net/cxgbe/cxgbe_flow.h b/drivers/net/cxgbe/cxgbe_flow.h
index 0f7504745..718bf3d05 100644
--- a/drivers/net/cxgbe/cxgbe_flow.h
+++ b/drivers/net/cxgbe/cxgbe_flow.h
@@ -7,6 +7,7 @@
 
 #include <rte_flow_driver.h>
 #include "cxgbe_filter.h"
+#include "mps_tcam.h"
 #include "cxgbe.h"
 
 #define CXGBE_FLOW_POLL_US  10
diff --git a/drivers/net/cxgbe/cxgbe_main.c b/drivers/net/cxgbe/cxgbe_main.c
index 20d2de442..9c40f51b2 100644
--- a/drivers/net/cxgbe/cxgbe_main.c
+++ b/drivers/net/cxgbe/cxgbe_main.c
@@ -1342,10 +1342,8 @@ int link_start(struct port_info *pi)
 	ret = t4_set_rxmode(adapter, adapter->mbox, pi->viid, mtu, -1, -1,
 			    -1, 1, true);
 	if (ret == 0) {
-		ret = t4_change_mac(adapter, adapter->mbox, pi->viid,
-				    pi->xact_addr_filt,
-				    (u8 *)&pi->eth_dev->data->mac_addrs[0],
-				    true, true);
+		ret = cxgbe_mpstcam_modify(pi, (int)pi->xact_addr_filt,
+				(u8 *)&pi->eth_dev->data->mac_addrs[0]);
 		if (ret >= 0) {
 			pi->xact_addr_filt = ret;
 			ret = 0;
-- 
2.14.1

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

* Re: [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API
  2018-08-27 12:52 [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Rahul Lakkireddy
                   ` (3 preceding siblings ...)
  2018-08-27 12:52 ` [dpdk-dev] [PATCH 4/4] net/cxgbe: add flow operations to match based on destination MAC address Rahul Lakkireddy
@ 2018-09-13 14:03 ` Ferruh Yigit
  4 siblings, 0 replies; 6+ messages in thread
From: Ferruh Yigit @ 2018-09-13 14:03 UTC (permalink / raw)
  To: Rahul Lakkireddy, dev; +Cc: shaguna, indranil, nirranjan

On 8/27/2018 1:52 PM, Rahul Lakkireddy wrote:
> This series of patches add support to offload flows with destination MAC
> match item and VLAN push/pop/rewrite actions.
> 
> Patch 1 adds API to program and manage hardware Layer 2 Table (L2T).
> L2T holds destination node information to be used for VLAN rewrite.
> 
> Patch 2 implements offloading VLAN push/pop/rewrite actions.
> 
> Patch 3 adds API to program and manage hardware Multi Port Switch (MPS)
> table. MPS holds the destination MAC addresses to be matched against
> incoming packets.
> 
> Patch 4 implements offloading destination MAC match item.
> 
> Thanks,
> Rahul
> 
> Shagun Agrawal (4):
>   net/cxgbe: add API to program hardware layer 2 table
>   net/cxgbe: add flow operations to offload vlan actions
>   net/cxgbe: add API to program hardware MPS table
>   net/cxgbe: add flow operations to match based on destination MAC
>     address

Series applied to dpdk-next-net/master, thanks.

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

end of thread, other threads:[~2018-09-13 14:03 UTC | newest]

Thread overview: 6+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2018-08-27 12:52 [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Rahul Lakkireddy
2018-08-27 12:52 ` [dpdk-dev] [PATCH 1/4] net/cxgbe: add API to program hardware layer 2 table Rahul Lakkireddy
2018-08-27 12:52 ` [dpdk-dev] [PATCH 2/4] net/cxgbe: add flow operations to offload vlan actions Rahul Lakkireddy
2018-08-27 12:52 ` [dpdk-dev] [PATCH 3/4] net/cxgbe: add API to program hardware MPS table Rahul Lakkireddy
2018-08-27 12:52 ` [dpdk-dev] [PATCH 4/4] net/cxgbe: add flow operations to match based on destination MAC address Rahul Lakkireddy
2018-09-13 14:03 ` [dpdk-dev] [PATCH 0/4] net/cxgbe: add destination MAC match and VLAN rewrite support for flow API Ferruh Yigit

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