[dpdk-dev] [PATCH v4 10/12] virtio: Add QTest support to vtpci abstraction

Tetsuya Mukawa mukawa at igel.co.jp
Wed Mar 9 09:33:27 CET 2016


The patch adds QTest support to vtpci abstraction.
With this patch, only modern virtio device will be supported.
This QTest support will be used by later QTest extension patch of
virtio-net PMD.

Signed-off-by: Tetsuya Mukawa <mukawa at igel.co.jp>
---
 drivers/net/virtio/qtest.h         |  39 ++++
 drivers/net/virtio/virtio_ethdev.c |   2 +-
 drivers/net/virtio/virtio_pci.c    | 368 ++++++++++++++++++++++++++++++++++---
 drivers/net/virtio/virtio_pci.h    |   9 +-
 4 files changed, 387 insertions(+), 31 deletions(-)
 create mode 100644 drivers/net/virtio/qtest.h

diff --git a/drivers/net/virtio/qtest.h b/drivers/net/virtio/qtest.h
new file mode 100644
index 0000000..46b9ee6
--- /dev/null
+++ b/drivers/net/virtio/qtest.h
@@ -0,0 +1,39 @@
+/*-
+ *   BSD LICENSE
+ *
+ *   Copyright(c) 2016 IGEL Co., Ltd. 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 IGEL Co., Ltd. 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 _VIRTIO_QTEST_H_
+#define _VIRTIO_QTEST_H_
+
+#define QTEST_DRV_NAME		        "eth_qtest_virtio"
+
+#endif /* _VIRTIO_QTEST_H_ */
diff --git a/drivers/net/virtio/virtio_ethdev.c b/drivers/net/virtio/virtio_ethdev.c
index bc631c7..747596d 100644
--- a/drivers/net/virtio/virtio_ethdev.c
+++ b/drivers/net/virtio/virtio_ethdev.c
@@ -1055,7 +1055,7 @@ eth_virtio_dev_init(struct rte_eth_dev *eth_dev)
 	pci_dev = eth_dev->pci_dev;
 
 	if (virtio_dev_check(eth_dev, RTE_ETH_DEV_PCI, NULL, 0)) {
-		if (vtpci_init(pci_dev, hw) < 0)
+		if (vtpci_init(eth_dev, hw) < 0)
 			return -1;
 	}
 
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 85fbe88..e88531e 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -37,10 +37,16 @@
  #include <fcntl.h>
 #endif
 
+#include "virtio_ethdev.h"
 #include "virtio_pci.h"
 #include "virtio_logs.h"
 #include "virtqueue.h"
 
+#ifdef RTE_VIRTIO_VDEV_QTEST
+#include "qtest.h"
+#include "qtest_utils.h"
+#endif
+
 /*
  * Following macros are derived from linux/pci_regs.h, however,
  * we can't simply include that header here, as there is no such
@@ -440,6 +446,220 @@ static const struct virtio_pci_ops modern_ops = {
 };
 
 
+#ifdef RTE_VIRTIO_VDEV_QTEST
+static inline uint8_t
+qtest_read8(struct virtio_hw *hw, uint8_t *addr)
+{
+	return qtest_read(hw->qsession, (uint64_t)addr, 'b');
+}
+
+static inline void
+qtest_write8(struct virtio_hw *hw, uint8_t val, uint8_t *addr)
+{
+	return qtest_write(hw->qsession, (uint64_t)addr, val, 'b');
+}
+
+static inline uint16_t
+qtest_read16(struct virtio_hw *hw, uint16_t *addr)
+{
+	return qtest_read(hw->qsession, (uint64_t)addr, 'w');
+}
+
+static inline void
+qtest_write16(struct virtio_hw *hw, uint16_t val, uint16_t *addr)
+{
+	return qtest_write(hw->qsession, (uint64_t)addr, val, 'w');
+}
+
+static inline uint32_t
+qtest_read32(struct virtio_hw *hw, uint32_t *addr)
+{
+	return qtest_read(hw->qsession, (uint64_t)addr, 'l');
+}
+
+static inline void
+qtest_write32(struct virtio_hw *hw, uint32_t val, uint32_t *addr)
+{
+	return qtest_write(hw->qsession, (uint64_t)addr, val, 'l');
+}
+
+static inline void
+qtest_write64_twopart(struct virtio_hw *hw,
+		uint64_t val, uint32_t *lo, uint32_t *hi)
+{
+	qtest_write32(hw, val & ((1ULL << 32) - 1), lo);
+	qtest_write32(hw, val >> 32,		     hi);
+}
+
+static void
+qtest_modern_read_dev_config(struct virtio_hw *hw, size_t offset,
+		       void *dst, int length)
+{
+	int i;
+	uint8_t *p;
+	uint8_t old_gen, new_gen;
+
+	do {
+		old_gen = qtest_read8(hw, &hw->common_cfg->config_generation);
+
+		p = dst;
+		for (i = 0;  i < length; i++)
+			*p++ = qtest_read8(hw, (uint8_t *)hw->dev_cfg + offset + i);
+
+		new_gen = qtest_read8(hw, &hw->common_cfg->config_generation);
+	} while (old_gen != new_gen);
+}
+
+static void
+qtest_modern_write_dev_config(struct virtio_hw *hw, size_t offset,
+			const void *src, int length)
+{
+	int i;
+	const uint8_t *p = src;
+
+	for (i = 0;  i < length; i++)
+		qtest_write8(hw, *p++, (uint8_t *)hw->dev_cfg + offset + i);
+}
+
+static uint64_t
+qtest_modern_get_features(struct virtio_hw *hw)
+{
+	uint32_t features_lo, features_hi;
+
+	qtest_write32(hw, 0, &hw->common_cfg->device_feature_select);
+	features_lo = qtest_read32(hw, &hw->common_cfg->device_feature);
+
+	qtest_write32(hw, 1, &hw->common_cfg->device_feature_select);
+	features_hi = qtest_read32(hw, &hw->common_cfg->device_feature);
+
+	return ((uint64_t)features_hi << 32) | features_lo;
+}
+
+static void
+qtest_modern_set_features(struct virtio_hw *hw, uint64_t features)
+{
+	qtest_write32(hw, 0, &hw->common_cfg->guest_feature_select);
+	qtest_write32(hw, features & ((1ULL << 32) - 1),
+		&hw->common_cfg->guest_feature);
+
+	qtest_write32(hw, 1, &hw->common_cfg->guest_feature_select);
+	qtest_write32(hw, features >> 32,
+		&hw->common_cfg->guest_feature);
+}
+
+static uint8_t
+qtest_modern_get_status(struct virtio_hw *hw)
+{
+	return qtest_read8(hw, &hw->common_cfg->device_status);
+}
+
+static void
+qtest_modern_set_status(struct virtio_hw *hw, uint8_t status)
+{
+	qtest_write8(hw, status, &hw->common_cfg->device_status);
+}
+
+static void
+qtest_modern_reset(struct virtio_hw *hw)
+{
+	modern_set_status(hw, VIRTIO_CONFIG_STATUS_RESET);
+	modern_get_status(hw);
+}
+
+static uint8_t
+qtest_modern_get_isr(struct virtio_hw *hw)
+{
+	return qtest_read8(hw, hw->isr);
+}
+
+static uint16_t
+qtest_modern_set_config_irq(struct virtio_hw *hw, uint16_t vec)
+{
+	qtest_write16(hw, vec, &hw->common_cfg->msix_config);
+	return qtest_read16(hw, &hw->common_cfg->msix_config);
+}
+
+static uint16_t
+qtest_modern_get_queue_num(struct virtio_hw *hw, uint16_t queue_id)
+{
+	qtest_write16(hw, queue_id, &hw->common_cfg->queue_select);
+	return qtest_read16(hw, &hw->common_cfg->queue_size);
+}
+
+static void
+qtest_modern_setup_queue(struct virtio_hw *hw, struct virtqueue *vq)
+{
+	uint64_t desc_addr, avail_addr, used_addr;
+	uint16_t notify_off;
+
+	desc_addr = (uint64_t)vq->mz->addr;
+	avail_addr = desc_addr + vq->vq_nentries * sizeof(struct vring_desc);
+	used_addr = RTE_ALIGN_CEIL(avail_addr + offsetof(struct vring_avail,
+							 ring[vq->vq_nentries]),
+				   VIRTIO_PCI_VRING_ALIGN);
+
+	qtest_write16(hw, vq->vq_queue_index, &hw->common_cfg->queue_select);
+
+	qtest_write64_twopart(hw, desc_addr, &hw->common_cfg->queue_desc_lo,
+				      &hw->common_cfg->queue_desc_hi);
+	qtest_write64_twopart(hw, avail_addr, &hw->common_cfg->queue_avail_lo,
+				       &hw->common_cfg->queue_avail_hi);
+	qtest_write64_twopart(hw, used_addr, &hw->common_cfg->queue_used_lo,
+				      &hw->common_cfg->queue_used_hi);
+
+	notify_off = qtest_read16(hw, &hw->common_cfg->queue_notify_off);
+	vq->notify_addr = (void *)((uint8_t *)hw->notify_base +
+				notify_off * hw->notify_off_multiplier);
+
+	qtest_write16(hw, 1, &hw->common_cfg->queue_enable);
+
+	PMD_INIT_LOG(DEBUG, "queue %u addresses:", vq->vq_queue_index);
+	PMD_INIT_LOG(DEBUG, "\t desc_addr: %" PRIx64, desc_addr);
+	PMD_INIT_LOG(DEBUG, "\t aval_addr: %" PRIx64, avail_addr);
+	PMD_INIT_LOG(DEBUG, "\t used_addr: %" PRIx64, used_addr);
+	PMD_INIT_LOG(DEBUG, "\t notify addr: %p (notify offset: %u)",
+		vq->notify_addr, notify_off);
+}
+
+static void
+qtest_modern_del_queue(struct virtio_hw *hw, struct virtqueue *vq)
+{
+	qtest_write16(hw, vq->vq_queue_index, &hw->common_cfg->queue_select);
+
+	qtest_write64_twopart(hw, 0, &hw->common_cfg->queue_desc_lo,
+				  &hw->common_cfg->queue_desc_hi);
+	qtest_write64_twopart(hw, 0, &hw->common_cfg->queue_avail_lo,
+				  &hw->common_cfg->queue_avail_hi);
+	qtest_write64_twopart(hw, 0, &hw->common_cfg->queue_used_lo,
+				  &hw->common_cfg->queue_used_hi);
+
+	qtest_write16(hw, 0, &hw->common_cfg->queue_enable);
+}
+
+static void
+qtest_modern_notify_queue(struct virtio_hw *hw __rte_unused, struct virtqueue *vq)
+{
+	qtest_write16(hw, 1, vq->notify_addr);
+}
+
+static const struct virtio_pci_ops qtest_modern_ops = {
+	.read_dev_cfg	= qtest_modern_read_dev_config,
+	.write_dev_cfg	= qtest_modern_write_dev_config,
+	.reset		= qtest_modern_reset,
+	.get_status	= qtest_modern_get_status,
+	.set_status	= qtest_modern_set_status,
+	.get_features	= qtest_modern_get_features,
+	.set_features	= qtest_modern_set_features,
+	.get_isr	= qtest_modern_get_isr,
+	.set_config_irq	= qtest_modern_set_config_irq,
+	.get_queue_num	= qtest_modern_get_queue_num,
+	.setup_queue	= qtest_modern_setup_queue,
+	.del_queue	= qtest_modern_del_queue,
+	.notify_queue	= qtest_modern_notify_queue,
+};
+#endif /* RTE_VIRTIO_VDEV_QTEST */
+
+
 void
 vtpci_read_dev_config(struct virtio_hw *hw, size_t offset,
 		      void *dst, int length)
@@ -513,12 +733,16 @@ vtpci_irq_config(struct virtio_hw *hw, uint16_t vec)
 }
 
 static void *
-get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
+get_cfg_addr(struct rte_eth_dev *eth_dev,
+		struct virtio_hw *hw,
+		struct virtio_pci_cap *cap)
 {
+	struct rte_pci_device *pci_dev = eth_dev->pci_dev;
 	uint8_t  bar    = cap->bar;
 	uint32_t length = cap->length;
 	uint32_t offset = cap->offset;
-	uint8_t *base;
+	uint8_t *base = NULL;
+	uint64_t size = 0;
 
 	if (bar > 5) {
 		PMD_INIT_LOG(ERR, "invalid bar: %u", bar);
@@ -531,14 +755,29 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 		return NULL;
 	}
 
-	if (offset + length > dev->mem_resource[bar].len) {
+	if (virtio_dev_check(eth_dev, RTE_ETH_DEV_PCI, NULL, 0)) {
+		size = pci_dev->mem_resource[bar].len;
+		base = pci_dev->mem_resource[bar].addr;
+	}
+#ifdef RTE_VIRTIO_VDEV_QTEST
+	else if (virtio_dev_check(eth_dev, RTE_ETH_DEV_VIRTUAL,
+				QTEST_DRV_NAME, 0)) {
+		qtest_get_bar_size(hw->qsession,
+				"virtio-net", bar, &size);
+		qtest_get_bar_addr(hw->qsession,
+				"virtio-net", bar, (uint64_t **)&base);
+	}
+#else
+	RTE_SET_USED(hw);
+#endif
+
+	if (offset + length > size) {
 		PMD_INIT_LOG(ERR,
 			"invalid cap: overflows bar space: %u > %" PRIu64,
-			offset + length, dev->mem_resource[bar].len);
+			offset + length, size);
 		return NULL;
 	}
 
-	base = dev->mem_resource[bar].addr;
 	if (base == NULL) {
 		PMD_INIT_LOG(ERR, "bar %u base addr is NULL", bar);
 		return NULL;
@@ -548,25 +787,49 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 }
 
 static int
-virtio_read_caps(struct rte_pci_device *dev, struct virtio_hw *hw)
+virtio_read_pci_config(struct rte_eth_dev *eth_dev,
+			struct virtio_hw *hw,
+			void *buf, size_t len, off_t offset)
 {
+	struct rte_pci_device *pci_dev = eth_dev->pci_dev;
+	int ret = -1;
+
+	if (virtio_dev_check(eth_dev, RTE_ETH_DEV_PCI, NULL, 0))
+		ret = rte_eal_pci_read_config(pci_dev, buf, len, offset);
+#ifdef RTE_VIRTIO_VDEV_QTEST
+	else if (virtio_dev_check(eth_dev, RTE_ETH_DEV_VIRTUAL,
+				QTEST_DRV_NAME, 0))
+		ret = qtest_read_pci_cfg(hw->qsession,
+				"virtio-net", buf, len, offset);
+#else
+	RTE_SET_USED(hw);
+#endif
+
+	return ret;
+}
+
+static int
+virtio_read_caps(struct rte_eth_dev *eth_dev, struct virtio_hw *hw)
+{
+	struct rte_pci_device *pci_dev = eth_dev->pci_dev;
 	uint8_t pos;
 	struct virtio_pci_cap cap;
 	int ret;
 
-	if (rte_eal_pci_map_device(dev)) {
+	if ((eth_dev->dev_type == RTE_ETH_DEV_PCI) &&
+			(rte_eal_pci_map_device(pci_dev) < 0)) {
 		PMD_INIT_LOG(DEBUG, "failed to map pci device!");
 		return -1;
 	}
 
-	ret = rte_eal_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
+	ret = virtio_read_pci_config(eth_dev, hw, &pos, 1, PCI_CAPABILITY_LIST);
 	if (ret < 0) {
 		PMD_INIT_LOG(DEBUG, "failed to read pci capability list");
 		return -1;
 	}
 
 	while (pos) {
-		ret = rte_eal_pci_read_config(dev, &cap, sizeof(cap), pos);
+		ret = virtio_read_pci_config(eth_dev, hw, &cap, sizeof(cap), pos);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR,
 				"failed to read pci cap at pos: %x", pos);
@@ -586,18 +849,19 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_hw *hw)
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
-			hw->common_cfg = get_cfg_addr(dev, &cap);
+			hw->common_cfg = get_cfg_addr(eth_dev, hw, &cap);
 			break;
 		case VIRTIO_PCI_CAP_NOTIFY_CFG:
-			rte_eal_pci_read_config(dev, &hw->notify_off_multiplier,
+			virtio_read_pci_config(eth_dev, hw,
+						&hw->notify_off_multiplier,
 						4, pos + sizeof(cap));
-			hw->notify_base = get_cfg_addr(dev, &cap);
+			hw->notify_base = get_cfg_addr(eth_dev, hw, &cap);
 			break;
 		case VIRTIO_PCI_CAP_DEVICE_CFG:
-			hw->dev_cfg = get_cfg_addr(dev, &cap);
+			hw->dev_cfg = get_cfg_addr(eth_dev, hw, &cap);
 			break;
 		case VIRTIO_PCI_CAP_ISR_CFG:
-			hw->isr = get_cfg_addr(dev, &cap);
+			hw->isr = get_cfg_addr(eth_dev, hw, &cap);
 			break;
 		}
 
@@ -622,31 +886,77 @@ next:
 	return 0;
 }
 
+static int
+vtpci_modern_init(struct rte_eth_dev *eth_dev, struct virtio_hw *hw)
+{
+	struct rte_pci_device *pci_dev = eth_dev->pci_dev;
+
+	PMD_INIT_LOG(INFO, "modern virtio pci detected.");
+
+	if (virtio_dev_check(eth_dev, RTE_ETH_DEV_PCI, NULL, 0)) {
+		hw->vtpci_ops = &modern_ops;
+		pci_dev->driver->drv_flags |= RTE_PCI_DRV_INTR_LSC;
+	}
+#ifdef RTE_VIRTIO_VDEV_QTEST
+	else if (virtio_dev_check(eth_dev, RTE_ETH_DEV_VIRTUAL, NULL, 0)) {
+		hw->vtpci_ops = &qtest_modern_ops;
+		eth_dev->data->dev_flags |= RTE_ETH_DEV_INTR_LSC;
+	}
+#endif
+
+	hw->modern = 1;
+
+	return 0;
+}
+
+static int
+vtpci_legacy_init(struct rte_eth_dev *eth_dev, struct virtio_hw *hw)
+{
+	struct rte_pci_device *pci_dev = eth_dev->pci_dev;
+	struct virtio_pci_cap cap;
+
+	PMD_INIT_LOG(INFO, "trying with legacy virtio pci.");
+	if (virtio_dev_check(eth_dev, RTE_ETH_DEV_PCI, NULL, 0)) {
+		if (legacy_virtio_resource_init(pci_dev, hw) < 0)
+			return -1;
+
+		hw->vtpci_ops = &legacy_ops;
+		hw->use_msix = legacy_virtio_has_msix(&pci_dev->addr);
+	}
+#ifdef RTE_VIRTIO_VDEV_QTEST
+	else if (virtio_dev_check(eth_dev, RTE_ETH_DEV_VIRTUAL,
+				QTEST_DRV_NAME, 0)) {
+		PMD_INIT_LOG(ERR, "Legacy virtio device isn't supported.");
+		return -1;
+	}
+#endif
+
+	cap.bar = cap.length = cap.offset = 0;
+	hw->modern = 0;
+
+	return 0;
+}
+
 int
-vtpci_init(struct rte_pci_device *dev, struct virtio_hw *hw)
+vtpci_init(struct rte_eth_dev *eth_dev, struct virtio_hw *hw)
 {
-	hw->dev = dev;
+	struct rte_pci_device *pci_dev = eth_dev->pci_dev;
+	int ret;
+
+	hw->dev = pci_dev;
 
 	/*
 	 * Try if we can succeed reading virtio pci caps, which exists
 	 * only on modern pci device. If failed, we fallback to legacy
 	 * virtio handling.
 	 */
-	if (virtio_read_caps(dev, hw) == 0) {
-		PMD_INIT_LOG(INFO, "modern virtio pci detected.");
-		hw->vtpci_ops = &modern_ops;
-		hw->modern    = 1;
-		dev->driver->drv_flags |= RTE_PCI_DRV_INTR_LSC;
-		return 0;
-	}
+	if (virtio_read_caps(eth_dev, hw) == 0)
+		ret = vtpci_modern_init(eth_dev, hw);
+	else
+		ret = vtpci_legacy_init(eth_dev, hw);
 
-	PMD_INIT_LOG(INFO, "trying with legacy virtio pci.");
-	if (legacy_virtio_resource_init(dev, hw) < 0)
+	if (ret < 0)
 		return -1;
 
-	hw->vtpci_ops = &legacy_ops;
-	hw->use_msix = legacy_virtio_has_msix(&dev->addr);
-	hw->modern   = 0;
-
 	return 0;
 }
diff --git a/drivers/net/virtio/virtio_pci.h b/drivers/net/virtio/virtio_pci.h
index ae6777d..9eb210c 100644
--- a/drivers/net/virtio/virtio_pci.h
+++ b/drivers/net/virtio/virtio_pci.h
@@ -39,6 +39,10 @@
 #include <rte_pci.h>
 #include <rte_ethdev.h>
 
+#ifdef RTE_VIRTIO_VDEV_QTEST
+#include "qtest_utils.h"
+#endif /* RTE_VIRTIO_VDEV_QTEST */
+
 struct virtqueue;
 
 /* VirtIO PCI vendor/device ID. */
@@ -242,6 +246,9 @@ struct virtio_net_config;
 
 struct virtio_hw {
 	struct virtqueue *cvq;
+#ifdef RTE_VIRTIO_VDEV_QTEST
+	struct qtest_session *qsession;
+#endif
 	struct rte_pci_ioport io;
 	uint64_t    guest_features;
 	uint32_t    max_tx_queues;
@@ -306,7 +313,7 @@ vtpci_with_feature(struct virtio_hw *hw, uint64_t bit)
 /*
  * Function declaration from virtio_pci.c
  */
-int vtpci_init(struct rte_pci_device *, struct virtio_hw *);
+int vtpci_init(struct rte_eth_dev *, struct virtio_hw *);
 void vtpci_reset(struct virtio_hw *);
 
 void vtpci_reinit_complete(struct virtio_hw *);
-- 
2.1.4



More information about the dev mailing list