mail archive of the barebox mailing list
 help / color / mirror / Atom feed
* [PATCH v2 0/4] video: add support for QEMU ramfb
@ 2023-01-30  7:27 Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 1/4] fs: devfs: implement cdev_fdopen Ahmad Fatoum
                   ` (4 more replies)
  0 siblings, 5 replies; 6+ messages in thread
From: Ahmad Fatoum @ 2023-01-30  7:27 UTC (permalink / raw)
  To: barebox; +Cc: Adrian Negreanu, Ahmad Fatoum

QEMU's ramfb is a very simple Qemu fw_cfg protocol, where the guest
need only write a video settings structure to /etc/ramfb to get
DMA from the framebuffer working. Add a driver for this on top
of a newly added character device interface.

Adrian Negreanu (1):
  video: add support for QEMU ramfb

Ahmad Fatoum (3):
  fs: devfs: implement cdev_fdopen
  asm-generic: avoid compiler warnings due to PCI_IOBASE
  firmware: add QEMU FW CFG driver

 drivers/firmware/Kconfig         |  10 +
 drivers/firmware/Makefile        |   1 +
 drivers/firmware/qemu_fw_cfg.c   | 307 +++++++++++++++++++++++++++++++
 drivers/video/Kconfig            |   6 +
 drivers/video/Makefile           |   1 +
 drivers/video/ramfb.c            | 191 +++++++++++++++++++
 fs/devfs-core.c                  |  20 ++
 include/asm-generic/io.h         |   3 +-
 include/driver.h                 |   1 +
 include/filetype.h               |   1 +
 include/uapi/linux/qemu_fw_cfg.h | 100 ++++++++++
 11 files changed, 640 insertions(+), 1 deletion(-)
 create mode 100644 drivers/firmware/qemu_fw_cfg.c
 create mode 100644 drivers/video/ramfb.c
 create mode 100644 include/uapi/linux/qemu_fw_cfg.h

-- 
2.38.1




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

* [PATCH v2 1/4] fs: devfs: implement cdev_fdopen
  2023-01-30  7:27 [PATCH v2 0/4] video: add support for QEMU ramfb Ahmad Fatoum
@ 2023-01-30  7:27 ` Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 2/4] asm-generic: avoid compiler warnings due to PCI_IOBASE Ahmad Fatoum
                   ` (3 subsequent siblings)
  4 siblings, 0 replies; 6+ messages in thread
From: Ahmad Fatoum @ 2023-01-30  7:27 UTC (permalink / raw)
  To: barebox; +Cc: Adrian Negreanu, Ahmad Fatoum

As an alternative to cdev_open and using cdev_read/write, we define a
new cdev_fdopen function that returns a file descriptor. The benefit of
this is that code using it may use all the more high level helpers we
have for reading/writing file descriptors.

Signed-off-by: Ahmad Fatoum <ahmad@a3f.at>
---
 fs/devfs-core.c  | 20 ++++++++++++++++++++
 include/driver.h |  1 +
 2 files changed, 21 insertions(+)

diff --git a/fs/devfs-core.c b/fs/devfs-core.c
index 2a259c2fe0ef..fbcf68e81597 100644
--- a/fs/devfs-core.c
+++ b/fs/devfs-core.c
@@ -177,6 +177,26 @@ int cdev_open(struct cdev *cdev, unsigned long flags)
 	return 0;
 }
 
+int cdev_fdopen(struct cdev *cdev, unsigned long flags)
+{
+	char *path;
+	int fd;
+
+	if (!cdev)
+		return -ENODEV;
+	if (IS_ERR(cdev))
+		return PTR_ERR(cdev);
+
+	path = basprintf("/dev/%s", cdev->name);
+	if (!path)
+		return -ENOMEM;
+
+	fd = open(path, flags);
+
+	free(path);
+	return fd;
+}
+
 struct cdev *cdev_open_by_name(const char *name, unsigned long flags)
 {
 	struct cdev *cdev;
diff --git a/include/driver.h b/include/driver.h
index f0a0b9d6ae8f..f53668711b81 100644
--- a/include/driver.h
+++ b/include/driver.h
@@ -535,6 +535,7 @@ struct cdev *cdev_open_by_name(const char *name, unsigned long flags);
 struct cdev *cdev_create_loop(const char *path, ulong flags, loff_t offset);
 void cdev_remove_loop(struct cdev *cdev);
 int cdev_open(struct cdev *, unsigned long flags);
+int cdev_fdopen(struct cdev *cdev, unsigned long flags);
 void cdev_close(struct cdev *cdev);
 int cdev_flush(struct cdev *cdev);
 ssize_t cdev_read(struct cdev *cdev, void *buf, size_t count, loff_t offset, ulong flags);
-- 
2.38.1




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

* [PATCH v2 2/4] asm-generic: avoid compiler warnings due to PCI_IOBASE
  2023-01-30  7:27 [PATCH v2 0/4] video: add support for QEMU ramfb Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 1/4] fs: devfs: implement cdev_fdopen Ahmad Fatoum
@ 2023-01-30  7:27 ` Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 3/4] firmware: add QEMU FW CFG driver Ahmad Fatoum
                   ` (2 subsequent siblings)
  4 siblings, 0 replies; 6+ messages in thread
From: Ahmad Fatoum @ 2023-01-30  7:27 UTC (permalink / raw)
  To: barebox; +Cc: Adrian Negreanu, Ahmad Fatoum

Some GCC versions take offence at PCI_IOBASE's default value of 0.
Hide warnings about this.

Signed-off-by: Ahmad Fatoum <ahmad@a3f.at>
---
 include/asm-generic/io.h | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/include/asm-generic/io.h b/include/asm-generic/io.h
index acb70509d168..6e91c0aea68f 100644
--- a/include/asm-generic/io.h
+++ b/include/asm-generic/io.h
@@ -12,6 +12,7 @@
 #define __ASM_GENERIC_IO_H
 
 #include <linux/string.h> /* for memset() and memcpy() */
+#include <linux/compiler.h>
 #include <linux/types.h>
 #include <asm/byteorder.h>
 
@@ -86,7 +87,7 @@ static inline void __raw_writeq(u64 b, volatile void __iomem *addr)
 #endif
 
 #ifndef PCI_IOBASE
-#define PCI_IOBASE ((void __iomem *)0)
+#define PCI_IOBASE ((void __iomem *)RELOC_HIDE((void *)0, 0))
 #endif
 
 #ifndef IO_SPACE_LIMIT
-- 
2.38.1




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

* [PATCH v2 3/4] firmware: add QEMU FW CFG driver
  2023-01-30  7:27 [PATCH v2 0/4] video: add support for QEMU ramfb Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 1/4] fs: devfs: implement cdev_fdopen Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 2/4] asm-generic: avoid compiler warnings due to PCI_IOBASE Ahmad Fatoum
@ 2023-01-30  7:27 ` Ahmad Fatoum
  2023-01-30  7:27 ` [PATCH v2 4/4] video: add support for QEMU ramfb Ahmad Fatoum
  2023-01-31  8:19 ` [PATCH v2 0/4] " Sascha Hauer
  4 siblings, 0 replies; 6+ messages in thread
From: Ahmad Fatoum @ 2023-01-30  7:27 UTC (permalink / raw)
  To: barebox; +Cc: Adrian Negreanu, Ahmad Fatoum

Quoting the QEMU Docs[1]:

  The QEMU Firmware Configuration (fw_cfg) Device allows the guest to
  retrieve various data items (blobs) that can influence how the firmware
  configures itself, or may contain tables to be installed for the guest OS.
  Examples include device boot order, ACPI and SMBIOS tables, virtual
  machine UUID, SMP and NUMA information, kernel/initrd images for
  direct (Linux) kernel booting, etc.

The driver added here is mostly based on the Linux driver.

[1]: https://www.qemu.org/docs/master/specs/fw_cfg.html
Signed-off-by: Ahmad Fatoum <ahmad@a3f.at>
---
v1 -> v2:
  - split off into own file
  - add cdev/fd API
  - DMA map written buffers
  - reuse kernel headers and part of kernel code
  - handle unaligned buffers correctly
---
 drivers/firmware/Kconfig         |  10 +
 drivers/firmware/Makefile        |   1 +
 drivers/firmware/qemu_fw_cfg.c   | 307 +++++++++++++++++++++++++++++++
 include/filetype.h               |   1 +
 include/uapi/linux/qemu_fw_cfg.h | 100 ++++++++++
 5 files changed, 419 insertions(+)
 create mode 100644 drivers/firmware/qemu_fw_cfg.c
 create mode 100644 include/uapi/linux/qemu_fw_cfg.h

diff --git a/drivers/firmware/Kconfig b/drivers/firmware/Kconfig
index d3cca41a7e8f..a6c564320eff 100644
--- a/drivers/firmware/Kconfig
+++ b/drivers/firmware/Kconfig
@@ -32,4 +32,14 @@ config ARM_SCMI_PROTOCOL
 	  set of operating system-independent software interfaces that are
 	  used in system management.
 
+config QEMU_FW_CFG
+	bool "QEMU FW CFG interface"
+	help
+	  This driver exposes the QEMU FW CFG conduit as a single
+	  character device.
+
+	  The selector key can be set via ioctl or device parameter
+	  and read/writes are translated to the MMIO/IO port appropriate
+	  for the platform.
+
 endmenu
diff --git a/drivers/firmware/Makefile b/drivers/firmware/Makefile
index 26d6f3275ae1..90f5113f532e 100644
--- a/drivers/firmware/Makefile
+++ b/drivers/firmware/Makefile
@@ -2,4 +2,5 @@
 obj-$(CONFIG_FIRMWARE_ALTERA_SERIAL) += altera_serial.o
 obj-$(CONFIG_FIRMWARE_ALTERA_SOCFPGA) += socfpga.o socfpga_sdr.o
 obj-$(CONFIG_FIRMWARE_ZYNQMP_FPGA) += zynqmp-fpga.o
+obj-$(CONFIG_QEMU_FW_CFG) += qemu_fw_cfg.o
 obj-y += arm_scmi/
diff --git a/drivers/firmware/qemu_fw_cfg.c b/drivers/firmware/qemu_fw_cfg.c
new file mode 100644
index 000000000000..3fad90bbded2
--- /dev/null
+++ b/drivers/firmware/qemu_fw_cfg.c
@@ -0,0 +1,307 @@
+// SPDX-License-Identifier: GPL-2.0-or-later
+/*
+ * qemu_fw_cfg.c - QEMU FW CFG character device
+ *
+ * Copyright (C) 2022 Adrian Negreanu
+ * Copyright (C) 2022 Ahmad Fatoum
+ */
+
+#include <common.h>
+#include <driver.h>
+#include <init.h>
+#include <fcntl.h>
+#include <dma.h>
+#include <linux/err.h>
+#include <linux/bitfield.h>
+#include <linux/qemu_fw_cfg.h>
+#include <asm/unaligned.h>
+#include <io-64-nonatomic-lo-hi.h>
+
+/* arch-specific ctrl & data register offsets are not available in ACPI, DT */
+#ifdef CONFIG_X86
+# define FW_CFG_CTRL_OFF 0x00
+# define FW_CFG_DATA_OFF 0x01
+# define FW_CFG_DMA_OFF 0x04
+#else
+# define FW_CFG_CTRL_OFF 0x08
+# define FW_CFG_DATA_OFF 0x00
+# define FW_CFG_DMA_OFF 0x10
+#endif
+
+/* fw_cfg DMA commands */
+#define FW_CFG_DMA_CTL_ERROR   0x01
+#define FW_CFG_DMA_CTL_READ    0x02
+#define FW_CFG_DMA_CTL_SKIP    0x04
+#define FW_CFG_DMA_CTL_SELECT  0x08
+#define FW_CFG_DMA_CTL_WRITE   0x10
+
+struct fw_cfg_dma {
+	__be32 control;
+	__be32 length;
+	__be64 address;
+} __packed;
+
+/* fw_cfg device i/o register addresses */
+struct fw_cfg {
+	struct resource *iores;
+	void __iomem *reg_ctrl;
+	void __iomem *reg_data;
+	void __iomem *reg_dma;
+	struct cdev cdev;
+	loff_t next_read_offset;
+	u32 sel;
+	bool is_mmio;
+	struct fw_cfg_dma __iomem *acc_virt;
+	dma_addr_t acc_dma;
+};
+
+static struct fw_cfg *to_fw_cfg(struct cdev *cdev)
+{
+	return container_of(cdev, struct fw_cfg, cdev);
+}
+
+/* pick appropriate endianness for selector key */
+static void fw_cfg_select(struct fw_cfg *fw_cfg)
+{
+	if (fw_cfg->is_mmio)
+		iowrite16be(fw_cfg->sel, fw_cfg->reg_ctrl);
+	else
+		iowrite16(fw_cfg->sel, fw_cfg->reg_ctrl);
+}
+
+/* clean up fw_cfg device i/o */
+static void fw_cfg_io_cleanup(struct fw_cfg *fw_cfg)
+{
+	release_region(fw_cfg->iores);
+}
+
+static int fw_cfg_ioctl(struct cdev *cdev, int request, void *buf)
+{
+	struct fw_cfg *fw_cfg = to_fw_cfg(cdev);
+	int ret = 0;
+
+	switch (request) {
+	case FW_CFG_SELECT:
+		fw_cfg->sel = *(u16 *)buf;
+		break;
+	default:
+		ret = -ENOTTY;
+	}
+
+	return 0;
+}
+
+#define __raw_readu64 __raw_readq
+#define __raw_readu32 __raw_readl
+#define __raw_readu16 __raw_readw
+#define __raw_readu8 __raw_readb
+
+#define fw_cfg_data_read_sized(fw_cfg, remaining, address, type) do {	\
+	while (*remaining >= sizeof(type)) {				\
+		val = __raw_read##type((fw_cfg)->reg_data);		\
+		*remaining -= sizeof(type);				\
+		if (*address) {						\
+			put_unaligned(val, (type *)*address);		\
+			*address += sizeof(type);			\
+		}							\
+	}								\
+} while(0)
+
+static void fw_cfg_data_read(struct fw_cfg *fw_cfg, void *address, size_t remaining,
+			     unsigned rdsize)
+{
+
+	u64 val;
+
+	if (fw_cfg->is_mmio) {
+		/*
+		 * This is just a preference. If we can't honour it, we
+		 * fall back to byte-sized copy
+		 */
+		switch(rdsize) {
+		case 8:
+#ifdef CONFIG_64BIT
+			fw_cfg_data_read_sized(fw_cfg, &remaining, &address, u64);
+			break;
+#endif
+		case 4:
+			fw_cfg_data_read_sized(fw_cfg, &remaining, &address, u32);
+			break;
+		case 2:
+			fw_cfg_data_read_sized(fw_cfg, &remaining, &address, u16);
+			break;
+		}
+	}
+
+	fw_cfg_data_read_sized(fw_cfg, &remaining, &address, u8);
+}
+
+static ssize_t fw_cfg_read(struct cdev *cdev, void *buf, size_t count,
+			   loff_t pos, unsigned long flags)
+{
+	struct fw_cfg *fw_cfg = to_fw_cfg(cdev);
+	unsigned rdsize = FIELD_GET(O_RWSIZE_MASK, flags);
+
+	if (!pos || pos != fw_cfg->next_read_offset) {
+		fw_cfg_select(fw_cfg);
+		fw_cfg->next_read_offset = 0;
+	}
+
+	if (!rdsize) {
+		if (pos % 8 == 0)
+			rdsize = 8;
+		else if (pos % 4 == 0)
+			rdsize = 4;
+		else if (pos % 2 == 0)
+			rdsize = 2;
+		else
+			rdsize = 1;
+	}
+
+	while (pos-- > fw_cfg->next_read_offset)
+		fw_cfg_data_read(fw_cfg, NULL, count, rdsize);
+
+	fw_cfg_data_read(fw_cfg, buf, count, rdsize);
+
+	fw_cfg->next_read_offset += count;
+	return count;
+}
+
+static ssize_t fw_cfg_write(struct cdev *cdev, const void *buf, size_t count,
+			    loff_t pos, unsigned long flags)
+{
+	struct fw_cfg *fw_cfg = to_fw_cfg(cdev);
+	struct device_d *dev = cdev->dev;
+	struct fw_cfg_dma __iomem *acc = fw_cfg->acc_virt;
+	dma_addr_t mapping;
+
+	if (pos != 0)
+		return -EINVAL;
+
+	mapping = dma_map_single(dev, (void *)buf, count, DMA_TO_DEVICE);
+	if (dma_mapping_error(dev, mapping))
+		return -EFAULT;
+
+	fw_cfg->next_read_offset = 0;
+
+	acc->address = cpu_to_be64(mapping);
+	acc->length = cpu_to_be32(count);
+	acc->control = cpu_to_be32(FW_CFG_DMA_CTL_WRITE |
+				   FW_CFG_DMA_CTL_SELECT | fw_cfg->sel << 16);
+
+	iowrite64be(fw_cfg->acc_dma, fw_cfg->reg_dma);
+
+	while (ioread32be(&acc->control) & ~FW_CFG_DMA_CTL_ERROR)
+		;
+
+	dma_unmap_single(dev, mapping, count, DMA_FROM_DEVICE);
+
+	return count;
+}
+
+static struct cdev_operations fw_cfg_ops = {
+	.read = fw_cfg_read,
+	.write = fw_cfg_write,
+	.ioctl = fw_cfg_ioctl,
+};
+
+static int fw_cfg_param_select(struct param_d *p, void *priv)
+{
+	struct fw_cfg *fw_cfg = priv;
+
+	return fw_cfg->sel <= U16_MAX ? 0 : -EINVAL;
+}
+
+static int fw_cfg_probe(struct device_d *dev)
+{
+	struct device_node *np = dev_of_node(dev);
+	struct resource *parent_res, *iores;
+	char sig[FW_CFG_SIG_SIZE];
+	struct fw_cfg *fw_cfg;
+	int ret;
+
+	fw_cfg = xzalloc(sizeof(*fw_cfg));
+
+	/* acquire i/o range details */
+	fw_cfg->is_mmio = false;
+	iores = dev_get_resource(dev, IORESOURCE_IO, 0);
+	if (IS_ERR(iores)) {
+		fw_cfg->is_mmio = true;
+		iores = dev_get_resource(dev, IORESOURCE_MEM, 0);
+		if (IS_ERR(iores))
+			return -EINVAL;
+	}
+
+	parent_res = fw_cfg->is_mmio ? &iomem_resource : &ioport_resource;
+	iores = __request_region(parent_res, iores->start, iores->end, dev_name(dev), 0);
+	if (IS_ERR(iores))
+		return -EBUSY;
+
+	/* use architecture-specific offsets */
+	fw_cfg->reg_ctrl = IOMEM(iores->start + FW_CFG_CTRL_OFF);
+	fw_cfg->reg_data = IOMEM(iores->start + FW_CFG_DATA_OFF);
+	fw_cfg->reg_dma  = IOMEM(iores->start + FW_CFG_DMA_OFF);
+
+	fw_cfg->iores = iores;
+
+	/* verify fw_cfg device signature */
+	fw_cfg->sel = FW_CFG_SIGNATURE;
+	fw_cfg_read(&fw_cfg->cdev, sig, FW_CFG_SIG_SIZE, 0, 0);
+
+	if (memcmp(sig, "QEMU", FW_CFG_SIG_SIZE) != 0) {
+		ret = np ? -EILSEQ : -ENODEV;
+		goto err;
+	}
+
+	fw_cfg->acc_virt = dma_alloc_coherent(sizeof(*fw_cfg->acc_virt), &fw_cfg->acc_dma);
+
+	fw_cfg->cdev.name = basprintf("fw_cfg%d", cdev_find_free_index("fw_cfg"));
+	fw_cfg->cdev.flags = DEVFS_IS_CHARACTER_DEV;
+	fw_cfg->cdev.size = 0;
+	fw_cfg->cdev.ops = &fw_cfg_ops;
+	fw_cfg->cdev.dev = dev;
+	fw_cfg->cdev.filetype = filetype_qemu_fw_cfg;
+
+	dev_set_name(dev, fw_cfg->cdev.name);
+
+	ret = devfs_create(&fw_cfg->cdev);
+	if (ret) {
+		dev_err(dev, "Failed to create corresponding cdev\n");
+		goto err;
+	}
+
+	cdev_create_default_automount(&fw_cfg->cdev);
+
+	dev_add_param_uint32(dev, "selector", fw_cfg_param_select,
+			     NULL, &fw_cfg->sel, "%u", fw_cfg);
+
+	dev->priv = fw_cfg;
+
+	return 0;
+err:
+	fw_cfg_io_cleanup(fw_cfg);
+	return ret;
+}
+
+static const struct of_device_id qemu_fw_cfg_of_match[] = {
+	{ .compatible = "qemu,fw-cfg-mmio", },
+	{ /* sentinel */ },
+};
+
+static struct driver_d qemu_fw_cfg_drv = {
+	.name = "fw_cfg",
+	.probe  = fw_cfg_probe,
+	.of_compatible = of_match_ptr(qemu_fw_cfg_of_match),
+};
+
+static int qemu_fw_cfg_init(void)
+{
+	int ret;
+
+	ret = platform_driver_register(&qemu_fw_cfg_drv);
+	if (ret)
+		return ret;
+
+	return of_devices_ensure_probed_by_dev_id(qemu_fw_cfg_of_match);
+}
+postmmu_initcall(qemu_fw_cfg_init);
diff --git a/include/filetype.h b/include/filetype.h
index 00d54e48d528..1a7d145555b1 100644
--- a/include/filetype.h
+++ b/include/filetype.h
@@ -58,6 +58,7 @@ enum filetype {
 	filetype_mxs_sd_image,
 	filetype_rockchip_rkns_image,
 	filetype_fip,
+	filetype_qemu_fw_cfg,
 	filetype_max,
 };
 
diff --git a/include/uapi/linux/qemu_fw_cfg.h b/include/uapi/linux/qemu_fw_cfg.h
new file mode 100644
index 000000000000..97a720c383cc
--- /dev/null
+++ b/include/uapi/linux/qemu_fw_cfg.h
@@ -0,0 +1,100 @@
+/* SPDX-License-Identifier: BSD-3-Clause */
+#ifndef _LINUX_FW_CFG_H
+#define _LINUX_FW_CFG_H
+
+#include <linux/types.h>
+#include <ioctl.h>
+
+#define FW_CFG_ACPI_DEVICE_ID	"QEMU0002"
+
+/* selector key values for "well-known" fw_cfg entries */
+#define FW_CFG_SIGNATURE	0x00
+#define FW_CFG_ID		0x01
+#define FW_CFG_UUID		0x02
+#define FW_CFG_RAM_SIZE		0x03
+#define FW_CFG_NOGRAPHIC	0x04
+#define FW_CFG_NB_CPUS		0x05
+#define FW_CFG_MACHINE_ID	0x06
+#define FW_CFG_KERNEL_ADDR	0x07
+#define FW_CFG_KERNEL_SIZE	0x08
+#define FW_CFG_KERNEL_CMDLINE	0x09
+#define FW_CFG_INITRD_ADDR	0x0a
+#define FW_CFG_INITRD_SIZE	0x0b
+#define FW_CFG_BOOT_DEVICE	0x0c
+#define FW_CFG_NUMA		0x0d
+#define FW_CFG_BOOT_MENU	0x0e
+#define FW_CFG_MAX_CPUS		0x0f
+#define FW_CFG_KERNEL_ENTRY	0x10
+#define FW_CFG_KERNEL_DATA	0x11
+#define FW_CFG_INITRD_DATA	0x12
+#define FW_CFG_CMDLINE_ADDR	0x13
+#define FW_CFG_CMDLINE_SIZE	0x14
+#define FW_CFG_CMDLINE_DATA	0x15
+#define FW_CFG_SETUP_ADDR	0x16
+#define FW_CFG_SETUP_SIZE	0x17
+#define FW_CFG_SETUP_DATA	0x18
+#define FW_CFG_FILE_DIR		0x19
+
+#define FW_CFG_FILE_FIRST	0x20
+#define FW_CFG_FILE_SLOTS_MIN	0x10
+
+#define FW_CFG_WRITE_CHANNEL	0x4000
+#define FW_CFG_ARCH_LOCAL	0x8000
+#define FW_CFG_ENTRY_MASK	(~(FW_CFG_WRITE_CHANNEL | FW_CFG_ARCH_LOCAL))
+
+#define FW_CFG_INVALID		0xffff
+
+/* width in bytes of fw_cfg control register */
+#define FW_CFG_CTL_SIZE		0x02
+
+/* fw_cfg "file name" is up to 56 characters (including terminating nul) */
+#define FW_CFG_MAX_FILE_PATH	56
+
+/* size in bytes of fw_cfg signature */
+#define FW_CFG_SIG_SIZE 4
+
+/* FW_CFG_ID bits */
+#define FW_CFG_VERSION		0x01
+#define FW_CFG_VERSION_DMA	0x02
+
+/* fw_cfg file directory entry type */
+struct fw_cfg_file {
+	__be32 size;
+	__be16 select;
+	__u16 reserved;
+	char name[FW_CFG_MAX_FILE_PATH];
+};
+
+/* FW_CFG_DMA_CONTROL bits */
+#define FW_CFG_DMA_CTL_ERROR	0x01
+#define FW_CFG_DMA_CTL_READ	0x02
+#define FW_CFG_DMA_CTL_SKIP	0x04
+#define FW_CFG_DMA_CTL_SELECT	0x08
+#define FW_CFG_DMA_CTL_WRITE	0x10
+
+#define FW_CFG_DMA_SIGNATURE    0x51454d5520434647ULL /* "QEMU CFG" */
+
+/* Control as first field allows for different structures selected by this
+ * field, which might be useful in the future
+ */
+struct fw_cfg_dma_access {
+	__be32 control;
+	__be32 length;
+	__be64 address;
+};
+
+#define FW_CFG_VMCOREINFO_FILENAME "etc/vmcoreinfo"
+
+#define FW_CFG_VMCOREINFO_FORMAT_NONE 0x0
+#define FW_CFG_VMCOREINFO_FORMAT_ELF 0x1
+
+struct fw_cfg_vmcoreinfo {
+	__le16 host_format;
+	__le16 guest_format;
+	__le32 size;
+	__le64 paddr;
+};
+
+#define FW_CFG_SELECT		_IOW('Q', 1, __u16)
+
+#endif
-- 
2.38.1




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

* [PATCH v2 4/4] video: add support for QEMU ramfb
  2023-01-30  7:27 [PATCH v2 0/4] video: add support for QEMU ramfb Ahmad Fatoum
                   ` (2 preceding siblings ...)
  2023-01-30  7:27 ` [PATCH v2 3/4] firmware: add QEMU FW CFG driver Ahmad Fatoum
@ 2023-01-30  7:27 ` Ahmad Fatoum
  2023-01-31  8:19 ` [PATCH v2 0/4] " Sascha Hauer
  4 siblings, 0 replies; 6+ messages in thread
From: Ahmad Fatoum @ 2023-01-30  7:27 UTC (permalink / raw)
  To: barebox; +Cc: Adrian Negreanu

From: Adrian Negreanu <adrian.negreanu@nxp.com>

QEMU's ramfb is a very simple Qemu fw_cfg protocol, where the guest
need only write a video settings structure to /etc/ramfb to get
DMA from the framebuffer working. We don't yet have FS support
for fw_cfg, so we use the character device interface.

As barebox display mode handling only supports selecting predefined
modes and has no accommodation yet for arbitrary resolution support
like on QEMU, for now we just provide a fixed 640x480@XRGB8888 mode.

Tested with:

	qemu-system-aarch64 -M virt -vga none -device ramfb \
		-kernel images/barebox-dt-2nd.img -cpu cortex-a57 -serial mon:stdio

Signed-off-by: Adrian Negreanu <adrian.negreanu@nxp.com>
Signed-off-by: Ahmad Fatoum <a.fatoum@pengutronix.de>
---
v1 -> v2:
  - rebased on new /dev/fw_cfg API
  - remove Kconfig resolution setup as no other driver does this
  - replace own PACKED definition with __packed
  - use <video/fourcc.h> instead of duplicating DMA_FORMAT_* definitions
  - allocate etc/ramfb buffer with dma_alloc
  - map framebuffer coherent
  - replaces RISC-V example in commit message with arm64, because that's
    what I last tested with (probably too old qemu for RISC-V on my side)
---
 drivers/video/Kconfig  |   6 ++
 drivers/video/Makefile |   1 +
 drivers/video/ramfb.c  | 191 +++++++++++++++++++++++++++++++++++++++++
 3 files changed, 198 insertions(+)
 create mode 100644 drivers/video/ramfb.c

diff --git a/drivers/video/Kconfig b/drivers/video/Kconfig
index a20b7bbee9b7..01bdaf47bfca 100644
--- a/drivers/video/Kconfig
+++ b/drivers/video/Kconfig
@@ -123,6 +123,12 @@ config DRIVER_VIDEO_SIMPLEFB
 	  Add support for setting up the kernel's simple framebuffer driver
 	  based on the active barebox framebuffer.
 
+config DRIVER_VIDEO_RAMFB
+	bool "QEMU RamFB support"
+	select QEMU_FW_CFG
+	help
+	  Add support for setting up a QEMU RamFB driver.
+
 config DRIVER_VIDEO_EDID
 	bool "Add EDID support"
 	help
diff --git a/drivers/video/Makefile b/drivers/video/Makefile
index 9ec0420ccad1..d50d2d3ba562 100644
--- a/drivers/video/Makefile
+++ b/drivers/video/Makefile
@@ -25,6 +25,7 @@ obj-$(CONFIG_DRIVER_VIDEO_OMAP) += omap.o
 obj-$(CONFIG_DRIVER_VIDEO_BCM283X) += bcm2835.o
 obj-$(CONFIG_DRIVER_VIDEO_SIMPLEFB_CLIENT) += simplefb-client.o
 obj-$(CONFIG_DRIVER_VIDEO_SIMPLEFB) += simplefb-fixup.o
+obj-$(CONFIG_DRIVER_VIDEO_RAMFB) += ramfb.o
 obj-$(CONFIG_DRIVER_VIDEO_IMX_IPUV3) += imx-ipu-v3/
 obj-$(CONFIG_DRIVER_VIDEO_EFI_GOP) += efi_gop.o
 obj-$(CONFIG_DRIVER_VIDEO_FB_SSD1307) += ssd1307fb.o
diff --git a/drivers/video/ramfb.c b/drivers/video/ramfb.c
new file mode 100644
index 000000000000..26e01196fc02
--- /dev/null
+++ b/drivers/video/ramfb.c
@@ -0,0 +1,191 @@
+// SPDX-License-Identifier: GPL-2.0-or-later
+// SPDX-FileCopyrightText: (C) 2022 Adrian Negreanu
+
+#define pr_fmt(fmt) "ramfb: " fmt
+
+#include <common.h>
+#include <fb.h>
+#include <fcntl.h>
+#include <dma.h>
+#include <init.h>
+#include <unistd.h>
+#include <sys/ioctl.h>
+#include <fs.h>
+#include <linux/qemu_fw_cfg.h>
+#include <video/fourcc.h>
+
+struct ramfb {
+	int fd;
+	struct fb_info info;
+	dma_addr_t screen_dma;
+	struct fb_videomode mode;
+	u16 etcfb_select;
+};
+
+struct fw_cfg_etc_ramfb {
+	u64 addr;
+	u32 fourcc;
+	u32 flags;
+	u32 width;
+	u32 height;
+	u32 stride;
+} __packed;
+
+static int fw_cfg_find_file(struct device *dev, int fd, const char *filename)
+{
+	size_t filename_len = strlen(filename);
+	ssize_t ret;
+	__be32 count;
+	int i;
+
+	ioctl(fd, FW_CFG_SELECT, &(u16) { FW_CFG_FILE_DIR });
+
+	lseek(fd, 0, SEEK_SET);
+
+	ret = read(fd, &count, sizeof(count));
+	if (ret < 0)
+		return ret;
+
+	for (i = 0; i < be32_to_cpu(count); i++) {
+		struct fw_cfg_file qfile;
+
+		read(fd, &qfile, sizeof(qfile));
+
+		dev_dbg(dev, "enumerating file %s\n", qfile.name);
+
+		if (memcmp(qfile.name, filename, filename_len))
+			continue;
+
+		return be16_to_cpu(qfile.select);
+	}
+
+	return -ENOENT;
+}
+
+static void ramfb_populate_modes(struct ramfb *ramfb)
+{
+	struct fb_info *info = &ramfb->info;
+
+	ramfb->mode.name = "x8r8g8b8";
+	info->xres = ramfb->mode.xres = 640;
+	info->yres = ramfb->mode.yres = 480;
+
+	info->mode = &ramfb->mode;
+	info->bits_per_pixel = 32;
+	info->red	= (struct fb_bitfield) {16, 8};
+	info->green	= (struct fb_bitfield) {8, 8};
+	info->blue	= (struct fb_bitfield) {0, 8};
+	info->transp	= (struct fb_bitfield) {0, 0};
+}
+
+static int ramfb_activate_var(struct fb_info *fbi)
+{
+	struct ramfb *ramfb = fbi->priv;
+
+	if (fbi->screen_base)
+		dma_free_coherent(fbi->screen_base, ramfb->screen_dma, fbi->screen_size);
+
+	fbi->screen_size = fbi->xres * fbi->yres * fbi->bits_per_pixel;
+	fbi->screen_base = dma_alloc_coherent(fbi->screen_size, &ramfb->screen_dma);
+
+	return 0;
+}
+
+static void ramfb_enable(struct fb_info *fbi)
+{
+	struct ramfb *ramfb = fbi->priv;
+	struct fw_cfg_etc_ramfb *etc_ramfb;
+
+	etc_ramfb = dma_alloc(sizeof(*etc_ramfb));
+
+	etc_ramfb->addr = cpu_to_be64(ramfb->screen_dma);
+	etc_ramfb->fourcc = cpu_to_be32(DRM_FORMAT_XRGB8888);
+	etc_ramfb->flags  = cpu_to_be32(0);
+	etc_ramfb->width  = cpu_to_be32(fbi->xres);
+	etc_ramfb->height = cpu_to_be32(fbi->yres);
+	etc_ramfb->stride = cpu_to_be32(fbi->line_length);
+
+	ioctl(ramfb->fd, FW_CFG_SELECT, &ramfb->etcfb_select);
+
+	pwrite(ramfb->fd, etc_ramfb, sizeof(*etc_ramfb), 0);
+
+	dma_free(etc_ramfb);
+}
+
+static struct fb_ops ramfb_ops = {
+	.fb_activate_var = ramfb_activate_var,
+	.fb_enable = ramfb_enable,
+};
+
+static int ramfb_probe(struct device *parent_dev, int fd)
+{
+	int ret;
+	struct ramfb *ramfb;
+	struct fb_info *fbi;
+
+	ret = -ENODEV;
+
+	ramfb = xzalloc(sizeof(*ramfb));
+
+	ramfb->fd = fd;
+
+	ret = fw_cfg_find_file(parent_dev, fd, "etc/ramfb");
+	if (ret < 0) {
+		dev_err(parent_dev, "ramfb: fw_cfg (etc/ramfb) file not found\n");
+		return -ENODEV;
+	}
+
+	ramfb->etcfb_select = ret;
+	dev_dbg(parent_dev, "etc/ramfb file at slot 0x%x\n", ramfb->etcfb_select);
+
+	fbi = &ramfb->info;
+	fbi->priv = ramfb;
+	fbi->fbops = &ramfb_ops;
+	fbi->dev.parent = parent_dev;
+
+	ramfb_populate_modes(ramfb);
+
+	ret = register_framebuffer(fbi);
+	if (ret < 0) {
+		dev_err(parent_dev, "Unable to register ramfb: %d\n", ret);
+		return ret;
+	}
+
+	dev_info(parent_dev, "ramfb registered\n");
+
+	return 0;
+}
+
+static int ramfb_driver_init(void)
+{
+	struct cdev *cdev;
+	int err = 0;
+
+	for_each_cdev(cdev) {
+		int fd, ret;
+
+		if (!strstarts(cdev->name, "fw_cfg"))
+			continue;
+
+		fd = cdev_fdopen(cdev, O_RDWR);
+		if (fd < 0) {
+			err = fd;
+			continue;
+		}
+
+		ret = ramfb_probe(cdev->dev, fd);
+		if (ret == 0)
+			continue;
+		if (ret != -ENODEV && ret != -ENXIO)
+			err = ret;
+
+		close(fd);
+	}
+
+	return err;
+}
+device_initcall(ramfb_driver_init);
+
+MODULE_AUTHOR("Adrian Negreanu <adrian.negreanu@nxp.com>");
+MODULE_DESCRIPTION("QEMU RamFB driver");
+MODULE_LICENSE("GPL v2");
-- 
2.38.1




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

* Re: [PATCH v2 0/4] video: add support for QEMU ramfb
  2023-01-30  7:27 [PATCH v2 0/4] video: add support for QEMU ramfb Ahmad Fatoum
                   ` (3 preceding siblings ...)
  2023-01-30  7:27 ` [PATCH v2 4/4] video: add support for QEMU ramfb Ahmad Fatoum
@ 2023-01-31  8:19 ` Sascha Hauer
  4 siblings, 0 replies; 6+ messages in thread
From: Sascha Hauer @ 2023-01-31  8:19 UTC (permalink / raw)
  To: Ahmad Fatoum; +Cc: barebox, Adrian Negreanu

On Mon, Jan 30, 2023 at 08:27:03AM +0100, Ahmad Fatoum wrote:
> QEMU's ramfb is a very simple Qemu fw_cfg protocol, where the guest
> need only write a video settings structure to /etc/ramfb to get
> DMA from the framebuffer working. Add a driver for this on top
> of a newly added character device interface.
> 
> Adrian Negreanu (1):
>   video: add support for QEMU ramfb
> 
> Ahmad Fatoum (3):
>   fs: devfs: implement cdev_fdopen
>   asm-generic: avoid compiler warnings due to PCI_IOBASE
>   firmware: add QEMU FW CFG driver

Applied, thanks

Sascha

> 
>  drivers/firmware/Kconfig         |  10 +
>  drivers/firmware/Makefile        |   1 +
>  drivers/firmware/qemu_fw_cfg.c   | 307 +++++++++++++++++++++++++++++++
>  drivers/video/Kconfig            |   6 +
>  drivers/video/Makefile           |   1 +
>  drivers/video/ramfb.c            | 191 +++++++++++++++++++
>  fs/devfs-core.c                  |  20 ++
>  include/asm-generic/io.h         |   3 +-
>  include/driver.h                 |   1 +
>  include/filetype.h               |   1 +
>  include/uapi/linux/qemu_fw_cfg.h | 100 ++++++++++
>  11 files changed, 640 insertions(+), 1 deletion(-)
>  create mode 100644 drivers/firmware/qemu_fw_cfg.c
>  create mode 100644 drivers/video/ramfb.c
>  create mode 100644 include/uapi/linux/qemu_fw_cfg.h
> 
> -- 
> 2.38.1
> 
> 
> 

-- 
Pengutronix e.K.                           |                             |
Steuerwalder Str. 21                       | http://www.pengutronix.de/  |
31137 Hildesheim, Germany                  | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |



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

end of thread, other threads:[~2023-01-31  8:21 UTC | newest]

Thread overview: 6+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2023-01-30  7:27 [PATCH v2 0/4] video: add support for QEMU ramfb Ahmad Fatoum
2023-01-30  7:27 ` [PATCH v2 1/4] fs: devfs: implement cdev_fdopen Ahmad Fatoum
2023-01-30  7:27 ` [PATCH v2 2/4] asm-generic: avoid compiler warnings due to PCI_IOBASE Ahmad Fatoum
2023-01-30  7:27 ` [PATCH v2 3/4] firmware: add QEMU FW CFG driver Ahmad Fatoum
2023-01-30  7:27 ` [PATCH v2 4/4] video: add support for QEMU ramfb Ahmad Fatoum
2023-01-31  8:19 ` [PATCH v2 0/4] " Sascha Hauer

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox