diff --git a/04_build_linux.sh b/04_build_linux.sh index 146e942..a5a1672 100755 --- a/04_build_linux.sh +++ b/04_build_linux.sh @@ -9,8 +9,8 @@ cd ./linux/ if [ ! -f ./.patched ] ; then if [ -f arch/riscv/configs/mpfs_defconfig ] ; then git am ../patches/linux/0008-Add-wireless-regdb-regulatory-database-file.patch - git am ../patches/linux/linux-6.6.y/0011-can-mpfs_can-add-registration-string.patch - git am ../patches/linux/linux-6.6.y/0012-gpio-gpio-mpfs-add-registration-string.patch + git am ../patches/linux/0011-can-mpfs_can-add-registration-string.patch + git am ../patches/linux/0012-gpio-gpio-mpfs-add-registration-string.patch fi touch .patched fi diff --git a/patches/fix/0002-PCIe-Change-controller-and-bridge-base-address.patch b/patches/fix/0002-PCIe-Change-controller-and-bridge-base-address.patch deleted file mode 100644 index 9fb4752..0000000 --- a/patches/fix/0002-PCIe-Change-controller-and-bridge-base-address.patch +++ /dev/null @@ -1,27 +0,0 @@ -From 8911855f7b07ba7f592f73850e551802ae40601d Mon Sep 17 00:00:00 2001 -From: vauban353 -Date: Sat, 5 Nov 2022 17:47:50 +0000 -Subject: [PATCH 2/8] PCIe: Change controller and bridge base address. - ---- - drivers/pci/controller/pcie-microchip-host.c | 4 ++-- - 1 file changed, 2 insertions(+), 2 deletions(-) - -diff --git a/drivers/pci/controller/pcie-microchip-host.c b/drivers/pci/controller/pcie-microchip-host.c -index 56306f514..b1b3b7820 100644 ---- a/drivers/pci/controller/pcie-microchip-host.c -+++ b/drivers/pci/controller/pcie-microchip-host.c -@@ -26,8 +26,8 @@ - #define MC_ATT_MASK GENMASK_ULL(63, 31) - - /* PCIe Bridge Phy and Controller Phy offsets */ --#define MC_PCIE1_BRIDGE_ADDR 0x00008000u --#define MC_PCIE1_CTRL_ADDR 0x0000a000u -+#define MC_PCIE1_BRIDGE_ADDR 0x00004000u -+#define MC_PCIE1_CTRL_ADDR 0x00006000u - - #define MC_PCIE_BRIDGE_ADDR (MC_PCIE1_BRIDGE_ADDR) - #define MC_PCIE_CTRL_ADDR (MC_PCIE1_CTRL_ADDR) --- -2.39.2 - diff --git a/patches/fix/0003-GPIO-Add-Microchip-CoreGPIO-driver.patch b/patches/fix/0003-GPIO-Add-Microchip-CoreGPIO-driver.patch deleted file mode 100644 index eccc9a5..0000000 --- a/patches/fix/0003-GPIO-Add-Microchip-CoreGPIO-driver.patch +++ /dev/null @@ -1,371 +0,0 @@ -From 37ff4eff8ff033c48aa73526fec7291127326dcb Mon Sep 17 00:00:00 2001 -From: vauban353 -Date: Fri, 21 Jul 2023 19:33:28 +0100 -Subject: [PATCH 3/8] GPIO: Add Microchip CoreGPIO driver. - ---- - drivers/gpio/Kconfig | 8 + - drivers/gpio/Makefile | 1 + - drivers/gpio/gpio-microchip-core.c | 319 +++++++++++++++++++++++++++++ - 3 files changed, 328 insertions(+) - create mode 100644 drivers/gpio/gpio-microchip-core.c - -diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig -index d71f5bd6f..8e3858e34 100644 ---- a/drivers/gpio/Kconfig -+++ b/drivers/gpio/Kconfig -@@ -501,6 +501,14 @@ config GPIO_POLARFIRE_SOC - help - Say yes here to support the GPIO device on Microchip FPGAs. - -+config GPIO_MICROCHIP_CORE -+ bool "Microchip FPGA soft-IP GPIO support" -+ depends on OF_GPIO -+ select GPIOLIB_IRQCHIP -+ help -+ Say yes here to support the soft-IP GPIO device on Microchip FPGAs -+ -+ - config GPIO_PXA - bool "PXA GPIO support" - depends on ARCH_PXA || ARCH_MMP || COMPILE_TEST -diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile -index 9be0691d9..05a65ff04 100644 ---- a/drivers/gpio/Makefile -+++ b/drivers/gpio/Makefile -@@ -121,6 +121,7 @@ obj-$(CONFIG_GPIO_PISOSR) += gpio-pisosr.o - obj-$(CONFIG_GPIO_PL061) += gpio-pl061.o - obj-$(CONFIG_GPIO_PMIC_EIC_SPRD) += gpio-pmic-eic-sprd.o - obj-$(CONFIG_GPIO_POLARFIRE_SOC) += gpio-mpfs.o -+obj-$(CONFIG_GPIO_MICROCHIP_CORE) += gpio-microchip-core.o - obj-$(CONFIG_GPIO_PXA) += gpio-pxa.o - obj-$(CONFIG_GPIO_RASPBERRYPI_EXP) += gpio-raspberrypi-exp.o - obj-$(CONFIG_GPIO_RC5T583) += gpio-rc5t583.o -diff --git a/drivers/gpio/gpio-microchip-core.c b/drivers/gpio/gpio-microchip-core.c -new file mode 100644 -index 000000000..fd630cac4 ---- /dev/null -+++ b/drivers/gpio/gpio-microchip-core.c -@@ -0,0 +1,319 @@ -+// SPDX-License-Identifier: (GPL-2.0) -+/* -+ * Microchip CoreGPIO FPGA soft-IP GPIO controller driver -+ * -+ * Copyright (c) 2022 Microchip Technology Inc. and its subsidiaries -+ * -+ * Author: Lewis Hanly -+ * -+ */ -+ -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+ -+#define MPFS_GPIO_CTRL(i) (0x4 * (i)) -+#define MAX_NUM_GPIO 32 -+#define MPFS_GPIO_EN_INT 3 -+#define MPFS_GPIO_EN_OUT_BUF BIT(2) -+#define MPFS_GPIO_EN_IN BIT(1) -+#define MPFS_GPIO_EN_OUT BIT(0) -+ -+#define MPFS_GPIO_TYPE_INT_EDGE_BOTH 0x80 -+#define MPFS_GPIO_TYPE_INT_EDGE_NEG 0x60 -+#define MPFS_GPIO_TYPE_INT_EDGE_POS 0x40 -+#define MPFS_GPIO_TYPE_INT_LEVEL_LOW 0x20 -+#define MPFS_GPIO_TYPE_INT_LEVEL_HIGH 0x00 -+#define MPFS_GPIO_TYPE_INT_MASK GENMASK(7, 5) -+#define MPFS_IRQ_REG 0x80 -+#define MPFS_INP_REG 0x90 -+#define MPFS_OUTP_REG 0xA0 -+ -+struct mpfs_gpio_chip { -+ void __iomem *base; -+ struct clk *clk; -+ raw_spinlock_t lock; -+ struct gpio_chip gc; -+}; -+ -+static void mpfs_gpio_assign_bit(void __iomem *addr, unsigned int bit_offset, bool value) -+{ -+ unsigned long reg = readl(addr); -+ -+ __assign_bit(bit_offset, ®, value); -+ writel(reg, addr); -+} -+ -+static int mpfs_gpio_direction_input(struct gpio_chip *gc, unsigned int gpio_index) -+{ -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ u32 gpio_cfg; -+ unsigned long flags; -+ -+ raw_spin_lock_irqsave(&mpfs_gpio->lock, flags); -+ -+ gpio_cfg = readl(mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ gpio_cfg |= MPFS_GPIO_EN_IN; -+ gpio_cfg &= ~(MPFS_GPIO_EN_OUT | MPFS_GPIO_EN_OUT_BUF); -+ writel(gpio_cfg, mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ -+ raw_spin_unlock_irqrestore(&mpfs_gpio->lock, flags); -+ -+ return 0; -+} -+ -+static int mpfs_gpio_direction_output(struct gpio_chip *gc, unsigned int gpio_index, int value) -+{ -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ u32 gpio_cfg; -+ unsigned long flags; -+ -+ raw_spin_lock_irqsave(&mpfs_gpio->lock, flags); -+ -+ gpio_cfg = readl(mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ gpio_cfg |= MPFS_GPIO_EN_OUT | MPFS_GPIO_EN_OUT_BUF; -+ gpio_cfg &= ~MPFS_GPIO_EN_IN; -+ writel(gpio_cfg, mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_OUTP_REG, gpio_index, value); -+ -+ raw_spin_unlock_irqrestore(&mpfs_gpio->lock, flags); -+ -+ return 0; -+} -+ -+static int mpfs_gpio_get_direction(struct gpio_chip *gc, -+ unsigned int gpio_index) -+{ -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ u32 gpio_cfg; -+ -+ gpio_cfg = readl(mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ if (gpio_cfg & MPFS_GPIO_EN_IN) -+ return GPIO_LINE_DIRECTION_IN; -+ -+ return GPIO_LINE_DIRECTION_OUT; -+} -+ -+static int mpfs_gpio_get(struct gpio_chip *gc, -+ unsigned int gpio_index) -+{ -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ -+ return !!(readl(mpfs_gpio->base + MPFS_INP_REG) & BIT(gpio_index)); -+} -+ -+static void mpfs_gpio_set(struct gpio_chip *gc, unsigned int gpio_index, int value) -+{ -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ unsigned long flags; -+ -+ raw_spin_lock_irqsave(&mpfs_gpio->lock, flags); -+ -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_OUTP_REG, -+ gpio_index, value); -+ -+ raw_spin_unlock_irqrestore(&mpfs_gpio->lock, flags); -+} -+ -+static int mpfs_gpio_irq_set_type(struct irq_data *data, unsigned int type) -+{ -+ struct gpio_chip *gc = irq_data_get_irq_chip_data(data); -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ int gpio_index = irqd_to_hwirq(data); -+ u32 interrupt_type; -+ u32 gpio_cfg; -+ unsigned long flags; -+ -+ switch (type) { -+ case IRQ_TYPE_EDGE_BOTH: -+ interrupt_type = MPFS_GPIO_TYPE_INT_EDGE_BOTH; -+ break; -+ case IRQ_TYPE_EDGE_FALLING: -+ interrupt_type = MPFS_GPIO_TYPE_INT_EDGE_NEG; -+ break; -+ case IRQ_TYPE_EDGE_RISING: -+ interrupt_type = MPFS_GPIO_TYPE_INT_EDGE_POS; -+ break; -+ case IRQ_TYPE_LEVEL_HIGH: -+ interrupt_type = MPFS_GPIO_TYPE_INT_LEVEL_HIGH; -+ break; -+ case IRQ_TYPE_LEVEL_LOW: -+ interrupt_type = MPFS_GPIO_TYPE_INT_LEVEL_LOW; -+ break; -+ } -+ -+ raw_spin_lock_irqsave(&mpfs_gpio->lock, flags); -+ -+ gpio_cfg = readl(mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ gpio_cfg &= ~MPFS_GPIO_TYPE_INT_MASK; -+ gpio_cfg |= interrupt_type; -+ writel(gpio_cfg, mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index)); -+ -+ raw_spin_unlock_irqrestore(&mpfs_gpio->lock, flags); -+ -+ return 0; -+} -+ -+static void mpfs_gpio_irq_unmask(struct irq_data *data) -+{ -+ struct gpio_chip *gc = irq_data_get_irq_chip_data(data); -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ int gpio_index = irqd_to_hwirq(data) % MAX_NUM_GPIO; -+ -+ mpfs_gpio_direction_input(gc, gpio_index); -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_IRQ_REG, gpio_index, 1); -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index), -+ MPFS_GPIO_EN_INT, 1); -+} -+ -+static void mpfs_gpio_irq_mask(struct irq_data *data) -+{ -+ struct gpio_chip *gc = irq_data_get_irq_chip_data(data); -+ struct mpfs_gpio_chip *mpfs_gpio = gpiochip_get_data(gc); -+ int gpio_index = irqd_to_hwirq(data) % MAX_NUM_GPIO; -+ -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_IRQ_REG, gpio_index, 1); -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_GPIO_CTRL(gpio_index), -+ MPFS_GPIO_EN_INT, 0); -+} -+ -+static struct irq_chip mpfs_gpio_irqchip = { -+ .name = "mpfs", -+ .irq_set_type = mpfs_gpio_irq_set_type, -+ .irq_mask = mpfs_gpio_irq_mask, -+ .irq_unmask = mpfs_gpio_irq_unmask, -+ .flags = IRQCHIP_MASK_ON_SUSPEND, -+}; -+ -+static void mpfs_gpio_irq_handler(struct irq_desc *desc) -+{ -+ struct irq_chip *irqchip = irq_desc_get_chip(desc); -+ struct mpfs_gpio_chip *mpfs_gpio = -+ gpiochip_get_data(irq_desc_get_handler_data(desc)); -+ unsigned long status; -+ int offset; -+ -+ chained_irq_enter(irqchip, desc); -+ -+ status = readl(mpfs_gpio->base + MPFS_IRQ_REG); -+ for_each_set_bit(offset, &status, mpfs_gpio->gc.ngpio) { -+ mpfs_gpio_assign_bit(mpfs_gpio->base + MPFS_IRQ_REG, offset, 1); -+ generic_handle_irq(irq_find_mapping(mpfs_gpio->gc.irq.domain, offset)); -+ } -+ -+ chained_irq_exit(irqchip, desc); -+} -+ -+static int mpfs_gpio_probe(struct platform_device *pdev) -+{ -+ struct clk *clk; -+ struct device *dev = &pdev->dev; -+ struct device_node *node = pdev->dev.of_node; -+ struct mpfs_gpio_chip *mpfs_gpio; -+ struct gpio_irq_chip *girq; -+ int i, ret, ngpios, nirqs; -+ -+ mpfs_gpio = devm_kzalloc(dev, sizeof(*mpfs_gpio), GFP_KERNEL); -+ if (!mpfs_gpio) -+ return -ENOMEM; -+ -+ mpfs_gpio->base = devm_platform_ioremap_resource(pdev, 0); -+ if (IS_ERR(mpfs_gpio->base)) -+ return dev_err_probe(dev, PTR_ERR(mpfs_gpio->base), "memory allocation failure\n"); -+ -+ clk = devm_clk_get(dev, NULL); -+ if (IS_ERR(clk)) -+ return dev_err_probe(dev, PTR_ERR(clk), "devm_clk_get failed\n"); -+ -+ ret = clk_prepare_enable(clk); -+ if (ret) -+ return dev_err_probe(dev, ret, "failed to enable clock\n"); -+ -+ mpfs_gpio->clk = clk; -+ -+ raw_spin_lock_init(&mpfs_gpio->lock); -+ -+ ngpios = MAX_NUM_GPIO; -+ device_property_read_u32(dev, "ngpios", &ngpios); -+ if (ngpios > MAX_NUM_GPIO) -+ ngpios = MAX_NUM_GPIO; -+ -+ mpfs_gpio->gc.direction_input = mpfs_gpio_direction_input; -+ mpfs_gpio->gc.direction_output = mpfs_gpio_direction_output; -+ mpfs_gpio->gc.get_direction = mpfs_gpio_get_direction; -+ mpfs_gpio->gc.get = mpfs_gpio_get; -+ mpfs_gpio->gc.set = mpfs_gpio_set; -+ mpfs_gpio->gc.base = -1; -+ mpfs_gpio->gc.ngpio = ngpios; -+ mpfs_gpio->gc.label = dev_name(dev); -+ mpfs_gpio->gc.parent = dev; -+ mpfs_gpio->gc.owner = THIS_MODULE; -+ -+ nirqs = of_irq_count(node); -+ if (nirqs > MAX_NUM_GPIO) { -+ ret = -ENXIO; -+ goto cleanup_clock; -+ } -+ girq = &mpfs_gpio->gc.irq; -+ girq->chip = &mpfs_gpio_irqchip; -+ girq->handler = handle_simple_irq; -+ girq->parent_handler = mpfs_gpio_irq_handler; -+ girq->default_type = IRQ_TYPE_NONE; -+ girq->num_parents = nirqs; -+ girq->parents = devm_kcalloc(&pdev->dev, nirqs, -+ sizeof(*girq->parents), GFP_KERNEL); -+ if (!girq->parents) { -+ ret = -ENOMEM; -+ goto cleanup_clock; -+ } -+ for (i = 0; i < nirqs; i++) -+ girq->parents[i] = platform_get_irq(pdev, i); -+ -+ ret = gpiochip_add_data(&mpfs_gpio->gc, mpfs_gpio); -+ if (ret) -+ goto cleanup_clock; -+ -+ platform_set_drvdata(pdev, mpfs_gpio); -+ -+ return 0; -+ -+cleanup_clock: -+ clk_disable_unprepare(mpfs_gpio->clk); -+ return ret; -+} -+ -+static int mpfs_gpio_remove(struct platform_device *pdev) -+{ -+ struct mpfs_gpio_chip *mpfs_gpio = platform_get_drvdata(pdev); -+ -+ gpiochip_remove(&mpfs_gpio->gc); -+ clk_disable_unprepare(mpfs_gpio->clk); -+ -+ return 0; -+} -+ -+static const struct of_device_id mpfs_of_ids[] = { -+ { .compatible = "microchip,core-gpio", }, -+ { /* end of list */ } -+}; -+ -+static struct platform_driver mchp_core_gpio_driver = { -+ .probe = mpfs_gpio_probe, -+ .driver = { -+ .name = "microchip,core-gpio", -+ .of_match_table = mpfs_of_ids, -+ }, -+ .remove = mpfs_gpio_remove, -+}; -+builtin_platform_driver(mchp_core_gpio_driver); --- -2.39.2 - diff --git a/patches/fix/0004-ADC-Add-Microchip-MCP356X-driver.patch b/patches/fix/0004-ADC-Add-Microchip-MCP356X-driver.patch deleted file mode 100644 index 32fa0f1..0000000 --- a/patches/fix/0004-ADC-Add-Microchip-MCP356X-driver.patch +++ /dev/null @@ -1,1450 +0,0 @@ -From deadef387eed1bc60c8d2570e86a9bd0b4b196b4 Mon Sep 17 00:00:00 2001 -From: vauban353 -Date: Fri, 16 Jun 2023 16:05:01 +0100 -Subject: [PATCH 4/8] ADC: Add Microchip MCP356X driver. - ---- - drivers/iio/adc/Kconfig | 10 + - drivers/iio/adc/Makefile | 1 + - drivers/iio/adc/mcp356x.c | 1396 +++++++++++++++++++++++++++++++++++++ - 3 files changed, 1407 insertions(+) - create mode 100644 drivers/iio/adc/mcp356x.c - -diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig -index 48763d6a8..6c6b62a7f 100644 ---- a/drivers/iio/adc/Kconfig -+++ b/drivers/iio/adc/Kconfig -@@ -741,6 +741,16 @@ config MCP3911 - This driver can also be built as a module. If so, the module will be - called mcp3911. - -+config MCP356X -+ tristate "Microchip Technology MCP356X driver" -+ depends on SPI -+ help -+ Say yes here to build support for Microchip Technology's MCP356X -+ analog to digital converter. -+ -+ This driver can also be built as a module. If so, the module will be -+ called mcp356x. -+ - config MEDIATEK_MT6360_ADC - tristate "Mediatek MT6360 ADC driver" - depends on MFD_MT6360 -diff --git a/drivers/iio/adc/Makefile b/drivers/iio/adc/Makefile -index d5ca37205..5b3f027ac 100644 ---- a/drivers/iio/adc/Makefile -+++ b/drivers/iio/adc/Makefile -@@ -68,6 +68,7 @@ obj-$(CONFIG_MAX9611) += max9611.o - obj-$(CONFIG_MCP320X) += mcp320x.o - obj-$(CONFIG_MCP3422) += mcp3422.o - obj-$(CONFIG_MCP3911) += mcp3911.o -+obj-$(CONFIG_MCP356X) += mcp356x.o - obj-$(CONFIG_MEDIATEK_MT6360_ADC) += mt6360-adc.o - obj-$(CONFIG_MEDIATEK_MT6577_AUXADC) += mt6577_auxadc.o - obj-$(CONFIG_MEN_Z188_ADC) += men_z188_adc.o -diff --git a/drivers/iio/adc/mcp356x.c b/drivers/iio/adc/mcp356x.c -new file mode 100644 -index 000000000..22d59413d ---- /dev/null -+++ b/drivers/iio/adc/mcp356x.c -@@ -0,0 +1,1396 @@ -+// SPDX-License-Identifier: GPL-2.0+ -+/* -+ * IIO driver for MCP356X/MCP356XR and MCP346X/MCP346XR series ADC chip family -+ * -+ * Copyright (C) 2022-2023 Microchip Technology Inc. and its subsidiaries -+ * -+ * Author: Marius Cristea -+ * -+ * Datasheet for MCP3561, MCP3562, MCP3564 can be found here: -+ * https://ww1.microchip.com/downloads/aemDocuments/documents/MSLD/ProductDocuments/DataSheets/MCP3561-2-4-Family-Data-Sheet-DS20006181C.pdf -+ * Datasheet for MCP3561R, MCP3562R, MCP3564R can be found here: -+ * https://ww1.microchip.com/downloads/aemDocuments/documents/APID/ProductDocuments/DataSheets/MCP3561_2_4R-Data-Sheet-DS200006391C.pdf -+ * Datasheet for MCP3461, MCP3462, MCP3464 can be found here: -+ * https://ww1.microchip.com/downloads/aemDocuments/documents/APID/ProductDocuments/DataSheets/MCP3461-2-4-Two-Four-Eight-Channel-153.6-ksps-Low-Noise-16-Bit-Delta-Sigma-ADC-Data-Sheet-20006180D.pdf -+ * Datasheet for MCP3461R, MCP3462R, MCP3464R can be found here: -+ * https://ww1.microchip.com/downloads/aemDocuments/documents/APID/ProductDocuments/DataSheets/MCP3461-2-4R-Family-Data-Sheet-DS20006404C.pdf -+ * -+ */ -+ -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+ -+#include -+#include -+ -+#define MCP356X_ADCDATA 0x00 -+#define MCP356X_CONFIG0 0x01 -+#define MCP356X_CONFIG1 0x02 -+#define MCP356X_CONFIG2 0x03 -+#define MCP356X_CONFIG3 0x04 -+#define MCP356X_IRQ 0x05 -+#define MCP356X_MUX 0x06 -+#define MCP356X_SCAN 0x07 -+#define MCP356X_TIMER 0x08 -+#define MCP356X_OFFSETCAL 0x09 -+#define MCP356X_GAINCAL 0x0A -+#define MCP356X_RESERVED_B 0x0B -+#define MCP356X_RESERVED_C 0x0C -+#define MCP356X_LOCK 0x0D -+#define MCP356X_RESERVED_E 0x0E -+#define MCP356X_CRCCFG 0x0F -+ -+#define MCP356X_FAST_CMD_CTRL 0 -+#define MCP356X_RD_CTRL BIT(0) -+#define MCP356X_WRT_CTRL BIT(1) -+ -+#define MCP356X_FULL_RESET_CMD GENMASK(3, 1) -+ -+#define MCP3461_HW_ID BIT(3) -+#define MCP3462_HW_ID 0x0009 -+#define MCP3464_HW_ID 0x000B -+ -+#define MCP3561_HW_ID GENMASK(3, 2) -+#define MCP3562_HW_ID 0x000D -+#define MCP3564_HW_ID GENMASK(3, 0) -+#define MCP356X_HW_ID_MASK GENMASK(3, 0) -+ -+#define MCP356XR_INT_VREF_MV 2400 -+ -+/* MUX_VIN Input Selection -+ */ -+#define MCP356X_INTERNAL_VCM GENMASK(3, 0) -+#define MCP356X_TEMP_DIODE_M GENMASK(3, 1) -+#define MCP356X_TEMP_DIODE_P 0b1101 -+#define MCP356X_REFIN_NEG GENMASK(3, 2) -+#define MCP356X_REFIN_POZ 0b1011 -+#define MCP356X_RESERVED 0b1010 /* do not use */ -+#define MCP356X_AVDD 0b1001 -+#define MCP356X_AGND BIT(3) -+#define MCP356X_CH7 GENMASK(2, 0) -+#define MCP356X_CH6 GENMASK(2, 1) -+#define MCP356X_CH5 0b0101 -+#define MCP356X_CH4 BIT(2) -+#define MCP356X_CH3 GENMASK(1, 0) -+#define MCP356X_CH2 BIT(1) -+#define MCP356X_CH1 BIT(0) -+#define MCP356X_CH0 0 -+ -+#define MCP356X_ADC_MODE_MASK GENMASK(1, 0) -+ -+#define MCP356X_ADC_DEFAULT_MODE 0 -+#define MCP356X_ADC_SHUTDOWN_MODE BIT(0) -+#define MCP356X_ADC_STANDBY BIT(1) -+#define MCP356X_ADC_CONVERSION_MODE GENMASK(1, 0) -+ -+#define MCP356X_DATA_READY_MASK BIT(6) -+ -+#define MCP356X_OVERSAMPLING_RATIO_32 0 -+#define MCP356X_OVERSAMPLING_RATIO_64 BIT(0) -+#define MCP356X_OVERSAMPLING_RATIO_128 BIT(1) -+#define MCP356X_OVERSAMPLING_RATIO_256 GENMASK(1, 0) -+#define MCP356X_OVERSAMPLING_RATIO_512 BIT(2) -+#define MCP356X_OVERSAMPLING_RATIO_1024 0x05 -+#define MCP356X_OVERSAMPLING_RATIO_2048 GENMASK(2, 1) -+#define MCP356X_OVERSAMPLING_RATIO_4096 GENMASK(2, 0) -+#define MCP356X_OVERSAMPLING_RATIO_8192 BIT(3) -+#define MCP356X_OVERSAMPLING_RATIO_16384 0x09 -+#define MCP356X_OVERSAMPLING_RATIO_20480 0x0A -+#define MCP356X_OVERSAMPLING_RATIO_24576 0x0B -+#define MCP356X_OVERSAMPLING_RATIO_40960 0x0C -+#define MCP356X_OVERSAMPLING_RATIO_49152 0x0D -+#define MCP356X_OVERSAMPLING_RATIO_81920 GENMASK(3, 1) -+#define MCP356X_OVERSAMPLING_RATIO_98304 GENMASK(3, 0) -+ -+#define MCP356X_OVERSAMPLING_RATIO_MASK GENMASK(5, 2) -+#define MCP356X_OVERSAMPLING_RATIO_SHIFT 0x02 -+ -+#define MCP356X_HARDWARE_GAIN_MASK GENMASK(5, 3) -+#define MCP356X_HARDWARE_GAIN_SHIFT 0x03 -+#define MCP356X_DEFAULT_HARDWARE_GAIN BIT(1) -+ -+#define MCP356X_CS_SEL_0_0_uA 0x0 -+#define MCP356X_CS_SEL_0_9_uA BIT(0) -+#define MCP356X_CS_SEL_3_7_uA BIT(1) -+#define MCP356X_CS_SEL_15_uA GENMASK(1, 0) -+ -+#define MCP356X_CS_SEL_MASK GENMASK(3, 2) -+ -+#define MCP356X_BOOST_CURRENT_x0_50 0 -+#define MCP356X_BOOST_CURRENT_x0_66 BIT(0) -+#define MCP356X_BOOST_CURRENT_x1_00 BIT(1) -+#define MCP356X_BOOST_CURRENT_x2_00 GENMASK(1, 0) -+ -+#define MCP356X_BOOST_CURRENT_MASK GENMASK(7, 6) -+ -+/* Auto-Zeroing MUX Setting */ -+#define MCP356X_AZ_MUX_MASK BIT(2) -+/* Auto-Zeroing REF Setting */ -+#define MCP356X_AZ_REF_MASK BIT(1) -+ -+#define MCP356X_SHARED_DEVATTRS_COUNT 1 -+#define MCP356X_PARTICULAR_DEVATTRS_COUNT 1 -+ -+#define MAX_HWGAIN 64000 -+ -+#define MCP356X_DATA_READY_TIMEOUT_MS 2000 -+ -+enum mcp356x_ids { -+ mcp3461, -+ mcp3462, -+ mcp3464, -+ mcp3461r, -+ mcp3462r, -+ mcp3464r, -+ mcp3561, -+ mcp3562, -+ mcp3564, -+ mcp3561r, -+ mcp3562r, -+ mcp3564r, -+}; -+ -+static const unsigned int mcp356x_oversampling_avail[16] = { -+ [MCP356X_OVERSAMPLING_RATIO_32] = 32, -+ [MCP356X_OVERSAMPLING_RATIO_64] = 64, -+ [MCP356X_OVERSAMPLING_RATIO_128] = 128, -+ [MCP356X_OVERSAMPLING_RATIO_256] = 256, -+ [MCP356X_OVERSAMPLING_RATIO_512] = 512, -+ [MCP356X_OVERSAMPLING_RATIO_1024] = 1024, -+ [MCP356X_OVERSAMPLING_RATIO_2048] = 2048, -+ [MCP356X_OVERSAMPLING_RATIO_4096] = 4096, -+ [MCP356X_OVERSAMPLING_RATIO_8192] = 8192, -+ [MCP356X_OVERSAMPLING_RATIO_16384] = 16384, -+ [MCP356X_OVERSAMPLING_RATIO_20480] = 20480, -+ [MCP356X_OVERSAMPLING_RATIO_24576] = 24576, -+ [MCP356X_OVERSAMPLING_RATIO_40960] = 40960, -+ [MCP356X_OVERSAMPLING_RATIO_49152] = 49152, -+ [MCP356X_OVERSAMPLING_RATIO_81920] = 81920, -+ [MCP356X_OVERSAMPLING_RATIO_98304] = 98304 -+}; -+ -+/* -+ * Current Source/Sink Selection Bits for Sensor Bias (source on VIN+/sink on VIN-) -+ */ -+static const char * const mcp356x_current_bias_avail[] = { -+ [MCP356X_CS_SEL_0_0_uA] = "no_current(default)", -+ [MCP356X_CS_SEL_0_9_uA] = "0.9_uA", -+ [MCP356X_CS_SEL_3_7_uA] = "3.7_uA", -+ [MCP356X_CS_SEL_15_uA] = "15_uA", -+}; -+ -+/* -+ * BOOST[1:0]: ADC Bias Current Selection -+ */ -+static const char * const mcp356x_boost_current_avail[] = { -+ [MCP356X_BOOST_CURRENT_x0_50] = "x0.5", -+ [MCP356X_BOOST_CURRENT_x0_66] = "x0.66", -+ [MCP356X_BOOST_CURRENT_x1_00] = "x1_(default)", -+ [MCP356X_BOOST_CURRENT_x2_00] = "x2", -+}; -+ -+/* -+ * Calibration bias values -+ */ -+static const int mcp356x_calib_bias[] = { -+ -8388608, /* min: -2^23 */ -+ 1, /* step: 1 */ -+ 8388607 /* max: 2^23 - 1 */ -+}; -+ -+/* -+ * Calibration scale values -+ * The Gain Error Calibration register (GAINCAL) is an -+ * unsigned 24-bit register that holds the digital gain error -+ * calibration value, GAINCAL which could be calculated by -+ * GAINCAL (V/V) = (GAINCAL[23:0])/8388608 -+ * The gain error calibration value range in equivalent voltage is [0; 2-2^(-23)] -+ */ -+static const unsigned int mcp356x_calib_scale[] = { -+ 0, /* min: 0 */ -+ 1, /* step: 1/8388608 */ -+ 16777215 /* max: 2 - 2^(-23) */ -+}; -+ -+/* Programmable hardware gain x1/3, x1, x2, x4, x8, x16, x32, x64 */ -+static const int mcp356x_hwgain_frac[] = { -+ 3, -+ 10, -+ 1, -+ 1, -+ 2, -+ 1, -+ 4, -+ 1, -+ 8, -+ 1, -+ 16, -+ 1, -+ 32, -+ 1, -+ 64, -+ 1 -+}; -+ -+static const int mcp356x_hwgain[] = { -+ 300, -+ 1000, -+ 2000, -+ 4000, -+ 8000, -+ 16000, -+ 32000, -+ 64000 -+}; -+ -+/** -+ * struct mcp356x_chip_info - chip specific data -+ * @channels: struct iio_chan_spec matching the device's capabilities -+ * @num_channels: number of channels -+ * @int_vref_uv: internal voltage reference value in microVolts -+ * @has_vref: Does the ADC has an internal voltage reference? -+ */ -+struct mcp356x_chip_info { -+ const struct iio_chan_spec *channels; -+ unsigned int num_channels; -+ unsigned int int_vref_uv; -+ bool has_vref; -+}; -+ -+/** -+ * struct mcp356x_state - working data for a ADC device -+ * @chip_info: chip specific data -+ * @mcp356x_info: information about iio device -+ * @spi: SPI device structure -+ * @vref: The regulator device used as a voltage reference in case -+ * external voltage reference is used -+ * @vref_mv: voltage reference value in miliVolts -+ * @lock: mutex to prevent concurrent reads/writes -+ * @dev_addr: hardware device address -+ * @oversampling: the index inside oversampling list of the ADC -+ * @hwgain: the index inside hardware gain list of the ADC -+ * @calib_bias: calibration bias value -+ * @calib_scale: calibration scale value -+ * @current_boost_mode: the index inside current boost list of the ADC -+ * @current_bias_mode: the index inside current bias list of the ADC -+ * @auto_zeroing_mux: set if ADC auto-zeroing algorithm is enabled -+ * @auto_zeroing_ref: set if ADC auto-Zeroing Reference Buffer Setting is enabled -+ */ -+struct mcp356x_state { -+ const struct mcp356x_chip_info *chip_info; -+ struct iio_info mcp356x_info; -+ struct spi_device *spi; -+ struct regulator *vref; -+ unsigned short vref_mv; -+ struct mutex lock; /*lock to prevent concurrent reads/writes */ -+ u8 dev_addr; -+ unsigned int oversampling; -+ unsigned int hwgain; -+ int calib_bias; -+ int calib_scale; -+ unsigned int current_boost_mode; -+ unsigned int current_bias_mode; -+ bool auto_zeroing_mux; -+ bool auto_zeroing_ref; -+}; -+ -+static inline u8 mcp356x_reg_write(u8 chip_addr, u8 reg) -+{ -+ return ((chip_addr << 6) | (reg << 2) | MCP356X_WRT_CTRL); -+} -+ -+static inline u8 mcp356x_reg_read(u8 chip_addr, u8 reg) -+{ -+ return ((chip_addr << 6) | (reg << 2) | MCP356X_RD_CTRL); -+} -+ -+static inline u8 mcp356x_reg_fast_cmd(u8 chip_addr, u8 cmd) -+{ -+ return ((chip_addr << 6) | (cmd << 2)); -+} -+ -+static int mcp356x_read(struct mcp356x_state *adc, u8 reg, u32 *val, u8 len) -+{ -+ int ret; -+ u8 tmp_reg; -+ -+ tmp_reg = mcp356x_reg_read(adc->dev_addr, reg); -+ -+ ret = spi_write_then_read(adc->spi, &tmp_reg, 1, val, len); -+ -+ be32_to_cpus(val); -+ *val >>= ((4 - len) * 8); -+ -+ return ret; -+} -+ -+static int mcp356x_write(struct mcp356x_state *adc, u8 reg, u32 val, u8 len) -+{ -+ val |= (mcp356x_reg_write(adc->dev_addr, reg) << (len * 8)); -+ val <<= (3 - len) * 8; -+ cpu_to_be32s(&val); -+ -+ return spi_write(adc->spi, &val, len + 1); -+} -+ -+static int mcp356x_fast_cmd(struct mcp356x_state *adc, u8 fast_cmd) -+{ -+ u8 val; -+ -+ val = mcp356x_reg_fast_cmd(adc->dev_addr, fast_cmd); -+ -+ return spi_write(adc->spi, &val, 1); -+} -+ -+static int mcp356x_update(struct mcp356x_state *adc, u8 reg, u32 mask, u32 val, -+ u8 len) -+{ -+ u32 tmp; -+ int ret; -+ -+ ret = mcp356x_read(adc, reg, &tmp, len); -+ -+ if (ret == 0) { -+ val &= mask; -+ val |= tmp & ~mask; -+ ret = mcp356x_write(adc, reg, val, len); -+ } -+ -+ return ret; -+} -+ -+/* Custom IIO Device Attributes */ -+static int mcp356x_set_current_boost_mode(struct iio_dev *indio_dev, -+ const struct iio_chan_spec *chan, -+ unsigned int mode) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ int ret; -+ -+ dev_dbg(&indio_dev->dev, "%s: %d\n", __func__, mode); -+ -+ mutex_lock(&adc->lock); -+ ret = mcp356x_update(adc, MCP356X_CONFIG2, MCP356X_BOOST_CURRENT_MASK, -+ mode, 1); -+ -+ if (ret) -+ dev_err(&indio_dev->dev, "Failed to configure CONFIG2 register\n"); -+ else -+ adc->current_boost_mode = mode; -+ -+ mutex_unlock(&adc->lock); -+ -+ return ret; -+} -+ -+static int mcp356x_get_current_boost_mode(struct iio_dev *indio_dev, -+ const struct iio_chan_spec *chan) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ -+ return adc->current_boost_mode; -+} -+ -+static int mcp356x_set_current_bias_mode(struct iio_dev *indio_dev, -+ const struct iio_chan_spec *chan, -+ unsigned int mode) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ int ret; -+ -+ dev_dbg(&indio_dev->dev, "%s: %d\n", __func__, mode); -+ -+ mutex_lock(&adc->lock); -+ ret = mcp356x_update(adc, MCP356X_CONFIG0, MCP356X_CS_SEL_MASK, mode, 1); -+ -+ if (ret) -+ dev_err(&indio_dev->dev, "Failed to configure CONFIG0 register\n"); -+ else -+ adc->current_bias_mode = mode; -+ -+ mutex_unlock(&adc->lock); -+ -+ return ret; -+} -+ -+static int mcp356x_get_current_bias_mode(struct iio_dev *indio_dev, -+ const struct iio_chan_spec *chan) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ -+ return adc->current_bias_mode; -+} -+ -+static const struct iio_enum mcp356x_current_boost_mode_enum = { -+ .items = mcp356x_boost_current_avail, -+ .num_items = ARRAY_SIZE(mcp356x_boost_current_avail), -+ .set = mcp356x_set_current_boost_mode, -+ .get = mcp356x_get_current_boost_mode, -+}; -+ -+static const struct iio_enum mcp356x_current_bias_mode_enum = { -+ .items = mcp356x_current_bias_avail, -+ .num_items = ARRAY_SIZE(mcp356x_current_bias_avail), -+ .set = mcp356x_set_current_bias_mode, -+ .get = mcp356x_get_current_bias_mode, -+}; -+ -+static const struct iio_chan_spec_ext_info mcp356x_ext_info[] = { -+ IIO_ENUM("boost_current", IIO_SHARED_BY_ALL, &mcp356x_current_boost_mode_enum), -+ { -+ .name = "boost_current_available", -+ .shared = IIO_SHARED_BY_ALL, -+ .read = iio_enum_available_read, -+ .private = (uintptr_t)&mcp356x_current_boost_mode_enum, -+ }, -+ IIO_ENUM("current_bias", IIO_SHARED_BY_ALL, &mcp356x_current_bias_mode_enum), -+ { -+ .name = "current_bias_available", -+ .shared = IIO_SHARED_BY_ALL, -+ .read = iio_enum_available_read, -+ .private = (uintptr_t)&mcp356x_current_bias_mode_enum, -+ }, -+ {} -+}; -+ -+static ssize_t mcp356x_auto_zeroing_mux_show(struct device *dev, -+ struct device_attribute *attr, -+ char *buf) -+{ -+ struct iio_dev *indio_dev = dev_to_iio_dev(dev); -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ -+ return sysfs_emit(buf, "%d\n", adc->auto_zeroing_mux); -+} -+ -+static ssize_t mcp356x_auto_zeroing_mux_store(struct device *dev, -+ struct device_attribute *attr, -+ const char *buf, size_t len) -+{ -+ struct iio_dev *indio_dev = dev_to_iio_dev(dev); -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ bool auto_zero; -+ int ret; -+ -+ ret = kstrtobool(buf, &auto_zero); -+ if (ret) -+ return ret; -+ -+ mutex_lock(&adc->lock); -+ ret = mcp356x_update(adc, MCP356X_CONFIG2, MCP356X_AZ_MUX_MASK, -+ (u32)auto_zero, 1); -+ -+ if (ret) -+ dev_err(&indio_dev->dev, "Failed to update CONFIG2 register\n"); -+ else -+ adc->auto_zeroing_mux = auto_zero; -+ -+ mutex_unlock(&adc->lock); -+ -+ return ret ? ret : len; -+} -+ -+static ssize_t mcp356x_auto_zeroing_ref_show(struct device *dev, -+ struct device_attribute *attr, -+ char *buf) -+{ -+ struct iio_dev *indio_dev = dev_to_iio_dev(dev); -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ -+ return sysfs_emit(buf, "%d\n", adc->auto_zeroing_ref); -+} -+ -+static ssize_t mcp356x_auto_zeroing_ref_store(struct device *dev, -+ struct device_attribute *attr, -+ const char *buf, size_t len) -+{ -+ struct iio_dev *indio_dev = dev_to_iio_dev(dev); -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ bool auto_zero; -+ int ret; -+ -+ ret = kstrtobool(buf, &auto_zero); -+ if (ret) -+ return ret; -+ -+ mutex_lock(&adc->lock); -+ ret = mcp356x_update(adc, MCP356X_CONFIG2, MCP356X_AZ_REF_MASK, -+ (u32)auto_zero, 1); -+ -+ if (ret) -+ dev_err(&indio_dev->dev, "Failed to update CONFIG2 register\n"); -+ else -+ adc->auto_zeroing_ref = auto_zero; -+ -+ mutex_unlock(&adc->lock); -+ -+ return ret ? ret : len; -+} -+ -+#define MCP356X_DEV_ATTR(name) (&iio_dev_attr_##name.dev_attr.attr) -+ -+static IIO_DEVICE_ATTR(enable_auto_zeroing_ref, 0644, -+ mcp356x_auto_zeroing_ref_show, -+ mcp356x_auto_zeroing_ref_store, 0); -+ -+static struct attribute *mcp356x_particular_attributes[] = { -+ MCP356X_DEV_ATTR(enable_auto_zeroing_ref), -+ NULL -+}; -+ -+static IIO_DEVICE_ATTR(enable_auto_zeroing_mux, 0644, -+ mcp356x_auto_zeroing_mux_show, -+ mcp356x_auto_zeroing_mux_store, 0); -+ -+static struct attribute *mcp356x_shared_attributes[] = { -+ MCP356X_DEV_ATTR(enable_auto_zeroing_mux), -+ NULL, -+}; -+ -+static int mcp356x_prep_custom_attributes(struct mcp356x_state *adc, -+ struct iio_dev *indio_dev) -+{ -+ int i; -+ struct attribute **mcp356x_custom_attr; -+ struct attribute_group *mcp356x_group; -+ -+ mcp356x_group = devm_kzalloc(&adc->spi->dev, sizeof(*mcp356x_group), GFP_KERNEL); -+ -+ if (!mcp356x_group) -+ return (-ENOMEM); -+ -+ mcp356x_custom_attr = devm_kzalloc(&adc->spi->dev, (MCP356X_SHARED_DEVATTRS_COUNT + -+ MCP356X_PARTICULAR_DEVATTRS_COUNT + 1) * sizeof(struct attribute *), -+ GFP_KERNEL); -+ -+ if (!mcp356x_custom_attr) -+ return (-ENOMEM); -+ -+ for (i = 0; i < MCP356X_SHARED_DEVATTRS_COUNT; i++) -+ mcp356x_custom_attr[i] = mcp356x_shared_attributes[i]; -+ -+ if (adc->chip_info->has_vref) { -+ dev_dbg(&indio_dev->dev, "Setup custom attr for R variant\n"); -+ for (i = 0; i < MCP356X_PARTICULAR_DEVATTRS_COUNT; i++) -+ mcp356x_custom_attr[MCP356X_SHARED_DEVATTRS_COUNT + i] = -+ mcp356x_particular_attributes[i]; -+ } -+ -+ mcp356x_group->attrs = mcp356x_custom_attr; -+ adc->mcp356x_info.attrs = mcp356x_group; -+ -+ return 0; -+} -+ -+#define MCP356X_V_CHANNEL(index, addr, depth) { \ -+ .type = IIO_VOLTAGE, \ -+ .indexed = 1, \ -+ .channel = (index), \ -+ .address = (((addr) << 4) | MCP356X_AGND), \ -+ .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \ -+ .info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE), \ -+ .info_mask_shared_by_all = BIT(IIO_CHAN_INFO_HARDWAREGAIN) | \ -+ BIT(IIO_CHAN_INFO_CALIBBIAS) | \ -+ BIT(IIO_CHAN_INFO_CALIBSCALE) | \ -+ BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO), \ -+ .info_mask_shared_by_all_available = BIT(IIO_CHAN_INFO_CALIBSCALE) | \ -+ BIT(IIO_CHAN_INFO_HARDWAREGAIN) | \ -+ BIT(IIO_CHAN_INFO_CALIBBIAS) | \ -+ BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO), \ -+ .ext_info = mcp356x_ext_info, \ -+ .scan_index = 0, \ -+ .scan_type = { \ -+ .sign = 's', \ -+ .realbits = depth, \ -+ .storagebits = 32, \ -+ .endianness = IIO_BE, \ -+ }, \ -+} -+ -+#define MCP356X_T_CHAN(depth) { \ -+ .type = IIO_TEMP, \ -+ .channel = 0, \ -+ .address = ((MCP356X_TEMP_DIODE_P << 4) | MCP356X_TEMP_DIODE_M), \ -+ .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \ -+ .info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE), \ -+ .info_mask_shared_by_all = BIT(IIO_CHAN_INFO_HARDWAREGAIN) | \ -+ BIT(IIO_CHAN_INFO_CALIBBIAS) | \ -+ BIT(IIO_CHAN_INFO_CALIBSCALE) | \ -+ BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO), \ -+ .info_mask_shared_by_all_available = BIT(IIO_CHAN_INFO_CALIBSCALE) | \ -+ BIT(IIO_CHAN_INFO_CALIBBIAS) | \ -+ BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO), \ -+ .ext_info = mcp356x_ext_info, \ -+ .scan_index = 0, \ -+ .scan_type = { \ -+ .sign = 'u', \ -+ .realbits = depth, \ -+ .storagebits = 32, \ -+ .endianness = IIO_BE, \ -+ }, \ -+} -+ -+#define MCP356X_V_CHANNEL_DIFF(chan1, chan2, addr, depth) { \ -+ .type = IIO_VOLTAGE, \ -+ .indexed = 1, \ -+ .channel = (chan1), \ -+ .channel2 = (chan2), \ -+ .address = (addr), \ -+ .differential = 1, \ -+ .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \ -+ .info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE), \ -+ .info_mask_shared_by_all = BIT(IIO_CHAN_INFO_HARDWAREGAIN) | \ -+ BIT(IIO_CHAN_INFO_CALIBBIAS) | \ -+ BIT(IIO_CHAN_INFO_CALIBSCALE) | \ -+ BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO), \ -+ .info_mask_shared_by_all_available = BIT(IIO_CHAN_INFO_CALIBSCALE) | \ -+ BIT(IIO_CHAN_INFO_CALIBBIAS) | \ -+ BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO), \ -+ .ext_info = mcp356x_ext_info, \ -+ .scan_index = 0, \ -+ .scan_type = { \ -+ .sign = 's', \ -+ .realbits = depth, \ -+ .storagebits = 32, \ -+ .endianness = IIO_BE, \ -+ }, \ -+} -+ -+#define MCP3561_CHANNELS(depth) { \ -+ MCP356X_V_CHANNEL(0, 0, depth), \ -+ MCP356X_V_CHANNEL(1, 1, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 1, 0x01, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 0, 0x10, depth), \ -+ MCP356X_T_CHAN(depth) \ -+} -+ -+#define MCP3562_CHANNELS(depth) { \ -+ MCP356X_V_CHANNEL(0, 0, depth), \ -+ MCP356X_V_CHANNEL(1, 1, depth), \ -+ MCP356X_V_CHANNEL(2, 2, depth), \ -+ MCP356X_V_CHANNEL(3, 3, depth), \ -+ MCP356X_T_CHAN(depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 1, 0x01, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 0, 0x10, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 2, 0x02, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 3, 0x03, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 2, 0x12, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 3, 0x13, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 3, 0x23, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 0, 0x20, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 0, 0x30, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 1, 0x21, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 1, 0x31, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 2, 0x32, depth), \ -+} -+ -+#define MCP3564_CHANNELS(depth) { \ -+ MCP356X_V_CHANNEL(0, 0, depth), \ -+ MCP356X_V_CHANNEL(1, 1, depth), \ -+ MCP356X_V_CHANNEL(2, 2, depth), \ -+ MCP356X_V_CHANNEL(3, 3, depth), \ -+ MCP356X_V_CHANNEL(4, 4, depth), \ -+ MCP356X_V_CHANNEL(5, 5, depth), \ -+ MCP356X_V_CHANNEL(6, 6, depth), \ -+ MCP356X_V_CHANNEL(7, 7, depth), \ -+ MCP356X_T_CHAN(depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 1, 0x01, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 0, 0x10, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 2, 0x02, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 3, 0x03, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 2, 0x12, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 3, 0x13, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 3, 0x23, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 0, 0x20, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 0, 0x30, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 1, 0x21, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 1, 0x31, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 2, 0x32, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 4, 0x04, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 5, 0x05, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 6, 0x06, depth), \ -+ MCP356X_V_CHANNEL_DIFF(0, 7, 0x07, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 4, 0x14, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 5, 0x15, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 6, 0x16, depth), \ -+ MCP356X_V_CHANNEL_DIFF(1, 7, 0x17, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 4, 0x24, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 5, 0x25, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 6, 0x26, depth), \ -+ MCP356X_V_CHANNEL_DIFF(2, 7, 0x27, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 4, 0x34, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 5, 0x35, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 6, 0x36, depth), \ -+ MCP356X_V_CHANNEL_DIFF(3, 7, 0x37, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 5, 0x45, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 6, 0x46, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 7, 0x47, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 6, 0x56, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 7, 0x57, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 7, 0x67, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 0, 0x40, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 0, 0x50, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 0, 0x60, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 0, 0x70, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 1, 0x41, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 1, 0x51, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 1, 0x61, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 1, 0x71, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 2, 0x42, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 2, 0x52, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 2, 0x62, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 2, 0x72, depth), \ -+ MCP356X_V_CHANNEL_DIFF(4, 3, 0x43, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 3, 0x53, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 3, 0x63, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 3, 0x73, depth), \ -+ MCP356X_V_CHANNEL_DIFF(5, 4, 0x54, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 4, 0x64, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 4, 0x74, depth), \ -+ MCP356X_V_CHANNEL_DIFF(6, 5, 0x65, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 5, 0x75, depth), \ -+ MCP356X_V_CHANNEL_DIFF(7, 6, 0x76, depth) \ -+} -+ -+static const struct iio_chan_spec mcp3461_channels[] = MCP3561_CHANNELS(16); -+static const struct iio_chan_spec mcp3462_channels[] = MCP3562_CHANNELS(16); -+static const struct iio_chan_spec mcp3464_channels[] = MCP3564_CHANNELS(16); -+static const struct iio_chan_spec mcp3561_channels[] = MCP3561_CHANNELS(24); -+static const struct iio_chan_spec mcp3562_channels[] = MCP3562_CHANNELS(24); -+static const struct iio_chan_spec mcp3564_channels[] = MCP3564_CHANNELS(24); -+ -+static const struct mcp356x_chip_info mcp356x_chip_infos_tbl[] = { -+ [mcp3461] = { -+ .channels = mcp3461_channels, -+ .num_channels = ARRAY_SIZE(mcp3461_channels), -+ .int_vref_uv = 0, -+ .has_vref = false -+ }, -+ [mcp3462] = { -+ .channels = mcp3462_channels, -+ .num_channels = ARRAY_SIZE(mcp3462_channels), -+ .int_vref_uv = 0, -+ .has_vref = false -+ }, -+ [mcp3464] = { -+ .channels = mcp3464_channels, -+ .num_channels = ARRAY_SIZE(mcp3464_channels), -+ .int_vref_uv = 0, -+ .has_vref = false -+ }, -+ [mcp3461r] = { -+ .channels = mcp3461_channels, -+ .num_channels = ARRAY_SIZE(mcp3461_channels), -+ .int_vref_uv = MCP356XR_INT_VREF_MV, -+ .has_vref = true -+ }, -+ [mcp3462r] = { -+ .channels = mcp3462_channels, -+ .num_channels = ARRAY_SIZE(mcp3462_channels), -+ .int_vref_uv = MCP356XR_INT_VREF_MV, -+ .has_vref = true -+ }, -+ [mcp3464r] = { -+ .channels = mcp3464_channels, -+ .num_channels = ARRAY_SIZE(mcp3464_channels), -+ .int_vref_uv = MCP356XR_INT_VREF_MV, -+ .has_vref = true -+ }, -+ [mcp3561] = { -+ .channels = mcp3561_channels, -+ .num_channels = ARRAY_SIZE(mcp3561_channels), -+ .int_vref_uv = 0, -+ .has_vref = false -+ }, -+ [mcp3562] = { -+ .channels = mcp3562_channels, -+ .num_channels = ARRAY_SIZE(mcp3562_channels), -+ .int_vref_uv = 0, -+ .has_vref = false -+ }, -+ [mcp3564] = { -+ .channels = mcp3564_channels, -+ .num_channels = ARRAY_SIZE(mcp3564_channels), -+ .int_vref_uv = 0, -+ .has_vref = false -+ }, -+ [mcp3561r] = { -+ .channels = mcp3561_channels, -+ .num_channels = ARRAY_SIZE(mcp3561_channels), -+ .int_vref_uv = MCP356XR_INT_VREF_MV, -+ .has_vref = true -+ }, -+ [mcp3562r] = { -+ .channels = mcp3562_channels, -+ .num_channels = ARRAY_SIZE(mcp3562_channels), -+ .int_vref_uv = MCP356XR_INT_VREF_MV, -+ .has_vref = true -+ }, -+ [mcp3564r] = { -+ .channels = mcp3564_channels, -+ .num_channels = ARRAY_SIZE(mcp3564_channels), -+ .int_vref_uv = MCP356XR_INT_VREF_MV, -+ .has_vref = true -+ }, -+}; -+ -+static int mcp356x_read_single_value(struct iio_dev *indio_dev, -+ struct iio_chan_spec const *channel, -+ int *val) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ int ret, tmp, ret_read = 0; -+ -+ /* Configure MUX register with the requested channel */ -+ ret = mcp356x_write(adc, MCP356X_MUX, channel->address, 1); -+ if (ret) { -+ dev_err(&indio_dev->dev, "Failed to configure MUX register\n"); -+ return ret; -+ } -+ -+ /* ADC Conversion starts by writing ADC_MODE[1:0] = 11 to CONFIG0[1:0] = */ -+ ret = mcp356x_update(adc, MCP356X_CONFIG0, MCP356X_ADC_MODE_MASK, -+ MCP356X_ADC_CONVERSION_MODE, 1); -+ if (ret) { -+ dev_err(&indio_dev->dev, -+ "Failed to configure CONFIG0 register\n"); -+ return ret; -+ } -+ -+ /* -+ * Check if the conversion is ready. If not, wait a little bit, and -+ * in case of timeout exit with an error. -+ */ -+ -+ ret = read_poll_timeout(mcp356x_read, ret_read, -+ ret_read || !(tmp & MCP356X_DATA_READY_MASK), -+ 1000, MCP356X_DATA_READY_TIMEOUT_MS * 1000, true, -+ adc, MCP356X_IRQ, &tmp, 1); -+ -+ /* failed to read status register */ -+ if (ret_read) -+ return ret; -+ -+ if (ret) -+ return -ETIMEDOUT; -+ -+ if (tmp & MCP356X_DATA_READY_MASK) -+ /* failing to finish conversion */ -+ return -EBUSY; -+ -+ ret = mcp356x_read(adc, MCP356X_ADCDATA, &tmp, 4); -+ if (ret) -+ return ret; -+ -+ *val = tmp; -+ -+ return ret; -+} -+ -+static int mcp356x_read_avail(struct iio_dev *indio_dev, -+ struct iio_chan_spec const *channel, -+ const int **vals, int *type, -+ int *length, long mask) -+{ -+ switch (mask) { -+ case IIO_CHAN_INFO_OVERSAMPLING_RATIO: -+ *type = IIO_VAL_INT; -+ *vals = mcp356x_oversampling_avail; -+ *length = ARRAY_SIZE(mcp356x_oversampling_avail); -+ return IIO_AVAIL_LIST; -+ case IIO_CHAN_INFO_HARDWAREGAIN: -+ *type = IIO_VAL_FRACTIONAL; -+ *length = ARRAY_SIZE(mcp356x_hwgain_frac); -+ *vals = mcp356x_hwgain_frac; -+ return IIO_AVAIL_LIST; -+ case IIO_CHAN_INFO_CALIBBIAS: -+ *vals = mcp356x_calib_bias; -+ *type = IIO_VAL_INT; -+ return IIO_AVAIL_RANGE; -+ case IIO_CHAN_INFO_CALIBSCALE: -+ *vals = mcp356x_calib_scale; -+ *type = IIO_VAL_INT; -+ return IIO_AVAIL_RANGE; -+ default: -+ return -EINVAL; -+ } -+} -+ -+static int mcp356x_read_raw(struct iio_dev *indio_dev, -+ struct iio_chan_spec const *channel, -+ int *val, int *val2, long mask) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ int ret; -+ -+ mutex_lock(&adc->lock); -+ -+ switch (mask) { -+ case IIO_CHAN_INFO_RAW: -+ ret = mcp356x_read_single_value(indio_dev, channel, val); -+ if (ret) -+ ret = -EINVAL; -+ else -+ ret = IIO_VAL_INT; -+ break; -+ case IIO_CHAN_INFO_SCALE: -+ *val = adc->vref_mv; -+ *val2 = channel->scan_type.realbits - 1; -+ ret = IIO_VAL_FRACTIONAL_LOG2; -+ break; -+ case IIO_CHAN_INFO_OVERSAMPLING_RATIO: -+ *val = mcp356x_oversampling_avail[adc->oversampling]; -+ ret = IIO_VAL_INT; -+ break; -+ case IIO_CHAN_INFO_HARDWAREGAIN: -+ *val = mcp356x_hwgain_frac[2 * adc->hwgain]; -+ *val2 = mcp356x_hwgain_frac[(2 * adc->hwgain) + 1]; -+ ret = IIO_VAL_FRACTIONAL; -+ break; -+ case IIO_CHAN_INFO_CALIBBIAS: -+ *val = adc->calib_bias; -+ ret = IIO_VAL_INT; -+ break; -+ case IIO_CHAN_INFO_CALIBSCALE: -+ *val = adc->calib_scale; -+ ret = IIO_VAL_INT; -+ break; -+ default: -+ ret = -EINVAL; -+ } -+ -+ mutex_unlock(&adc->lock); -+ -+ return ret; -+} -+ -+static int mcp356x_write_raw(struct iio_dev *indio_dev, -+ struct iio_chan_spec const *channel, int val, -+ int val2, long mask) -+{ -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ int tmp; -+ int ret = -EINVAL; -+ -+ mutex_lock(&adc->lock); -+ switch (mask) { -+ case IIO_CHAN_INFO_CALIBBIAS: -+ if (val < mcp356x_calib_bias[0] && val > mcp356x_calib_bias[2]) -+ goto out; -+ -+ adc->calib_bias = val; -+ ret = mcp356x_write(adc, MCP356X_OFFSETCAL, val, 3); -+ break; -+ case IIO_CHAN_INFO_CALIBSCALE: -+ if (val < mcp356x_calib_bias[0] && val > mcp356x_calib_bias[2]) -+ goto out; -+ -+ adc->calib_scale = val; -+ ret = mcp356x_write(adc, MCP356X_GAINCAL, val, 3); -+ break; -+ case IIO_CHAN_INFO_OVERSAMPLING_RATIO: -+ if (val < 0) -+ goto out; -+ -+ adc->oversampling = find_closest(val, mcp356x_oversampling_avail, -+ ARRAY_SIZE(mcp356x_oversampling_avail)); -+ -+ dev_dbg(&adc->spi->dev, -+ "IIO_CHAN_INFO_OVERSAMPLING_RATIO index %d\n", -+ adc->oversampling); -+ -+ ret = mcp356x_update(adc, MCP356X_CONFIG1, MCP356X_OVERSAMPLING_RATIO_MASK, -+ (adc->oversampling << MCP356X_OVERSAMPLING_RATIO_SHIFT), -+ 1); -+ if (ret) -+ dev_err(&indio_dev->dev, -+ "Failed to configure CONFIG1 register\n"); -+ -+ break; -+ case IIO_CHAN_INFO_HARDWAREGAIN: -+ /* -+ * calculate gain from read values. -+ * avoid using fractional numbers so -+ * multiply the value with 1000. In case of x1/3 gain -+ * the tmp will be 300 -+ */ -+ tmp = ((val * 1000000) + val2) / 1000; -+ if (tmp < 1 || tmp > MAX_HWGAIN) -+ goto out; -+ -+ adc->hwgain = find_closest(tmp, mcp356x_hwgain, -+ ARRAY_SIZE(mcp356x_hwgain)); -+ -+ dev_dbg(&adc->spi->dev, -+ "IIO_CHAN_INFO_HARDWAREGAIN Gain:%d; index %d\n", -+ tmp, adc->hwgain); -+ -+ /* Update GAIN in CONFIG2[5:3] -> GAIN[2:0]*/ -+ ret = mcp356x_update(adc, MCP356X_CONFIG2, MCP356X_HARDWARE_GAIN_MASK, -+ (adc->hwgain << MCP356X_HARDWARE_GAIN_SHIFT), 1); -+ if (ret) -+ dev_err(&indio_dev->dev, -+ "Failed to configure CONFIG0 register\n"); -+ break; -+ } -+ -+out: -+ mutex_unlock(&adc->lock); -+ -+ return ret; -+} -+ -+static int mcp356x_config(struct mcp356x_state *adc) -+{ -+ int ret = 0; -+ unsigned int tmp; -+ -+ dev_dbg(&adc->spi->dev, "%s: Start config...\n", __func__); -+ -+ /* -+ * The address is set on a per-device basis by fuses in the factory, -+ * configured on request. If not requested, the fuses are set for 0x1. -+ * The device address is part of the device markings to avoid -+ * potential confusion. This address is coded on two bits, so four possible -+ * addresses are available when multiple devices are present on the same -+ * SPI bus with only one Chip Select line for all devices. -+ */ -+ device_property_read_u32(&adc->spi->dev, "microchip,hw-device-address", &tmp); -+ -+ if (tmp > 3) { -+ dev_err_probe(&adc->spi->dev, tmp, -+ "invalid device address. Must be in range 0-3.\n"); -+ return -EINVAL; -+ } -+ -+ adc->dev_addr = 0xff & tmp; -+ -+ dev_dbg(&adc->spi->dev, "use device address %i\n", adc->dev_addr); -+ -+ ret = mcp356x_read(adc, MCP356X_RESERVED_E, &tmp, 2); -+ -+ if (ret == 0) { -+ switch (tmp & MCP356X_HW_ID_MASK) { -+ case MCP3461_HW_ID: -+ dev_dbg(&adc->spi->dev, "Found MCP3461 chip\n"); -+ break; -+ case MCP3462_HW_ID: -+ dev_dbg(&adc->spi->dev, "Found MCP3462 chip\n"); -+ break; -+ case MCP3464_HW_ID: -+ dev_dbg(&adc->spi->dev, "Found MCP3464 chip\n"); -+ break; -+ case MCP3561_HW_ID: -+ dev_dbg(&adc->spi->dev, "Found MCP3561 chip\n"); -+ break; -+ case MCP3562_HW_ID: -+ dev_dbg(&adc->spi->dev, "Found MCP3562 chip\n"); -+ break; -+ case MCP3564_HW_ID: -+ dev_dbg(&adc->spi->dev, "Found MCP3564 chip\n"); -+ break; -+ default: -+ dev_err_probe(&adc->spi->dev, tmp, -+ "Unknown chip found\n"); -+ return -EINVAL; -+ } -+ } else { -+ return ret; -+ } -+ -+ /* Command sequence that ensures a recovery with -+ * the desired settings in any cases of loss-of-power scenario. -+ */ -+ -+ /* Write LOCK register to 0xA5 (Write Access Password) -+ * Write access is allowed on the full register map. -+ */ -+ ret = mcp356x_write(adc, MCP356X_LOCK, 0x000000A5, 1); -+ if (ret) -+ return ret; -+ -+ /* Write IRQ register to 0x03 */ -+ /* IRQ --> IRQ Mode = Hi-Z IRQ Output --> (0b00000011). -+ * IRQ = 0x00000003 -+ */ -+ ret = mcp356x_write(adc, MCP356X_IRQ, 0x00000003, 1); -+ if (ret) -+ return ret; -+ -+ /* Device Full Reset Fast Command */ -+ ret = mcp356x_fast_cmd(adc, MCP356X_FULL_RESET_CMD); -+ -+ /* wait 1ms for the chip to restart after a full reset */ -+ mdelay(1); -+ -+ /* Reconfigure the ADC chip */ -+ -+ /* GAINCAL --> Disabled. -+ * Default value is GAINCAL = 0x00800000; which provides a gain of 1x -+ */ -+ ret = mcp356x_write(adc, MCP356X_GAINCAL, 0x00800000, 3); -+ if (ret) -+ return ret; -+ -+ adc->calib_scale = 0x00800000; -+ -+ /* OFFSETCAL --> 0 Counts of Offset Cancellation -+ * (Measured offset is negative). -+ * OFFSETCAL = 0x0 -+ */ -+ ret = mcp356x_write(adc, MCP356X_OFFSETCAL, 0x00000000, 3); -+ if (ret) -+ return ret; -+ -+ /* TIMER --> Disabled. -+ * TIMER = 0x00000000 -+ */ -+ ret = mcp356x_write(adc, MCP356X_TIMER, 0x00000000, 3); -+ if (ret) -+ return ret; -+ -+ /* SCAN --> Disabled. -+ * SCAN = 0x00000000 -+ */ -+ ret = mcp356x_write(adc, MCP356X_SCAN, 0x00000000, 3); -+ if (ret) -+ return ret; -+ -+ /* MUX --> VIN+ = CH0, VIN- = CH1 --> (0b00000001). -+ * MUX = 0x00000001 -+ */ -+ ret = mcp356x_write(adc, MCP356X_MUX, 0x00000001, 1); -+ if (ret) -+ return ret; -+ -+ /* IRQ --> IRQ Mode = Hi-Z IRQ Output --> (0b00000011). -+ * IRQ = 0x00000003 -+ */ -+ ret = mcp356x_write(adc, MCP356X_IRQ, 0x00000003, 1); -+ if (ret) -+ return ret; -+ -+ /* CONFIG3 -+ * Conv. Mod = One-Shot/Standby, -+ * FORMAT = 32-bit (right justified data): SGN extension + ADC data, -+ * CRC_FORMAT = 16b, CRC-COM = Disabled, -+ * OFFSETCAL = Enabled, GAINCAL = Enabled --> (10100011). -+ * CONFIG3 = 0x000000A3 -+ * -+ */ -+ ret = mcp356x_write(adc, MCP356X_CONFIG3, 0x000000A3, 1); -+ if (ret) -+ return ret; -+ -+ /* CONFIG2 --> BOOST = 1x, GAIN = 1x, AZ_MUX = 1 --> (0b10001101). -+ * CONFIG2 = 0x0000008D -+ */ -+ ret = mcp356x_write(adc, MCP356X_CONFIG2, 0x0000008D, 1); -+ if (ret) -+ return ret; -+ -+ adc->hwgain = 0x01; -+ adc->auto_zeroing_mux = true; -+ adc->auto_zeroing_ref = false; -+ adc->current_boost_mode = MCP356X_BOOST_CURRENT_x1_00; -+ -+ /* CONFIG1 --> AMCLK = MCLK, OSR = 98304 --> (0b00111100). -+ * CONFIG1 = 0x0000003C -+ */ -+ ret = mcp356x_write(adc, MCP356X_CONFIG1, 0x0000003C, 1); -+ if (ret) -+ return ret; -+ -+ adc->oversampling = 0x0F; -+ -+ if (!adc->vref) { -+ /* CONFIG0 --> VREF_SEL = Internal Voltage Reference 2.4v -+ * CLK_SEL = INTOSC w/o CLKOUT, CS_SEL = No Bias, -+ * ADC_MODE = Standby Mode --> (0b11100010). -+ * CONFIG0 = 0x000000E2 -+ */ -+ ret = mcp356x_write(adc, MCP356X_CONFIG0, 0x000000E2, 1); -+ -+ dev_dbg(&adc->spi->dev, "%s: Using internal Vref\n", -+ __func__); -+ adc->vref_mv = MCP356XR_INT_VREF_MV; -+ -+ } else { -+ /* CONFIG0 --> CLK_SEL = INTOSC w/o CLKOUT, CS_SEL = No Bias, -+ * ADC_MODE = Standby Mode --> (0b01100010). -+ * CONFIG0 = 0x000000E2 -+ */ -+ ret = mcp356x_write(adc, MCP356X_CONFIG0, 0x00000062, 1); -+ } -+ adc->current_bias_mode = MCP356X_CS_SEL_0_0_uA; -+ -+ return ret; -+} -+ -+static int mcp356x_probe(struct spi_device *spi) -+{ -+ int ret, device_index; -+ struct iio_dev *indio_dev; -+ struct mcp356x_state *adc; -+ -+ indio_dev = devm_iio_device_alloc(&spi->dev, sizeof(*adc)); -+ if (!indio_dev) { -+ dev_err_probe(&indio_dev->dev, PTR_ERR(indio_dev), -+ "Can't allocate iio device\n"); -+ return -ENOMEM; -+ } -+ -+ adc = iio_priv(indio_dev); -+ adc->spi = spi; -+ -+ dev_dbg(&adc->spi->dev, "%s: probe(spi = 0x%p)\n", __func__, spi); -+ -+ adc->vref = devm_regulator_get_optional(&adc->spi->dev, "vref"); -+ if (IS_ERR(adc->vref)) { -+ if (PTR_ERR(adc->vref) == -ENODEV) { -+ adc->vref = NULL; -+ dev_dbg(&adc->spi->dev, "%s: Using internal Vref\n", -+ __func__); -+ } else { -+ dev_err_probe(&adc->spi->dev, PTR_ERR(adc->vref), -+ "failed to get regulator\n"); -+ return PTR_ERR(adc->vref); -+ } -+ } else { -+ ret = regulator_enable(adc->vref); -+ if (ret) -+ return ret; -+ -+ dev_dbg(&adc->spi->dev, "%s: Using External Vref\n", -+ __func__); -+ -+ ret = regulator_get_voltage(adc->vref); -+ if (ret < 0) { -+ dev_err_probe(&adc->spi->dev, ret, -+ "Failed to read vref regulator\n"); -+ goto error_disable_reg; -+ } -+ -+ adc->vref_mv = ret / 1000; -+ } -+ -+ spi_set_drvdata(spi, indio_dev); -+ device_index = spi_get_device_id(spi)->driver_data; -+ adc->chip_info = &mcp356x_chip_infos_tbl[device_index]; -+ -+ adc->mcp356x_info.read_raw = mcp356x_read_raw; -+ adc->mcp356x_info.write_raw = mcp356x_write_raw; -+ adc->mcp356x_info.read_avail = mcp356x_read_avail; -+ -+ ret = mcp356x_prep_custom_attributes(adc, indio_dev); -+ if (ret) { -+ dev_err_probe(&adc->spi->dev, ret, -+ "Can't configure custom attributes for MCP356X device\n"); -+ goto error_disable_reg; -+ } -+ -+ indio_dev->name = spi_get_device_id(spi)->name; -+ indio_dev->modes = INDIO_DIRECT_MODE; -+ indio_dev->info = &adc->mcp356x_info; -+ -+ indio_dev->channels = adc->chip_info->channels; -+ indio_dev->num_channels = adc->chip_info->num_channels; -+ indio_dev->masklength = adc->chip_info->num_channels - 1; -+ -+ /* initialize the chip access mutex */ -+ mutex_init(&adc->lock); -+ -+ /* Do any chip specific initialization, e.g: -+ * read/write some registers -+ * enable/disable certain channels -+ * change the sampling rate to the requested value -+ */ -+ ret = mcp356x_config(adc); -+ if (ret) { -+ dev_err_probe(&adc->spi->dev, ret, -+ "Can't configure MCP356X device\n"); -+ goto error_disable_reg; -+ } -+ -+ dev_dbg(&adc->spi->dev, "%s: Vref (mV): %d\n", __func__, adc->vref_mv); -+ -+ ret = devm_iio_device_register(&spi->dev, indio_dev); -+ if (ret) { -+ dev_err_probe(&adc->spi->dev, ret, -+ "Can't register IIO device\n"); -+ goto error_disable_reg; -+ } -+ -+ return 0; -+ -+error_disable_reg: -+ if (adc->vref) -+ regulator_disable(adc->vref); -+ -+ return ret; -+} -+ -+static void mcp356x_remove(struct spi_device *spi) -+{ -+ struct iio_dev *indio_dev = spi_get_drvdata(spi); -+ struct mcp356x_state *adc = iio_priv(indio_dev); -+ -+ if (adc->vref) -+ regulator_disable(adc->vref); -+} -+ -+static const struct of_device_id mcp356x_dt_ids[] = { -+ { .compatible = "microchip,mcp3461" }, -+ { .compatible = "microchip,mcp3462" }, -+ { .compatible = "microchip,mcp3464" }, -+ { .compatible = "microchip,mcp3461r" }, -+ { .compatible = "microchip,mcp3462r" }, -+ { .compatible = "microchip,mcp3464r" }, -+ { .compatible = "microchip,mcp3561" }, -+ { .compatible = "microchip,mcp3562" }, -+ { .compatible = "microchip,mcp3564" }, -+ { .compatible = "microchip,mcp3561r" }, -+ { .compatible = "microchip,mcp3562r" }, -+ { .compatible = "microchip,mcp3564r" }, -+ { } -+}; -+MODULE_DEVICE_TABLE(of, mcp356x_dt_ids); -+ -+static const struct spi_device_id mcp356x_id[] = { -+ { "mcp3461", mcp3461 }, -+ { "mcp3462", mcp3462 }, -+ { "mcp3464", mcp3464 }, -+ { "mcp3461r", mcp3461r }, -+ { "mcp3462r", mcp3462r }, -+ { "mcp3464r", mcp3464r }, -+ { "mcp3561", mcp3561 }, -+ { "mcp3562", mcp3562 }, -+ { "mcp3564", mcp3564 }, -+ { "mcp3561r", mcp3561r }, -+ { "mcp3562r", mcp3562r }, -+ { "mcp3564r", mcp3564r }, -+ { } -+}; -+MODULE_DEVICE_TABLE(spi, mcp356x_id); -+ -+static struct spi_driver mcp356x_driver = { -+ .driver = { -+ .name = "mcp3564", -+ .of_match_table = mcp356x_dt_ids, -+ }, -+ .probe = mcp356x_probe, -+ .remove = mcp356x_remove, -+ .id_table = mcp356x_id, -+}; -+ -+module_spi_driver(mcp356x_driver); -+ -+MODULE_AUTHOR("Marius Cristea "); -+MODULE_DESCRIPTION("Microchip MCP346x/MCP346xR and MCP356x/MCP346xR ADCs"); -+MODULE_LICENSE("GPL v2"); -+MODULE_VERSION("0.1.2"); --- -2.39.2 - diff --git a/patches/fix/0005-Microchip-QSPI-Add-regular-transfers.patch b/patches/fix/0005-Microchip-QSPI-Add-regular-transfers.patch deleted file mode 100644 index b691b57..0000000 --- a/patches/fix/0005-Microchip-QSPI-Add-regular-transfers.patch +++ /dev/null @@ -1,275 +0,0 @@ -From 0eeed461b7b86e3b822984b1c266316ac70ccf69 Mon Sep 17 00:00:00 2001 -From: vauban353 -Date: Sun, 6 Aug 2023 09:37:40 +0100 -Subject: [PATCH 5/8] Microchip QSPI: Add regular transfers. - ---- - drivers/spi/spi-microchip-core-qspi.c | 226 +++++++++++++++++++++++++- - 1 file changed, 223 insertions(+), 3 deletions(-) - -diff --git a/drivers/spi/spi-microchip-core-qspi.c b/drivers/spi/spi-microchip-core-qspi.c -index 33c19b98b..5f1623ac4 100644 ---- a/drivers/spi/spi-microchip-core-qspi.c -+++ b/drivers/spi/spi-microchip-core-qspi.c -@@ -1,3 +1,4 @@ -+ - // SPDX-License-Identifier: (GPL-2.0) - /* - * Microchip coreQSPI QSPI controller driver -@@ -117,10 +118,10 @@ struct mchp_coreqspi { - struct completion data_completion; - struct mutex op_lock; /* lock access to the device */ - u8 *txbuf; -- u8 *rxbuf; -+ volatile u8 *rxbuf; - int irq; -- int tx_len; -- int rx_len; -+ volatile int tx_len; -+ volatile int rx_len; - }; - - static int mchp_coreqspi_set_mode(struct mchp_coreqspi *qspi, const struct spi_mem_op *op) -@@ -222,6 +223,68 @@ static inline void mchp_coreqspi_write_op(struct mchp_coreqspi *qspi, bool word) - } - } - -+static inline void mchp_coreqspi_write_read_op(struct mchp_coreqspi *qspi, bool last) -+{ -+ u32 frames, control, data; -+ qspi->rx_len = qspi->tx_len; -+ -+ control = readl_relaxed(qspi->regs + REG_CONTROL); -+ control |= CONTROL_FLAGSX4; -+ writel_relaxed(control, qspi->regs + REG_CONTROL); -+ -+ while (qspi->tx_len >= 4) { -+ while (readl_relaxed(qspi->regs + REG_STATUS) & STATUS_TXFIFOFULL) -+ ; -+ -+ data = *(u32 *)qspi->txbuf; -+ qspi->txbuf += 4; -+ qspi->tx_len -= 4; -+ writel_relaxed(data, qspi->regs + REG_X4_TX_DATA); -+ -+ if (qspi->rx_len >= 8) { -+ if (readl_relaxed(qspi->regs + REG_STATUS) & STATUS_RXAVAILABLE) { -+ data = readl_relaxed(qspi->regs + REG_X4_RX_DATA); -+ *(u32 *)qspi->rxbuf = data; -+ qspi->rxbuf += 4; -+ qspi->rx_len -= 4; -+ } -+ } -+ } -+ -+ if (!last ) { -+ while (qspi->rx_len >= 4) { -+ while (readl_relaxed(qspi->regs + REG_STATUS) & STATUS_RXFIFOEMPTY) -+ ; -+ data = readl_relaxed(qspi->regs + REG_X4_RX_DATA); -+ *(u32 *)qspi->rxbuf = data; -+ qspi->rxbuf += 4; -+ qspi->rx_len -= 4; -+ } -+ } -+ -+ if (qspi->tx_len) { -+ control &= ~CONTROL_FLAGSX4; -+ writel_relaxed(control, qspi->regs + REG_CONTROL); -+ -+ -+ while (qspi->tx_len--) { -+ while (readl_relaxed(qspi->regs + REG_STATUS) & STATUS_TXFIFOFULL) -+ ; -+ data = *qspi->txbuf++; -+ writel_relaxed(data, qspi->regs + REG_TX_DATA); -+ } -+ if (!last) { -+ while (qspi->rx_len--) { -+ while (readl_relaxed(qspi->regs + REG_STATUS) & STATUS_RXFIFOEMPTY) -+ ; -+ data = readl_relaxed(qspi->regs + REG_RX_DATA); -+ *qspi->rxbuf++ = (data & 0xFF); -+ } -+ } -+ } -+} -+ -+ - static void mchp_coreqspi_enable_ints(struct mchp_coreqspi *qspi) - { - u32 mask = IEN_TXDONE | -@@ -497,6 +560,160 @@ static const struct spi_controller_mem_ops mchp_coreqspi_mem_ops = { - .exec_op = mchp_coreqspi_exec_op, - }; - -+static int mchp_coreqspi_transfer_one_message(struct spi_controller *ctlr, -+ struct spi_message *m) -+{ -+ struct mchp_coreqspi *qspi = spi_controller_get_devdata(ctlr); -+ struct spi_transfer *t = NULL; -+ u32 control, frames, status; -+ u32 total_bytes, cmd_bytes = 0, idle_cycles = 0; -+ int ret; -+ bool quad = false, dual = false; -+ bool keep_cs = false; -+ -+ mutex_lock(&qspi->op_lock); -+ ret = readl_poll_timeout(qspi->regs + REG_STATUS, status, -+ (status & STATUS_READY), 0, -+ TIMEOUT_MS); -+ if (ret) { -+ dev_err(&ctlr->dev, -+ "Timeout waiting on QSPI ready.\n"); -+ return -ETIMEDOUT; -+ } -+ -+ ret = mchp_coreqspi_setup_clock(qspi, m->spi); -+ if (ret) -+ goto error; -+ -+ if (m->spi->cs_gpiod) { -+ if (m->spi->mode & SPI_CS_HIGH) { -+ gpiod_set_value(m->spi->cs_gpiod, 0); -+ } else { -+ gpiod_set_value(m->spi->cs_gpiod, 1); -+ } -+ } -+ -+ control = readl_relaxed(qspi->regs + REG_CONTROL); -+ control &= ~(CONTROL_MODE12_MASK | -+ CONTROL_MODE0); -+ writel_relaxed(control, qspi->regs + REG_CONTROL); -+ -+ reinit_completion(&qspi->data_completion); -+ -+ /* Check the total bytes and command bytes */ -+ list_for_each_entry(t, &m->transfers, transfer_list) { -+ total_bytes += t->len; -+ if ((!cmd_bytes) && !(t->tx_buf && t->rx_buf)) -+ cmd_bytes = t->len; -+ if (!t->rx_buf) -+ cmd_bytes = total_bytes; -+ if (t->tx_nbits == SPI_NBITS_QUAD || t->rx_nbits == SPI_NBITS_QUAD) -+ quad = true; -+ else if (t->tx_nbits == SPI_NBITS_DUAL || t->rx_nbits == SPI_NBITS_DUAL) -+ dual = true; -+ } -+ -+ control = readl_relaxed(qspi->regs + REG_CONTROL); -+ if (quad) { -+ control |= (CONTROL_MODE0 | CONTROL_MODE12_EX_RW); -+ } else if (dual) { -+ control &= ~CONTROL_MODE0; -+ control |= CONTROL_MODE12_FULL; -+ } else { -+ control &= ~(CONTROL_MODE12_MASK | -+ CONTROL_MODE0); -+ } -+ -+ writel_relaxed(control, qspi->regs + REG_CONTROL); -+ frames = total_bytes & BYTESUPPER_MASK; -+ writel_relaxed(frames, qspi->regs + REG_FRAMESUP); -+ frames = total_bytes & BYTESLOWER_MASK; -+ frames |= cmd_bytes << FRAMES_CMDBYTES_SHIFT; -+ frames |= idle_cycles << FRAMES_IDLE_SHIFT; -+ control = readl_relaxed(qspi->regs + REG_CONTROL); -+ if (control & CONTROL_MODE12_MASK) -+ frames |= (1 << FRAMES_SHIFT); -+ -+ frames |= FRAMES_FLAGWORD; -+ writel_relaxed(frames, qspi->regs + REG_FRAMES); -+ -+ list_for_each_entry(t, &m->transfers, transfer_list) { -+ -+ if ((t->tx_buf) && (t->rx_buf)){ -+ bool last = false; -+ qspi->txbuf = (u8 *)t->tx_buf; -+ qspi->rxbuf = (u8 *)t->rx_buf; -+ qspi->tx_len = t->len; -+ if (list_is_last(&t->transfer_list, &m->transfers)) -+ last = true; -+ mchp_coreqspi_write_read_op(qspi, last); -+ } else if (t->tx_buf) { -+ qspi->txbuf = (u8 *)t->tx_buf; -+ qspi->tx_len = t->len; -+ mchp_coreqspi_write_op(qspi, true); -+ } else { -+ qspi->rxbuf = (u8 *)t->rx_buf; -+ qspi->rx_len = t->len; -+ } -+ -+ if (t->cs_change) { -+ if (list_is_last(&t->transfer_list, -+ &m->transfers)) { -+ keep_cs = true; -+ } else { -+ if (!t->cs_off) { -+// gpiod_set_value(m->spi->cs_gpiod, 0); -+ if (m->spi->mode & SPI_CS_HIGH) { -+ gpiod_set_value(m->spi->cs_gpiod, 0); -+ } else { -+ gpiod_set_value(m->spi->cs_gpiod, 1); -+ } -+ } -+// _spi_transfer_cs_change_delay(m, t); -+ if (!list_next_entry(t, transfer_list)->cs_off) { -+// spi_set_cs(m->spi, true, false); -+ if (m->spi->mode & SPI_CS_HIGH) { -+// gpiod_set_value(m->spi->cs_gpiod, 0); -+ gpiod_set_value(m->spi->cs_gpiod, 1); -+ } else { -+// gpiod_set_value(m->spi->cs_gpiod, 1); -+ gpiod_set_value(m->spi->cs_gpiod, 0); -+ } -+// gpiod_set_value(m->spi->cs_gpiod, 1); -+ } -+ } -+ } else if (!list_is_last(&t->transfer_list, &m->transfers) && -+ t->cs_off != list_next_entry(t, transfer_list)->cs_off) { -+// spi_set_cs(m->spi, t->cs_off, false); -+ if (m->spi->mode & SPI_CS_HIGH) { -+ gpiod_set_value(m->spi->cs_gpiod, !t->cs_off); -+ } else { -+ gpiod_set_value(m->spi->cs_gpiod, !t->cs_off); -+ } -+ } -+ -+ -+ -+ } -+ -+ mchp_coreqspi_enable_ints(qspi); -+ -+ if (!wait_for_completion_timeout(&qspi->data_completion, msecs_to_jiffies(1000))) -+ ret = -ETIMEDOUT; -+ -+ m->actual_length = total_bytes; -+ -+error: -+ if (ret != 0 || !keep_cs) -+ gpiod_set_value(m->spi->cs_gpiod, 0); -+ -+ m->status = ret; -+ spi_finalize_current_message(ctlr); -+ mutex_unlock(&qspi->op_lock); -+ mchp_coreqspi_disable_ints(qspi); -+ return ret; -+} -+ - static int mchp_coreqspi_probe(struct platform_device *pdev) - { - struct spi_controller *ctlr; -@@ -550,6 +767,9 @@ static int mchp_coreqspi_probe(struct platform_device *pdev) - ctlr->mode_bits = SPI_CPOL | SPI_CPHA | SPI_RX_DUAL | SPI_RX_QUAD | - SPI_TX_DUAL | SPI_TX_QUAD; - ctlr->dev.of_node = np; -+ ctlr->transfer_one_message = mchp_coreqspi_transfer_one_message; -+ ctlr->num_chipselect = 2; -+ ctlr->use_gpio_descriptors = true; - - ret = devm_spi_register_controller(&pdev->dev, ctlr); - if (ret) { --- -2.39.2 - diff --git a/patches/fix/0006-BeagleV-Fire-Add-printk-to-IM219-driver-for-board-te.patch b/patches/fix/0006-BeagleV-Fire-Add-printk-to-IM219-driver-for-board-te.patch deleted file mode 100644 index b2aad86..0000000 --- a/patches/fix/0006-BeagleV-Fire-Add-printk-to-IM219-driver-for-board-te.patch +++ /dev/null @@ -1,45 +0,0 @@ -From 747c6d5984cccf7c3e48c2cdb4dd1d626889096e Mon Sep 17 00:00:00 2001 -From: vauban353 -Date: Sat, 12 Aug 2023 18:14:01 +0100 -Subject: [PATCH 6/8] BeagleV-Fire: Add printk to IM219 driver for board tests. - ---- - drivers/media/i2c/imx219.c | 8 ++++++++ - 1 file changed, 8 insertions(+) - -diff --git a/drivers/media/i2c/imx219.c b/drivers/media/i2c/imx219.c -index 7a14688f8..effb399b1 100644 ---- a/drivers/media/i2c/imx219.c -+++ b/drivers/media/i2c/imx219.c -@@ -1181,6 +1181,9 @@ static int imx219_identify_module(struct imx219 *imx219) - int ret; - u32 val; - -+ printk(KERN_INFO "imx219_identify_module()\n"); -+ -+ - ret = imx219_read_reg(imx219, IMX219_REG_CHIP_ID, - IMX219_REG_VALUE_16BIT, &val); - if (ret) { -@@ -1195,6 +1198,9 @@ static int imx219_identify_module(struct imx219 *imx219) - return -EIO; - } - -+ printk(KERN_INFO "imx219_identify_module() - Success\n"); -+ -+ - return 0; - } - -@@ -1402,6 +1408,8 @@ static int imx219_probe(struct i2c_client *client) - struct imx219 *imx219; - int ret; - -+ printk(KERN_INFO "imx219_probe()\n"); -+ - imx219 = devm_kzalloc(&client->dev, sizeof(*imx219), GFP_KERNEL); - if (!imx219) - return -ENOMEM; --- -2.39.2 - diff --git a/patches/fix/0007-MMC-SPI-Hack-to-support-non-DMA-capable-SPI-ctrl.patch b/patches/fix/0007-MMC-SPI-Hack-to-support-non-DMA-capable-SPI-ctrl.patch deleted file mode 100644 index 7953390..0000000 --- a/patches/fix/0007-MMC-SPI-Hack-to-support-non-DMA-capable-SPI-ctrl.patch +++ /dev/null @@ -1,66 +0,0 @@ -From e9aea028119afd0858e77989dd1a4ecc21d30dc1 Mon Sep 17 00:00:00 2001 -From: vauban353 -Date: Sun, 6 Aug 2023 11:13:27 +0100 -Subject: [PATCH 7/8] MMC SPI: Hack to support non DMA capable SPI ctrl. - ---- - drivers/mmc/host/mmc_spi.c | 6 +++++- - drivers/spi/internals.h | 3 +++ - drivers/spi/spi.c | 3 +++ - 3 files changed, 11 insertions(+), 1 deletion(-) - -diff --git a/drivers/mmc/host/mmc_spi.c b/drivers/mmc/host/mmc_spi.c -index cc333ad67..fb45c7fa4 100644 ---- a/drivers/mmc/host/mmc_spi.c -+++ b/drivers/mmc/host/mmc_spi.c -@@ -29,6 +29,9 @@ - - #include - -+//: -+#undef CONFIG_HAS_DMA -+//#define DEBUG 1 - - /* NOTES: - * -@@ -1375,7 +1378,8 @@ static int mmc_spi_probe(struct spi_device *spi) - * that's the only reason not to use a few MHz for f_min (until - * the upper layer reads the target frequency from the CSD). - */ -- mmc->f_min = 400000; -+// mmc->f_min = 400000; -+ mmc->f_min = 5000000; - mmc->f_max = spi->max_speed_hz; - - host = mmc_priv(mmc); -diff --git a/drivers/spi/internals.h b/drivers/spi/internals.h -index 4a28a8395..c49350240 100644 ---- a/drivers/spi/internals.h -+++ b/drivers/spi/internals.h -@@ -12,6 +12,9 @@ - #ifndef __LINUX_SPI_INTERNALS_H - #define __LINUX_SPI_INTERNALS_H - -+//: -+#undef CONFIG_HAS_DMA -+ - #include - #include - #include -diff --git a/drivers/spi/spi.c b/drivers/spi/spi.c -index a221478e5..e198049cc 100644 ---- a/drivers/spi/spi.c -+++ b/drivers/spi/spi.c -@@ -42,6 +42,9 @@ EXPORT_TRACEPOINT_SYMBOL(spi_transfer_stop); - - #include "internals.h" - -+//: -+#undef CONFIG_HAS_DMA -+ - static DEFINE_IDR(spi_master_idr); - - static void spidev_release(struct device *dev) --- -2.39.2 - diff --git a/patches/fix/0008-Add-wireless-regdb-regulatory-database-file.patch b/patches/fix/0008-Add-wireless-regdb-regulatory-database-file.patch deleted file mode 100644 index cd33500..0000000 --- a/patches/fix/0008-Add-wireless-regdb-regulatory-database-file.patch +++ /dev/null @@ -1,100 +0,0 @@ -From 17558b89548b694599af7d6144426f30fe83e2c7 Mon Sep 17 00:00:00 2001 -From: Robert Nelson -Date: Sun, 10 Sep 2023 19:07:40 -0500 -Subject: [PATCH 8/8] Add wireless-regdb regulatory database file - -https://git.kernel.org/pub/scm/linux/kernel/git/sforshee/wireless-regdb.git/commit/?id=991b1ef696b7a034a5bf001cf31ab7735888c6e1 -Signed-off-by: Robert Nelson ---- - firmware/regulatory.db | Bin 0 -> 4896 bytes - firmware/regulatory.db.p7s | Bin 0 -> 1182 bytes - 2 files changed, 0 insertions(+), 0 deletions(-) - create mode 100644 firmware/regulatory.db - create mode 100644 firmware/regulatory.db.p7s - -diff --git a/firmware/regulatory.db b/firmware/regulatory.db -new file mode 100644 -index 0000000000000000000000000000000000000000..ebdc7e354e9c2317f9b862300bdc9381def4f0e0 -GIT binary patch -literal 4896 -zcmZvfe~eUD702(r=j>0)_OTf^7As;4Bqd5#YLK8s-kY7BnVnyc`L#P^e~FO@Dt6lR -zM?_azsUoYjXbH8g6tS%|!Glth5V7H5c)=ZkOKt)i?kG;WX`FJiaMsP??QWj9Nc$yp-7+-Y -z3jE3)r@cDf?YVHt^Kg$hg3oygXnLdA@RIa5g`e`WIO*lk_42sGE8w$U5tn!+-0PKT -zzeb-rz7%)yL-A4E7*D~)cp4k=EbfTsp%pLCx`;Q&D>xLNz`gMrG~;z>j!=$~41IFA -zW~4x$IzEz!4rvQOZ49gbPUz-b#+(P00k_mmI~ZWC|O}EdBNA -zQ-o%+jBAn=T$QZhkyHk6NaeASD#9zNGPG}9w^O`7!6S@hF+Je)4#bLkRXO4BUH -za@ZIv;I1(rGnoWFlu6-aCXd@QJ|;3noSzxTt(h9`&D7yU*26|Nj@z?oxRlM{&Dj!8 -zW=SJUIkHt~=3LyGi^JL62z?Utp;~h(baNTFl*{AZTmcW|eB$-AU&P5A#pWusUxm{- -zI*;50HgYw5ET6<@@@aJQS!m`9a53-Wj(i=b3pt$hUHqU=XY7-DF2uXnMpn82xG0h&eXxmZD29LGk<#mN%Qq?E+L63x0qXHufMm8h;# -z6>Fs$rps~MUmn59auPR}Y3AiTZY>w#WVuZ1aa>%kK!lP=2`;NwK7iCUA(_eJ=5J4*DIkutOSmM=pO44-PcQE -zDR4Akr?+QT%zJRP7`TDFduAOmZ(7WM=?*dfckAYu)&qSrLag0p>{rO2`RaX|d9CB$ -zw@&ktCxuu#P4Q0QduDd79*(y; -zwEx)`BEQ(w%XVh2pX;+Zj1TQ$e9+&!iI;x)fQctP$voqTWdp-nzpsN?f9!9EM0N?; -zDW5}}-#sh}#}8?ab??{gzh_p+)!Sl&6wmg6g%HoTV?v)$!}b{rbVHvG4s=?!cFdu( -z=*%@3-HUaw)*0;orX8p6gr(y+bY?cUH8#D$JvytJ(!R2SbHK4b11sV-ixFZ%({Mw#wJ#7;RPOf|Nd=76@HIA-aG=N9^N -z-+Yc1bB(c~ckVgYM)#bURTt~pd37GE4xJ~;dKO5}sg+ybDb4%!otmr7u#Rch7Wj0q -z_KEcl8(rfwS8KpSVeNrNjP9zH*W`)r&Gi>*hW&(^^gLM_juZA4+Iwiu^z4Ms2hXc? -z@35%cCG_)y^bWO|`_lZFqwT$Yw`d;!M9TOFc4mH_x}zNHU^8!;3u}fkVGRMt!WshR -znAlKIm$m00^=j!*T!hUTMECUj#fou|&Oq~)SzUj-7Q=J37&i5XnqdshxOCJP<<_j3 -zNx+r!^q%Hti)T#s>MGyl;GE3c%{xffO+3EXyvJ>(nVP-=JF%{TzuQ=YV|ea-ha(*1 -z9H$!X8Z-ybr}ig1KPOl5xv^f@Q&3}@Ej?XRl+9ei8jMCvvBs%WVng2nu2K8&_e6#6 -z5}#xEyz*Q)k7hb&oB4gsT#G-f`{egK$4;C*ul@Nq12fw>p8aj+@60Hh__lwb7qXzf -zBL38q&HOysEUx-%lYA7y=y>pwjZ*1#IHM|q=rj&P2_r)So|?88DVzD%=)^O`TlwrN(~UWDnc -zMfvJ|5mp@>>W6yto0|Rcqqof%edlKf?@WB -zww>Z>4X=M(>q8%P{(|_2oG;%c_sEykAy^B~lIA=q#LvZx;y2>BT&@@G{| -z9`$$FXnb`2x2pfb)9^g}1iENGC*)@JN2tT@K;xubO7)CVKi|-rCuKqnDG&N#H}rxK -zr{#O)LF#C&dKEqk-_tWWEtk{IE$RyQOga7}H>x%20s#4+l^fK{q}@gPP5FM+r84RY -z=hDox+@j-pH0RZIYNPrOokiHwYw|`lUu}hjP}MQ7$*NkWHiLrufnzR{eUVzBeh*{t -zg&@ymxkVmPPr*uJuIIA+nmj{xu7TIDs%aQ&`~Gl_sosCfd*osDRai!Lau+T7%YC=x -z0(p&mNFGy%;Z}H1pIuAOW&#Gtr$_tL)pE5;{T2rG`Eu?S)iMn$b#7jVbpf4yOWrBz -z8x&B-QeIdQ_%Z|`#- -z-wm{R{Y20YulK?7c1^^vCh+@?oK<^*S|3+mf$Q}7w&dgBwf&!zXVjFQc}vndn0ZU` -zjK2<}QgROUqL~H#9PE-swNMpc -jkn<>J>#Vh%{SRw@IvcW^8c9=jktWSr_Q@6UU$E$Y57IP8L6oT -z3gWzm=7t6aW`>p~2F9jQ68uJnhUNyAhDJ~U?An?bm5_}Gx`?@nk)HwR0xqT|Mn;CM -z4v*((v{*8Kvb>(A<7gqerfz9-p=#ZPnvA>o_BXFbTFkG>3OdBBrCXQwMQ*cDfkO0^ -z=|;AN-PY0^;v(6JN5Z?OiOKv`xysG?GefZD_o+ahi>{Kl1YEjq{wrJgH$hi|TVv`b -z-B%qmc3cco{17bvktzSB+w95l8WZ@}nElF7E({O*cINW^TCJPX#jdY+skgqbs$Y7# -z;kbd>rQmmO*2q0K{AjjlPV%wT=z7)CjD@c**D=J*io2m8VN}kpDU>E>R{VTAi=+9* -zjYZmD7HTTgOsnM9zHsB-i5&aMzmLAF2oe;PuKM;UW9IYUZelHuk1u@o;F8AX=M0{IyM6Wwa{mIf7OHQT7tSL%AoG*M>*R=9_*YmGe6b-ztep`IAGVBw- -z!1vkYwQ2f*qmwdu%Ti1qxCzl8GMutX;+>(KaknSwU#Nh -zc=g}&Q_k>OCH%D!(HApbsVILsU}Hb?y9H@0#VSP%n;5qNQ^_V^qBc;#nzqnVFjAsl -zkZB+RPtu&shRAuqKn5YhYRE6nYh-L-X<%q*X=-L_9%Z19kYzDcVo~7o+FSLAmwk6Z -zil+IQO`29k%L3dD-YtpB>}ZOdACa7a9Cg6N&C; - clock-frequency = <50000000>; - }; - - fabric_clk1: fabric-clk1 { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <125000000>; - }; - - fabric-bus@40000000 { - compatible = "simple-bus"; - #address-cells = <2>; - #size-cells = <2>; - ranges = <0x0 0x40000000 0x0 0x40000000 0x0 0x20000000>, /* FIC3-FAB */ - <0x0 0x60000000 0x0 0x60000000 0x0 0x20000000>, /* FIC0, LO */ - <0x0 0xe0000000 0x0 0xe0000000 0x0 0x20000000>, /* FIC1, LO */ - <0x20 0x0 0x20 0x0 0x10 0x0>, /* FIC0,HI */ - <0x30 0x0 0x30 0x0 0x10 0x0>; /* FIC1,HI */ - - cape_gpios_p8: gpio@41100000 { - compatible = "microchip,coregpio-rtl-v3"; - reg = <0x0 0x41100000 0x0 0x1000>; - clocks = <&fabric_clk3>; - gpio-controller; - #gpio-cells = <2>; - ngpios = <16>; - gpio-line-names = "P8_PIN31", "P8_PIN32", "P8_PIN33", "P8_PIN34", - "P8_PIN35", "P8_PIN36", "P8_PIN37", "P8_PIN38", - "P8_PIN39", "P8_PIN40", "P8_PIN41", "P8_PIN42", - "P8_PIN43", "P8_PIN44", "P8_PIN45", "P8_PIN46"; - }; - - cape_gpios_p9: gpio@41200000 { - compatible = "microchip,coregpio-rtl-v3"; - reg = <0x0 0x41200000 0x0 0x1000>; - clocks = <&fabric_clk3>; - gpio-controller; - #gpio-cells = <2>; - ngpios = <20>; - gpio-line-names = "P9_PIN11", "P9_PIN12", "P9_PIN13", "P9_PIN14", - "P9_PIN15", "P9_PIN16", "P9_PIN17", "P9_PIN18", - "P9_PIN21", "P9_PIN22", "P9_PIN23", "P9_PIN24", - "P9_PIN25", "P9_PIN26", "P9_PIN27", "P9_PIN28", - "P9_PIN29", "P9_PIN31", "P9_PIN41", "P9_PIN42"; - }; - - hsi_gpios: gpio@44000000 { - compatible = "microchip,coregpio-rtl-v3"; - reg = <0x0 0x44000000 0x0 0x1000>; - clocks = <&fabric_clk3>; - gpio-controller; - #gpio-cells = <2>; - ngpios = <20>; - gpio-line-names = "B0_HSIO70N", "B0_HSIO71N", "B0_HSIO83N", - "B0_HSIO73N_C2P_CLKN", "B0_HSIO70P", "B0_HSIO71P", - "B0_HSIO83P", "B0_HSIO73N_C2P_CLKP", "XCVR1_RX_VALID", - "XCVR1_LOCK", "XCVR1_ERROR", "XCVR2_RX_VALID", - "XCVR2_LOCK", "XCVR2_ERROR", "XCVR3_RX_VALID", - "XCVR3_LOCK", "XCVR3_ERROR", "XCVR_0B_REF_CLK_PLL_LOCK", - "XCVR_0C_REF_CLK_PLL_LOCK", "B0_HSIO81N"; - }; - }; - - ihc: mailbox { - compatible = "microchip,miv-ihc"; - interrupt-parent = <&plic>; - interrupts = ; - microchip,miv-ihc-remote-context-id = ; - #mbox-cells = <1>; - status = "disabled"; - }; - - fabric-pcie-bus@3000000000 { - compatible = "simple-bus"; - #address-cells = <2>; - #size-cells = <2>; - ranges = <0x0 0x40000000 0x0 0x40000000 0x0 0x20000000>, - <0x30 0x0 0x30 0x0 0x10 0x0>; - dma-ranges = <0x0 0x0 0x0 0x80000000 0x0 0x4000000>, - <0x0 0x4000000 0x0 0xc4000000 0x0 0x6000000>, - <0x0 0xa000000 0x0 0x8a000000 0x0 0x8000000>, - <0x0 0x12000000 0x14 0x12000000 0x0 0x10000000>, - <0x0 0x22000000 0x10 0x22000000 0x0 0x5e000000>; - - pcie: pcie@3000000000 { - compatible = "microchip,pcie-host-1.0"; - #address-cells = <0x3>; - #interrupt-cells = <0x1>; - #size-cells = <0x2>; - device_type = "pci"; - dma-noncoherent; - reg = <0x30 0x0 0x0 0x8000000>, <0x0 0x43004000 0x0 0x2000>, <0x0 0x43006000 0x0 0x2000>; - reg-names = "cfg", "bridge", "ctrl"; - bus-range = <0x0 0x7f>; - interrupt-parent = <&plic>; - interrupts = <119>; - interrupt-map = <0 0 0 1 &pcie_intc 0>, - <0 0 0 2 &pcie_intc 1>, - <0 0 0 3 &pcie_intc 2>, - <0 0 0 4 &pcie_intc 3>; - interrupt-map-mask = <0 0 0 7>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT1>, - <&ccc_nw CLK_CCC_PLL0_OUT3>; - clock-names = "fic1", "fic3"; - ranges = <0x43000000 0x0 0x9000000 0x30 0x9000000 0x0 0xf000000>, - <0x1000000 0x0 0x8000000 0x30 0x8000000 0x0 0x1000000>, - <0x3000000 0x0 0x18000000 0x30 0x18000000 0x0 0x70000000>; - dma-ranges = <0x3000000 0x0 0x80000000 0x0 0x0 0x0 0x4000000>, - <0x3000000 0x0 0x84000000 0x0 0x4000000 0x0 0x6000000>, - <0x3000000 0x0 0x8a000000 0x0 0xa000000 0x0 0x8000000>, - <0x3000000 0x0 0x92000000 0x0 0x12000000 0x0 0x10000000>, - <0x3000000 0x0 0xa2000000 0x0 0x22000000 0x0 0x5e000000>; - msi-parent = <&pcie>; - msi-controller; - status = "disabled"; - - pcie_intc: interrupt-controller { - #address-cells = <0>; - #interrupt-cells = <1>; - interrupt-controller; - }; - }; - }; - - refclk_ccc: cccrefclk { - compatible = "fixed-clock"; - #clock-cells = <0>; - }; -}; - -&ccc_nw { - clocks = <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, - <&refclk_ccc>, <&refclk_ccc>; - clock-names = "pll0_ref0", "pll0_ref1", "pll1_ref0", "pll1_ref1", - "dll0_ref", "dll1_ref"; - status = "okay"; -}; diff --git a/patches/linux/dts/mpfs-beaglev-fire.dts b/patches/linux/dts/mpfs-beaglev-fire.dts deleted file mode 100644 index dd3b9d7..0000000 --- a/patches/linux/dts/mpfs-beaglev-fire.dts +++ /dev/null @@ -1,380 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/dts-v1/; - -#include -#include "mpfs.dtsi" -#include "mpfs-beaglev-fire-fabric.dtsi" -#include "mpfs-beaglev-fire-pinmux.dtsi" - -/* Clock frequency (in Hz) of the rtcclk */ -#define RTCCLK_FREQ 1000000 - -/ { - #address-cells = <2>; - #size-cells = <2>; - model = "BeagleBoard BeagleV-Fire"; - compatible = "beagle,beaglev-fire", "microchip,mpfs"; - - soc { - dma-ranges = <0x14 0x0 0x0 0x80000000 0x0 0x4000000>, - <0x14 0x4000000 0x0 0xc4000000 0x0 0x6000000>, - <0x14 0xa000000 0x0 0x8a000000 0x0 0x8000000>, - <0x14 0x12000000 0x14 0x12000000 0x0 0x10000000>, - <0x14 0x22000000 0x10 0x22000000 0x0 0x5e000000>; - }; - - aliases { - serial0 = &mmuart0; - serial1 = &mmuart1; - serial2 = &mmuart2; - serial3 = &mmuart3; - serial4 = &mmuart4; - mmc0 = &mmc; - }; - - chosen { - stdout-path = "serial0:115200n8"; - }; - - cpus { - timebase-frequency = ; - }; - - kernel: memory@80000000 { - device_type = "memory"; - reg = <0x0 0x80000000 0x0 0x4000000>; - }; - - ddr_cached_low: memory@8a000000 { - device_type = "memory"; - reg = <0x0 0x8a000000 0x0 0x8000000>; - }; - - ddr_non_cached_low: memory@c4000000 { - device_type = "memory"; - reg = <0x0 0xc4000000 0x0 0x6000000>; - }; - - ddr_cached_high: memory@1022000000 { - device_type = "memory"; - reg = <0x10 0x22000000 0x0 0x5e000000>; - }; - - ddr_non_cached_high: memory@1412000000 { - device_type = "memory"; - reg = <0x14 0x12000000 0x0 0x10000000>; - }; - - reserved-memory { - #address-cells = <2>; - #size-cells = <2>; - ranges; - - hss: hss-buffer@103fc00000 { - compatible = "shared-dma-pool"; - reg = <0x10 0x3fc00000 0x0 0x400000>; - no-map; - }; - - dma_non_cached_low: non-cached-low-buffer { - compatible = "shared-dma-pool"; - size = <0x0 0x4000000>; - no-map; - alloc-ranges = <0x0 0xc4000000 0x0 0x4000000>; - }; - - dma_non_cached_high: non-cached-high-buffer { - compatible = "shared-dma-pool"; - size = <0x0 0x10000000>; - no-map; - linux,dma-default; - alloc-ranges = <0x14 0x12000000 0x0 0x10000000>; - }; - }; - - imx219_vana: fixedregulator-0 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vana"; - regulator-min-microvolt = <2800000>; - regulator-max-microvolt = <2800000>; - }; - - imx219_vdig: fixedregulator-1 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vdig"; - regulator-min-microvolt = <1800000>; - regulator-max-microvolt = <1800000>; - }; - - imx219_vddl: fixedregulator-2 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vddl"; - regulator-min-microvolt = <1200000>; - regulator-max-microvolt = <1200000>; - }; - - imx219_clk: camera-clk { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <24000000>; - }; -}; - -&gpio0 { - ngpios=<14>; - gpio-line-names = "", "", "", "", "", "", "", - "", "", "", "", "", "SD_CARD_CS", "USER_BUTTON"; - status = "okay"; - - user-button-hog { - gpio-hog; - gpios = <13 13>; - input; - line-name = "USER_BUTTON"; - }; -}; - -&gpio1 { - ngpios=<24>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", - "", "", "", "", "", "", "", "", "", "", - "ADC_IRQn", "", "", "USB_OCn"; - status = "okay"; - - adc-irqn-hog { - gpio-hog; - gpios = <20 20>; - input; - line-name = "ADC_IRQn"; - }; - - usb-ocn-hog { - gpio-hog; - gpios = <23 23>; - input; - line-name = "USB_OCn"; - }; -}; - -&gpio2 { - gpio-line-names = "P8_PIN3_USER_LED_0", "P8_PIN4_USER_LED_1", "P8_PIN5_USER_LED_2", - "P8_PIN6_USER_LED_3", "P8_PIN7_USER_LED_4", "P8_PIN8_USER_LED_5", - "P8_PIN9_USER_LED_6", "P8_PIN10_USER_LED_7", "P8_PIN11_USER_LED_8", - "P8_PIN12_USER_LED_9", "P8_PIN13_USER_LED_10", "P8_PIN14_USER_LED_11", - "P8_PIN15", "P8_PIN16", "P8_PIN17", "P8_PIN18", "P8_PIN19", "P8_PIN20", - "P8_PIN21", "P8_PIN22", "P8_PIN23", "P8_PIN24", "P8_PIN25", "P8_PIN26", - "P8_PIN27", "P8_PIN28", "P8_PIN29", "P8_PIN30", "M2_W_DISABLE1", - "M2_W_DISABLE2", "VIO_ENABLE", "SD_DET"; - status = "okay"; - - vio-enable-hog { - gpio-hog; - gpios = <30 30>; - output-high; - line-name = "VIO_ENABLE"; - }; - - sd-det-hog { - gpio-hog; - gpios = <31 31>; - input; - line-name = "SD_DET"; - }; -}; - -&i2c0 { - status = "okay"; -}; - -&i2c1 { - status = "okay"; - - eeprom: eeprom@50 { - compatible = "at,24c32"; - reg = <0x50>; - }; - - imx219: sensor@10 { - compatible = "sony,imx219"; - reg = <0x10>; - clocks = <&imx219_clk>; - VANA-supply = <&imx219_vana>; /* 2.8v */ - VDIG-supply = <&imx219_vdig>; /* 1.8v */ - VDDL-supply = <&imx219_vddl>; /* 1.2v */ - - port { - imx219_0: endpoint { - data-lanes = <1 2>; - clock-noncontinuous; - link-frequencies = /bits/ 64 <456000000>; - }; - }; - }; -}; - -&mac0 { - dma-noncoherent; - status = "okay"; - phy-mode = "sgmii"; - phy-handle = <&phy0>; - phy0: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mbox { - status = "okay"; -}; - -&mmc { - dma-noncoherent; - bus-width = <4>; - disable-wp; - cap-sd-highspeed; - cap-mmc-highspeed; - mmc-ddr-1_8v; - mmc-hs200-1_8v; - sd-uhs-sdr12; - sd-uhs-sdr25; - sd-uhs-sdr50; - sd-uhs-sdr104; - status = "okay"; -}; - -&mmuart0 { - status = "okay"; -}; - -&mmuart1 { - status = "okay"; -}; - -&refclk { - clock-frequency = <125000000>; -}; - -&refclk_ccc { - clock-frequency = <50000000>; -}; - -&rtc { - status = "okay"; -}; - -&spi0 { - status = "okay"; -}; - -&spi1 { - status = "okay"; -}; - -&gpio0 { - status = "okay"; -}; - -&gpio1 { - status = "okay"; -}; - -&qspi { - status = "okay"; - cs-gpios = <&gpio1 17 GPIO_ACTIVE_LOW>, <&gpio0 12 GPIO_ACTIVE_LOW>; - num-cs = <2>; - - adc@0 { - compatible = "microchip,mcp3464r"; - reg = <0>; /* CE0 */ - spi-cpol; - spi-cpha; - spi-max-frequency = <5000000>; - microchip,hw-device-address = <1>; - #address-cells = <1>; - #size-cells = <0>; - status = "okay"; - - channel@0 { - /* CH0 to AGND */ - reg = <0>; - label = "CH0"; - }; - - channel@1 { - /* CH1 to AGND */ - reg = <1>; - label = "CH1"; - }; - - channel@2 { - /* CH2 to AGND */ - reg = <2>; - label = "CH2"; - }; - - channel@3 { - /* CH3 to AGND */ - reg = <3>; - label = "CH3"; - }; - - channel@4 { - /* CH4 to AGND */ - reg = <4>; - label = "CH4"; - }; - - channel@5 { - /* CH5 to AGND */ - reg = <5>; - label = "CH5"; - }; - - channel@6 { - /* CH6 to AGND */ - reg = <6>; - label = "CH6"; - }; - - channel@7 { - /* CH7 is connected to AGND */ - reg = <7>; - label = "CH7"; - }; - }; - - mmc-slot@1 { - compatible = "mmc-spi-slot"; - reg = <1>; - gpios = <&gpio2 31 1>; - voltage-ranges = <3300 3300>; - spi-max-frequency = <5000000>; - disable-wp; - }; -}; - - -&syscontroller { - microchip,bitstream-flash = <&sys_ctrl_flash>; - status = "okay"; -}; - -&syscontroller_qspi { - status = "okay"; - - sys_ctrl_flash: flash@0 { // MT25QL01GBBB8ESF-0SIT - compatible = "jedec,spi-nor"; - #address-cells = <1>; - #size-cells = <1>; - spi-max-frequency = <20000000>; - spi-rx-bus-width = <1>; - reg = <0>; - }; -}; - -&usb { - dma-noncoherent; - status = "okay"; - dr_mode = "otg"; -}; diff --git a/patches/linux/linux-6.1.y/Makefile b/patches/linux/linux-6.1.y/Makefile deleted file mode 100644 index 7042363..0000000 --- a/patches/linux/linux-6.1.y/Makefile +++ /dev/null @@ -1,7 +0,0 @@ -# SPDX-License-Identifier: GPL-2.0 -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-icicle-kit.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-m100pfsevp.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-polarberry.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-sev-kit.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-beaglev-fire.dtb -obj-$(CONFIG_BUILTIN_DTB) += $(addsuffix .o, $(dtb-y)) diff --git a/patches/linux/linux-6.1.y/defconfig b/patches/linux/linux-6.1.y/defconfig deleted file mode 100644 index 2e4c461..0000000 --- a/patches/linux/linux-6.1.y/defconfig +++ /dev/null @@ -1,5161 +0,0 @@ -# -# Automatically generated file; DO NOT EDIT. -# Linux/riscv 6.1.45 Kernel Configuration -# -CONFIG_CC_VERSION_TEXT="riscv64-linux-gcc (GCC) 11.4.0" -CONFIG_CC_IS_GCC=y -CONFIG_GCC_VERSION=110400 -CONFIG_CLANG_VERSION=0 -CONFIG_AS_IS_GNU=y -CONFIG_AS_VERSION=24000 -CONFIG_LD_IS_BFD=y -CONFIG_LD_VERSION=24000 -CONFIG_LLD_VERSION=0 -CONFIG_CC_HAS_ASM_GOTO_OUTPUT=y -CONFIG_CC_HAS_ASM_GOTO_TIED_OUTPUT=y -CONFIG_CC_HAS_ASM_INLINE=y -CONFIG_CC_HAS_NO_PROFILE_FN_ATTR=y -CONFIG_PAHOLE_VERSION=0 -CONFIG_IRQ_WORK=y -CONFIG_BUILDTIME_TABLE_SORT=y -CONFIG_THREAD_INFO_IN_TASK=y - -# -# General setup -# -CONFIG_INIT_ENV_ARG_LIMIT=32 -# CONFIG_COMPILE_TEST is not set -# CONFIG_WERROR is not set -CONFIG_LOCALVERSION="" -CONFIG_LOCALVERSION_AUTO=y -CONFIG_BUILD_SALT="" -CONFIG_DEFAULT_INIT="" -CONFIG_DEFAULT_HOSTNAME="(none)" -CONFIG_SYSVIPC=y -CONFIG_SYSVIPC_SYSCTL=y -CONFIG_SYSVIPC_COMPAT=y -CONFIG_POSIX_MQUEUE=y -CONFIG_POSIX_MQUEUE_SYSCTL=y -# CONFIG_WATCH_QUEUE is not set -CONFIG_CROSS_MEMORY_ATTACH=y -# CONFIG_USELIB is not set -CONFIG_AUDIT=y -CONFIG_HAVE_ARCH_AUDITSYSCALL=y -CONFIG_AUDITSYSCALL=y - -# -# IRQ subsystem -# -CONFIG_GENERIC_IRQ_SHOW=y -CONFIG_GENERIC_IRQ_SHOW_LEVEL=y -CONFIG_GENERIC_IRQ_EFFECTIVE_AFF_MASK=y -CONFIG_GENERIC_IRQ_MIGRATION=y -CONFIG_HARDIRQS_SW_RESEND=y -CONFIG_IRQ_DOMAIN=y -CONFIG_IRQ_DOMAIN_HIERARCHY=y -CONFIG_GENERIC_MSI_IRQ=y -CONFIG_GENERIC_MSI_IRQ_DOMAIN=y -CONFIG_IRQ_FORCED_THREADING=y -CONFIG_SPARSE_IRQ=y -# CONFIG_GENERIC_IRQ_DEBUGFS is not set -# end of IRQ subsystem - -CONFIG_GENERIC_IRQ_MULTI_HANDLER=y -CONFIG_ARCH_CLOCKSOURCE_INIT=y -CONFIG_GENERIC_TIME_VSYSCALL=y -CONFIG_GENERIC_CLOCKEVENTS=y -CONFIG_ARCH_HAS_TICK_BROADCAST=y -CONFIG_GENERIC_CLOCKEVENTS_BROADCAST=y -CONFIG_HAVE_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_CONTEXT_TRACKING=y -CONFIG_CONTEXT_TRACKING_IDLE=y - -# -# Timers subsystem -# -CONFIG_TICK_ONESHOT=y -CONFIG_NO_HZ_COMMON=y -# CONFIG_HZ_PERIODIC is not set -CONFIG_NO_HZ_IDLE=y -# CONFIG_NO_HZ_FULL is not set -# CONFIG_NO_HZ is not set -CONFIG_HIGH_RES_TIMERS=y -# end of Timers subsystem - -CONFIG_BPF=y -CONFIG_HAVE_EBPF_JIT=y - -# -# BPF subsystem -# -CONFIG_BPF_SYSCALL=y -# CONFIG_BPF_JIT is not set -CONFIG_BPF_UNPRIV_DEFAULT_OFF=y -# CONFIG_BPF_PRELOAD is not set -# end of BPF subsystem - -CONFIG_PREEMPT_NONE_BUILD=y -CONFIG_PREEMPT_NONE=y -# CONFIG_PREEMPT_VOLUNTARY is not set -# CONFIG_PREEMPT is not set -CONFIG_PREEMPT_COUNT=y - -# -# CPU/Task time and stats accounting -# -CONFIG_TICK_CPU_ACCOUNTING=y -# CONFIG_VIRT_CPU_ACCOUNTING_GEN is not set -# CONFIG_IRQ_TIME_ACCOUNTING is not set -# CONFIG_BSD_PROCESS_ACCT is not set -# CONFIG_TASKSTATS is not set -# CONFIG_PSI is not set -# end of CPU/Task time and stats accounting - -CONFIG_CPU_ISOLATION=y - -# -# RCU Subsystem -# -CONFIG_TREE_RCU=y -# CONFIG_RCU_EXPERT is not set -CONFIG_SRCU=y -CONFIG_TREE_SRCU=y -CONFIG_TASKS_RCU_GENERIC=y -CONFIG_TASKS_TRACE_RCU=y -CONFIG_RCU_STALL_COMMON=y -CONFIG_RCU_NEED_SEGCBLIST=y -# end of RCU Subsystem - -CONFIG_IKCONFIG=y -CONFIG_IKCONFIG_PROC=y -# CONFIG_IKHEADERS is not set -CONFIG_LOG_BUF_SHIFT=17 -CONFIG_LOG_CPU_MAX_BUF_SHIFT=12 -CONFIG_PRINTK_SAFE_LOG_BUF_SHIFT=13 -# CONFIG_PRINTK_INDEX is not set -CONFIG_GENERIC_SCHED_CLOCK=y - -# -# Scheduler features -# -# end of Scheduler features - -CONFIG_CC_HAS_INT128=y -CONFIG_CC_IMPLICIT_FALLTHROUGH="-Wimplicit-fallthrough=5" -CONFIG_GCC11_NO_ARRAY_BOUNDS=y -CONFIG_CC_NO_ARRAY_BOUNDS=y -CONFIG_ARCH_SUPPORTS_INT128=y -CONFIG_CGROUPS=y -CONFIG_PAGE_COUNTER=y -# CONFIG_CGROUP_FAVOR_DYNMODS is not set -CONFIG_MEMCG=y -CONFIG_MEMCG_KMEM=y -# CONFIG_BLK_CGROUP is not set -CONFIG_CGROUP_SCHED=y -CONFIG_FAIR_GROUP_SCHED=y -CONFIG_CFS_BANDWIDTH=y -CONFIG_RT_GROUP_SCHED=y -CONFIG_CGROUP_PIDS=y -# CONFIG_CGROUP_RDMA is not set -CONFIG_CGROUP_FREEZER=y -CONFIG_CGROUP_HUGETLB=y -CONFIG_CPUSETS=y -CONFIG_PROC_PID_CPUSET=y -CONFIG_CGROUP_DEVICE=y -CONFIG_CGROUP_CPUACCT=y -CONFIG_CGROUP_PERF=y -CONFIG_CGROUP_BPF=y -# CONFIG_CGROUP_MISC is not set -# CONFIG_CGROUP_DEBUG is not set -CONFIG_SOCK_CGROUP_DATA=y -CONFIG_NAMESPACES=y -CONFIG_UTS_NS=y -CONFIG_TIME_NS=y -CONFIG_IPC_NS=y -CONFIG_USER_NS=y -CONFIG_PID_NS=y -CONFIG_NET_NS=y -CONFIG_CHECKPOINT_RESTORE=y -# CONFIG_SCHED_AUTOGROUP is not set -# CONFIG_SYSFS_DEPRECATED is not set -# CONFIG_RELAY is not set -CONFIG_BLK_DEV_INITRD=y -CONFIG_INITRAMFS_SOURCE="" -CONFIG_RD_GZIP=y -CONFIG_RD_BZIP2=y -CONFIG_RD_LZMA=y -CONFIG_RD_XZ=y -CONFIG_RD_LZO=y -CONFIG_RD_LZ4=y -CONFIG_RD_ZSTD=y -# CONFIG_BOOT_CONFIG is not set -CONFIG_INITRAMFS_PRESERVE_MTIME=y -CONFIG_CC_OPTIMIZE_FOR_PERFORMANCE=y -# CONFIG_CC_OPTIMIZE_FOR_SIZE is not set -CONFIG_SYSCTL=y -CONFIG_SYSCTL_EXCEPTION_TRACE=y -CONFIG_EXPERT=y -CONFIG_MULTIUSER=y -# CONFIG_SGETMASK_SYSCALL is not set -# CONFIG_SYSFS_SYSCALL is not set -CONFIG_FHANDLE=y -CONFIG_POSIX_TIMERS=y -CONFIG_PRINTK=y -CONFIG_BUG=y -CONFIG_ELF_CORE=y -CONFIG_BASE_FULL=y -CONFIG_FUTEX=y -CONFIG_FUTEX_PI=y -CONFIG_EPOLL=y -CONFIG_SIGNALFD=y -CONFIG_TIMERFD=y -CONFIG_EVENTFD=y -CONFIG_SHMEM=y -CONFIG_AIO=y -CONFIG_IO_URING=y -CONFIG_ADVISE_SYSCALLS=y -CONFIG_MEMBARRIER=y -CONFIG_KALLSYMS=y -# CONFIG_KALLSYMS_ALL is not set -CONFIG_KALLSYMS_BASE_RELATIVE=y -CONFIG_KCMP=y -CONFIG_RSEQ=y -# CONFIG_DEBUG_RSEQ is not set -# CONFIG_EMBEDDED is not set -CONFIG_HAVE_PERF_EVENTS=y -# CONFIG_PC104 is not set - -# -# Kernel Performance Events And Counters -# -CONFIG_PERF_EVENTS=y -# CONFIG_DEBUG_PERF_USE_VMALLOC is not set -# end of Kernel Performance Events And Counters - -CONFIG_PROFILING=y -# end of General setup - -CONFIG_64BIT=y -CONFIG_RISCV=y -CONFIG_ARCH_MMAP_RND_BITS_MIN=18 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MIN=8 -CONFIG_ARCH_MMAP_RND_BITS_MAX=24 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MAX=17 -CONFIG_RISCV_SBI=y -CONFIG_MMU=y -CONFIG_PAGE_OFFSET=0xff60000000000000 -CONFIG_ARCH_FLATMEM_ENABLE=y -CONFIG_ARCH_SPARSEMEM_ENABLE=y -CONFIG_ARCH_SELECT_MEMORY_MODEL=y -CONFIG_ARCH_SUPPORTS_UPROBES=y -CONFIG_STACKTRACE_SUPPORT=y -CONFIG_GENERIC_BUG=y -CONFIG_GENERIC_BUG_RELATIVE_POINTERS=y -CONFIG_GENERIC_CALIBRATE_DELAY=y -CONFIG_GENERIC_CSUM=y -CONFIG_GENERIC_HWEIGHT=y -CONFIG_FIX_EARLYCON_MEM=y -CONFIG_PGTABLE_LEVELS=5 -CONFIG_LOCKDEP_SUPPORT=y -CONFIG_RISCV_DMA_NONCOHERENT=y -CONFIG_AS_HAS_INSN=y - -# -# SoC selection -# -CONFIG_SOC_MICROCHIP_POLARFIRE=y -CONFIG_SOC_SIFIVE=y -CONFIG_SOC_STARFIVE=y -CONFIG_SOC_VIRT=y -# end of SoC selection - -# -# CPU errata selection -# -CONFIG_ERRATA_SIFIVE=y -CONFIG_ERRATA_SIFIVE_CIP_453=y -CONFIG_ERRATA_SIFIVE_CIP_1200=y -# CONFIG_ERRATA_THEAD is not set -# end of CPU errata selection - -# -# Platform type -# -# CONFIG_NONPORTABLE is not set -CONFIG_ARCH_RV64I=y -# CONFIG_CMODEL_MEDLOW is not set -CONFIG_CMODEL_MEDANY=y -CONFIG_MODULE_SECTIONS=y -CONFIG_SMP=y -CONFIG_NR_CPUS=64 -CONFIG_HOTPLUG_CPU=y -CONFIG_TUNE_GENERIC=y -# CONFIG_NUMA is not set -CONFIG_RISCV_ALTERNATIVE=y -CONFIG_RISCV_ISA_C=y -CONFIG_RISCV_ISA_SVPBMT=y -CONFIG_TOOLCHAIN_HAS_ZICBOM=y -CONFIG_RISCV_ISA_ZICBOM=y -CONFIG_TOOLCHAIN_HAS_ZIHINTPAUSE=y -CONFIG_TOOLCHAIN_NEEDS_EXPLICIT_ZICSR_ZIFENCEI=y -CONFIG_FPU=y -# end of Platform type - -# -# Kernel features -# -# CONFIG_HZ_100 is not set -CONFIG_HZ_250=y -# CONFIG_HZ_300 is not set -# CONFIG_HZ_1000 is not set -CONFIG_HZ=250 -CONFIG_SCHED_HRTICK=y -# CONFIG_RISCV_SBI_V01 is not set -# CONFIG_RISCV_BOOT_SPINWAIT is not set -# CONFIG_KEXEC is not set -# CONFIG_KEXEC_FILE is not set -# CONFIG_CRASH_DUMP is not set -CONFIG_COMPAT=y -# end of Kernel features - -# -# Boot options -# -CONFIG_CMDLINE="" -CONFIG_EFI_STUB=y -CONFIG_EFI=y -CONFIG_CC_HAVE_STACKPROTECTOR_TLS=y -CONFIG_STACKPROTECTOR_PER_TASK=y -# end of Boot options - -CONFIG_PORTABLE=y - -# -# Power management options -# -CONFIG_PM=y -# CONFIG_PM_DEBUG is not set -CONFIG_PM_CLK=y -CONFIG_PM_GENERIC_DOMAINS=y -# CONFIG_WQ_POWER_EFFICIENT_DEFAULT is not set -CONFIG_PM_GENERIC_DOMAINS_OF=y -CONFIG_CPU_PM=y -# end of Power management options - -# -# CPU Power Management -# - -# -# CPU Idle -# -CONFIG_CPU_IDLE=y -CONFIG_CPU_IDLE_MULTIPLE_DRIVERS=y -# CONFIG_CPU_IDLE_GOV_LADDER is not set -CONFIG_CPU_IDLE_GOV_MENU=y -# CONFIG_CPU_IDLE_GOV_TEO is not set -CONFIG_DT_IDLE_STATES=y -CONFIG_DT_IDLE_GENPD=y - -# -# RISC-V CPU Idle Drivers -# -CONFIG_RISCV_SBI_CPUIDLE=y -# end of RISC-V CPU Idle Drivers -# end of CPU Idle -# end of CPU Power Management - -CONFIG_HAVE_KVM_EVENTFD=y -CONFIG_KVM_MMIO=y -CONFIG_KVM_GENERIC_DIRTYLOG_READ_PROTECT=y -CONFIG_HAVE_KVM_VCPU_ASYNC_IOCTL=y -CONFIG_KVM_XFER_TO_GUEST_WORK=y -CONFIG_VIRTUALIZATION=y -CONFIG_KVM=m - -# -# General architecture-dependent options -# -# CONFIG_KPROBES is not set -CONFIG_JUMP_LABEL=y -# CONFIG_STATIC_KEYS_SELFTEST is not set -CONFIG_HAVE_64BIT_ALIGNED_ACCESS=y -CONFIG_HAVE_KPROBES=y -CONFIG_HAVE_KRETPROBES=y -CONFIG_HAVE_KPROBES_ON_FTRACE=y -CONFIG_HAVE_FUNCTION_ERROR_INJECTION=y -CONFIG_TRACE_IRQFLAGS_SUPPORT=y -CONFIG_HAVE_ARCH_TRACEHOOK=y -CONFIG_HAVE_DMA_CONTIGUOUS=y -CONFIG_GENERIC_SMP_IDLE_THREAD=y -CONFIG_GENERIC_IDLE_POLL_SETUP=y -CONFIG_ARCH_HAS_FORTIFY_SOURCE=y -CONFIG_ARCH_HAS_SET_MEMORY=y -CONFIG_ARCH_HAS_SET_DIRECT_MAP=y -CONFIG_HAVE_ARCH_THREAD_STRUCT_WHITELIST=y -CONFIG_HAVE_ASM_MODVERSIONS=y -CONFIG_HAVE_REGS_AND_STACK_ACCESS_API=y -CONFIG_HAVE_RSEQ=y -CONFIG_HAVE_FUNCTION_ARG_ACCESS_API=y -CONFIG_HAVE_PERF_REGS=y -CONFIG_HAVE_PERF_USER_STACK_DUMP=y -CONFIG_HAVE_ARCH_JUMP_LABEL=y -CONFIG_HAVE_ARCH_JUMP_LABEL_RELATIVE=y -CONFIG_HAVE_ARCH_SECCOMP=y -CONFIG_HAVE_ARCH_SECCOMP_FILTER=y -CONFIG_SECCOMP=y -CONFIG_SECCOMP_FILTER=y -# CONFIG_SECCOMP_CACHE_DEBUG is not set -CONFIG_HAVE_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR_STRONG=y -CONFIG_LTO_NONE=y -CONFIG_HAVE_CONTEXT_TRACKING_USER=y -CONFIG_HAVE_VIRT_CPU_ACCOUNTING_GEN=y -CONFIG_HAVE_IRQ_TIME_ACCOUNTING=y -CONFIG_HAVE_MOVE_PUD=y -CONFIG_HAVE_MOVE_PMD=y -CONFIG_HAVE_ARCH_TRANSPARENT_HUGEPAGE=y -CONFIG_ARCH_WANT_HUGE_PMD_SHARE=y -CONFIG_HAVE_MOD_ARCH_SPECIFIC=y -CONFIG_MODULES_USE_ELF_RELA=y -CONFIG_ARCH_HAS_ELF_RANDOMIZE=y -CONFIG_HAVE_ARCH_MMAP_RND_BITS=y -CONFIG_ARCH_MMAP_RND_BITS=18 -CONFIG_HAVE_ARCH_MMAP_RND_COMPAT_BITS=y -CONFIG_ARCH_MMAP_RND_COMPAT_BITS=8 -CONFIG_PAGE_SIZE_LESS_THAN_64KB=y -CONFIG_PAGE_SIZE_LESS_THAN_256KB=y -CONFIG_ARCH_WANT_DEFAULT_TOPDOWN_MMAP_LAYOUT=y -CONFIG_CLONE_BACKWARDS=y -CONFIG_COMPAT_32BIT_TIME=y -CONFIG_HAVE_ARCH_VMAP_STACK=y -CONFIG_VMAP_STACK=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX_DEFAULT=y -CONFIG_ARCH_HAS_STRICT_KERNEL_RWX=y -CONFIG_STRICT_KERNEL_RWX=y -CONFIG_ARCH_HAS_STRICT_MODULE_RWX=y -CONFIG_STRICT_MODULE_RWX=y -CONFIG_ARCH_USE_MEMREMAP_PROT=y -# CONFIG_LOCK_EVENT_COUNTS is not set -CONFIG_ARCH_SUPPORTS_DEBUG_PAGEALLOC=y -CONFIG_ARCH_SUPPORTS_PAGE_TABLE_CHECK=y - -# -# GCOV-based kernel profiling -# -# CONFIG_GCOV_KERNEL is not set -CONFIG_ARCH_HAS_GCOV_PROFILE_ALL=y -# end of GCOV-based kernel profiling - -CONFIG_HAVE_GCC_PLUGINS=y -CONFIG_GCC_PLUGINS=y -# CONFIG_GCC_PLUGIN_LATENT_ENTROPY is not set -# end of General architecture-dependent options - -CONFIG_RT_MUTEXES=y -CONFIG_BASE_SMALL=0 -CONFIG_MODULES=y -# CONFIG_MODULE_FORCE_LOAD is not set -CONFIG_MODULE_UNLOAD=y -# CONFIG_MODULE_FORCE_UNLOAD is not set -# CONFIG_MODULE_UNLOAD_TAINT_TRACKING is not set -# CONFIG_MODVERSIONS is not set -# CONFIG_MODULE_SRCVERSION_ALL is not set -# CONFIG_MODULE_SIG is not set -CONFIG_MODULE_COMPRESS_NONE=y -# CONFIG_MODULE_COMPRESS_GZIP is not set -# CONFIG_MODULE_COMPRESS_XZ is not set -# CONFIG_MODULE_COMPRESS_ZSTD is not set -# CONFIG_MODULE_ALLOW_MISSING_NAMESPACE_IMPORTS is not set -CONFIG_MODPROBE_PATH="/sbin/modprobe" -# CONFIG_TRIM_UNUSED_KSYMS is not set -CONFIG_MODULES_TREE_LOOKUP=y -CONFIG_BLOCK=y -CONFIG_BLOCK_LEGACY_AUTOLOAD=y -CONFIG_BLK_DEV_BSG_COMMON=y -# CONFIG_BLK_DEV_BSGLIB is not set -# CONFIG_BLK_DEV_INTEGRITY is not set -# CONFIG_BLK_DEV_ZONED is not set -# CONFIG_BLK_WBT is not set -CONFIG_BLK_DEBUG_FS=y -# CONFIG_BLK_SED_OPAL is not set -# CONFIG_BLK_INLINE_ENCRYPTION is not set - -# -# Partition Types -# -# CONFIG_PARTITION_ADVANCED is not set -CONFIG_MSDOS_PARTITION=y -CONFIG_EFI_PARTITION=y -# end of Partition Types - -CONFIG_BLOCK_COMPAT=y -CONFIG_BLK_MQ_PCI=y -CONFIG_BLK_MQ_VIRTIO=y -CONFIG_BLK_PM=y -CONFIG_BLOCK_HOLDER_DEPRECATED=y -CONFIG_BLK_MQ_STACKING=y - -# -# IO Schedulers -# -CONFIG_MQ_IOSCHED_DEADLINE=y -CONFIG_MQ_IOSCHED_KYBER=y -# CONFIG_IOSCHED_BFQ is not set -# end of IO Schedulers - -CONFIG_PREEMPT_NOTIFIERS=y -CONFIG_ASN1=y -CONFIG_UNINLINE_SPIN_UNLOCK=y -CONFIG_ARCH_SUPPORTS_ATOMIC_RMW=y -CONFIG_MUTEX_SPIN_ON_OWNER=y -CONFIG_RWSEM_SPIN_ON_OWNER=y -CONFIG_LOCK_SPIN_ON_OWNER=y -CONFIG_ARCH_USE_QUEUED_RWLOCKS=y -CONFIG_QUEUED_RWLOCKS=y -CONFIG_ARCH_HAS_MMIOWB=y -CONFIG_MMIOWB=y -CONFIG_ARCH_HAS_NON_OVERLAPPING_ADDRESS_SPACE=y -CONFIG_FREEZER=y - -# -# Executable file formats -# -CONFIG_BINFMT_ELF=y -CONFIG_COMPAT_BINFMT_ELF=y -CONFIG_ELFCORE=y -CONFIG_CORE_DUMP_DEFAULT_ELF_HEADERS=y -CONFIG_BINFMT_SCRIPT=y -CONFIG_ARCH_HAS_BINFMT_FLAT=y -# CONFIG_BINFMT_FLAT is not set -# CONFIG_BINFMT_MISC is not set -CONFIG_COREDUMP=y -# end of Executable file formats - -# -# Memory Management options -# -CONFIG_SWAP=y -# CONFIG_ZSWAP is not set - -# -# SLAB allocator options -# -# CONFIG_SLAB is not set -CONFIG_SLUB=y -# CONFIG_SLOB is not set -CONFIG_SLAB_MERGE_DEFAULT=y -# CONFIG_SLAB_FREELIST_RANDOM is not set -# CONFIG_SLAB_FREELIST_HARDENED is not set -# CONFIG_SLUB_STATS is not set -CONFIG_SLUB_CPU_PARTIAL=y -# end of SLAB allocator options - -# CONFIG_SHUFFLE_PAGE_ALLOCATOR is not set -CONFIG_COMPAT_BRK=y -CONFIG_SELECT_MEMORY_MODEL=y -CONFIG_FLATMEM_MANUAL=y -# CONFIG_SPARSEMEM_MANUAL is not set -CONFIG_FLATMEM=y -CONFIG_SPARSEMEM_VMEMMAP_ENABLE=y -CONFIG_SPLIT_PTLOCK_CPUS=4 -CONFIG_ARCH_ENABLE_SPLIT_PMD_PTLOCK=y -CONFIG_MEMORY_BALLOON=y -CONFIG_BALLOON_COMPACTION=y -CONFIG_COMPACTION=y -CONFIG_COMPACT_UNEVICTABLE_DEFAULT=1 -CONFIG_PAGE_REPORTING=y -CONFIG_MIGRATION=y -CONFIG_ARCH_ENABLE_HUGEPAGE_MIGRATION=y -CONFIG_PHYS_ADDR_T_64BIT=y -CONFIG_MMU_NOTIFIER=y -# CONFIG_KSM is not set -CONFIG_DEFAULT_MMAP_MIN_ADDR=4096 -CONFIG_ARCH_WANT_GENERAL_HUGETLB=y -CONFIG_ARCH_WANTS_THP_SWAP=y -# CONFIG_TRANSPARENT_HUGEPAGE is not set -# CONFIG_CMA is not set -CONFIG_GENERIC_EARLY_IOREMAP=y -# CONFIG_IDLE_PAGE_TRACKING is not set -CONFIG_ARCH_HAS_CURRENT_STACK_POINTER=y -CONFIG_ZONE_DMA32=y -CONFIG_VM_EVENT_COUNTERS=y -# CONFIG_PERCPU_STATS is not set -# CONFIG_GUP_TEST is not set -CONFIG_ARCH_HAS_PTE_SPECIAL=y -CONFIG_SECRETMEM=y -# CONFIG_ANON_VMA_NAME is not set -# CONFIG_USERFAULTFD is not set -# CONFIG_LRU_GEN is not set -CONFIG_LOCK_MM_AND_FIND_VMA=y - -# -# Data Access Monitoring -# -# CONFIG_DAMON is not set -# end of Data Access Monitoring -# end of Memory Management options - -CONFIG_NET=y -CONFIG_NET_INGRESS=y -CONFIG_NET_EGRESS=y -CONFIG_SKB_EXTENSIONS=y - -# -# Networking options -# -CONFIG_PACKET=y -# CONFIG_PACKET_DIAG is not set -CONFIG_UNIX=y -CONFIG_UNIX_SCM=y -CONFIG_AF_UNIX_OOB=y -# CONFIG_UNIX_DIAG is not set -# CONFIG_TLS is not set -CONFIG_XFRM=y -CONFIG_XFRM_ALGO=m -CONFIG_XFRM_USER=m -# CONFIG_XFRM_INTERFACE is not set -# CONFIG_XFRM_SUB_POLICY is not set -# CONFIG_XFRM_MIGRATE is not set -# CONFIG_XFRM_STATISTICS is not set -CONFIG_XFRM_ESP=m -# CONFIG_NET_KEY is not set -# CONFIG_XDP_SOCKETS is not set -CONFIG_INET=y -CONFIG_IP_MULTICAST=y -CONFIG_IP_ADVANCED_ROUTER=y -# CONFIG_IP_FIB_TRIE_STATS is not set -# CONFIG_IP_MULTIPLE_TABLES is not set -# CONFIG_IP_ROUTE_MULTIPATH is not set -# CONFIG_IP_ROUTE_VERBOSE is not set -CONFIG_IP_PNP=y -CONFIG_IP_PNP_DHCP=y -CONFIG_IP_PNP_BOOTP=y -CONFIG_IP_PNP_RARP=y -# CONFIG_NET_IPIP is not set -# CONFIG_NET_IPGRE_DEMUX is not set -CONFIG_NET_IP_TUNNEL=y -# CONFIG_IP_MROUTE is not set -# CONFIG_SYN_COOKIES is not set -# CONFIG_NET_IPVTI is not set -CONFIG_NET_UDP_TUNNEL=m -# CONFIG_NET_FOU is not set -# CONFIG_NET_FOU_IP_TUNNELS is not set -# CONFIG_INET_AH is not set -CONFIG_INET_ESP=m -# CONFIG_INET_ESP_OFFLOAD is not set -# CONFIG_INET_ESPINTCP is not set -# CONFIG_INET_IPCOMP is not set -CONFIG_INET_TABLE_PERTURB_ORDER=16 -CONFIG_INET_TUNNEL=y -CONFIG_INET_DIAG=y -CONFIG_INET_TCP_DIAG=y -# CONFIG_INET_UDP_DIAG is not set -# CONFIG_INET_RAW_DIAG is not set -# CONFIG_INET_DIAG_DESTROY is not set -# CONFIG_TCP_CONG_ADVANCED is not set -CONFIG_TCP_CONG_CUBIC=y -CONFIG_DEFAULT_TCP_CONG="cubic" -# CONFIG_TCP_MD5SIG is not set -CONFIG_IPV6=y -# CONFIG_IPV6_ROUTER_PREF is not set -# CONFIG_IPV6_OPTIMISTIC_DAD is not set -# CONFIG_INET6_AH is not set -# CONFIG_INET6_ESP is not set -# CONFIG_INET6_IPCOMP is not set -# CONFIG_IPV6_MIP6 is not set -# CONFIG_IPV6_ILA is not set -# CONFIG_IPV6_VTI is not set -CONFIG_IPV6_SIT=y -# CONFIG_IPV6_SIT_6RD is not set -CONFIG_IPV6_NDISC_NODETYPE=y -# CONFIG_IPV6_TUNNEL is not set -# CONFIG_IPV6_MULTIPLE_TABLES is not set -# CONFIG_IPV6_MROUTE is not set -# CONFIG_IPV6_SEG6_LWTUNNEL is not set -# CONFIG_IPV6_SEG6_HMAC is not set -# CONFIG_IPV6_RPL_LWTUNNEL is not set -# CONFIG_IPV6_IOAM6_LWTUNNEL is not set -# CONFIG_NETLABEL is not set -# CONFIG_MPTCP is not set -CONFIG_NETWORK_SECMARK=y -# CONFIG_NETWORK_PHY_TIMESTAMPING is not set -CONFIG_NETFILTER=y -CONFIG_NETFILTER_ADVANCED=y -CONFIG_BRIDGE_NETFILTER=m - -# -# Core Netfilter Configuration -# -CONFIG_NETFILTER_INGRESS=y -CONFIG_NETFILTER_EGRESS=y -CONFIG_NETFILTER_FAMILY_BRIDGE=y -# CONFIG_NETFILTER_NETLINK_ACCT is not set -# CONFIG_NETFILTER_NETLINK_QUEUE is not set -# CONFIG_NETFILTER_NETLINK_LOG is not set -# CONFIG_NETFILTER_NETLINK_OSF is not set -CONFIG_NF_CONNTRACK=m -CONFIG_NF_LOG_SYSLOG=m -# CONFIG_NF_CONNTRACK_MARK is not set -# CONFIG_NF_CONNTRACK_SECMARK is not set -# CONFIG_NF_CONNTRACK_ZONES is not set -# CONFIG_NF_CONNTRACK_PROCFS is not set -# CONFIG_NF_CONNTRACK_EVENTS is not set -# CONFIG_NF_CONNTRACK_TIMEOUT is not set -# CONFIG_NF_CONNTRACK_TIMESTAMP is not set -# CONFIG_NF_CONNTRACK_LABELS is not set -CONFIG_NF_CT_PROTO_DCCP=y -CONFIG_NF_CT_PROTO_SCTP=y -CONFIG_NF_CT_PROTO_UDPLITE=y -# CONFIG_NF_CONNTRACK_AMANDA is not set -CONFIG_NF_CONNTRACK_FTP=m -# CONFIG_NF_CONNTRACK_H323 is not set -# CONFIG_NF_CONNTRACK_IRC is not set -# CONFIG_NF_CONNTRACK_NETBIOS_NS is not set -# CONFIG_NF_CONNTRACK_SNMP is not set -# CONFIG_NF_CONNTRACK_PPTP is not set -# CONFIG_NF_CONNTRACK_SANE is not set -# CONFIG_NF_CONNTRACK_SIP is not set -CONFIG_NF_CONNTRACK_TFTP=m -# CONFIG_NF_CT_NETLINK is not set -CONFIG_NF_NAT=m -CONFIG_NF_NAT_FTP=m -CONFIG_NF_NAT_TFTP=m -CONFIG_NF_NAT_REDIRECT=y -CONFIG_NF_NAT_MASQUERADE=y -# CONFIG_NF_TABLES is not set -CONFIG_NETFILTER_XTABLES=y -CONFIG_NETFILTER_XTABLES_COMPAT=y - -# -# Xtables combined modules -# -CONFIG_NETFILTER_XT_MARK=m -# CONFIG_NETFILTER_XT_CONNMARK is not set - -# -# Xtables targets -# -# CONFIG_NETFILTER_XT_TARGET_AUDIT is not set -# CONFIG_NETFILTER_XT_TARGET_CHECKSUM is not set -# CONFIG_NETFILTER_XT_TARGET_CLASSIFY is not set -# CONFIG_NETFILTER_XT_TARGET_CONNMARK is not set -# CONFIG_NETFILTER_XT_TARGET_DSCP is not set -# CONFIG_NETFILTER_XT_TARGET_HL is not set -# CONFIG_NETFILTER_XT_TARGET_HMARK is not set -# CONFIG_NETFILTER_XT_TARGET_IDLETIMER is not set -# CONFIG_NETFILTER_XT_TARGET_LOG is not set -# CONFIG_NETFILTER_XT_TARGET_MARK is not set -CONFIG_NETFILTER_XT_NAT=m -# CONFIG_NETFILTER_XT_TARGET_NETMAP is not set -# CONFIG_NETFILTER_XT_TARGET_NFLOG is not set -# CONFIG_NETFILTER_XT_TARGET_NFQUEUE is not set -# CONFIG_NETFILTER_XT_TARGET_RATEEST is not set -CONFIG_NETFILTER_XT_TARGET_REDIRECT=m -CONFIG_NETFILTER_XT_TARGET_MASQUERADE=m -# CONFIG_NETFILTER_XT_TARGET_TEE is not set -# CONFIG_NETFILTER_XT_TARGET_TPROXY is not set -# CONFIG_NETFILTER_XT_TARGET_SECMARK is not set -# CONFIG_NETFILTER_XT_TARGET_TCPMSS is not set -# CONFIG_NETFILTER_XT_TARGET_TCPOPTSTRIP is not set - -# -# Xtables matches -# -CONFIG_NETFILTER_XT_MATCH_ADDRTYPE=m -# CONFIG_NETFILTER_XT_MATCH_BPF is not set -# CONFIG_NETFILTER_XT_MATCH_CGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_CLUSTER is not set -# CONFIG_NETFILTER_XT_MATCH_COMMENT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNBYTES is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLABEL is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNMARK is not set -CONFIG_NETFILTER_XT_MATCH_CONNTRACK=m -# CONFIG_NETFILTER_XT_MATCH_CPU is not set -# CONFIG_NETFILTER_XT_MATCH_DCCP is not set -# CONFIG_NETFILTER_XT_MATCH_DEVGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_DSCP is not set -# CONFIG_NETFILTER_XT_MATCH_ECN is not set -# CONFIG_NETFILTER_XT_MATCH_ESP is not set -# CONFIG_NETFILTER_XT_MATCH_HASHLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_HELPER is not set -# CONFIG_NETFILTER_XT_MATCH_HL is not set -# CONFIG_NETFILTER_XT_MATCH_IPCOMP is not set -# CONFIG_NETFILTER_XT_MATCH_IPRANGE is not set -CONFIG_NETFILTER_XT_MATCH_IPVS=m -# CONFIG_NETFILTER_XT_MATCH_L2TP is not set -# CONFIG_NETFILTER_XT_MATCH_LENGTH is not set -# CONFIG_NETFILTER_XT_MATCH_LIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_MAC is not set -# CONFIG_NETFILTER_XT_MATCH_MARK is not set -# CONFIG_NETFILTER_XT_MATCH_MULTIPORT is not set -# CONFIG_NETFILTER_XT_MATCH_NFACCT is not set -# CONFIG_NETFILTER_XT_MATCH_OSF is not set -# CONFIG_NETFILTER_XT_MATCH_OWNER is not set -# CONFIG_NETFILTER_XT_MATCH_POLICY is not set -# CONFIG_NETFILTER_XT_MATCH_PHYSDEV is not set -# CONFIG_NETFILTER_XT_MATCH_PKTTYPE is not set -# CONFIG_NETFILTER_XT_MATCH_QUOTA is not set -# CONFIG_NETFILTER_XT_MATCH_RATEEST is not set -# CONFIG_NETFILTER_XT_MATCH_REALM is not set -# CONFIG_NETFILTER_XT_MATCH_RECENT is not set -# CONFIG_NETFILTER_XT_MATCH_SCTP is not set -# CONFIG_NETFILTER_XT_MATCH_SOCKET is not set -# CONFIG_NETFILTER_XT_MATCH_STATE is not set -# CONFIG_NETFILTER_XT_MATCH_STATISTIC is not set -# CONFIG_NETFILTER_XT_MATCH_STRING is not set -# CONFIG_NETFILTER_XT_MATCH_TCPMSS is not set -# CONFIG_NETFILTER_XT_MATCH_TIME is not set -# CONFIG_NETFILTER_XT_MATCH_U32 is not set -# end of Core Netfilter Configuration - -# CONFIG_IP_SET is not set -CONFIG_IP_VS=m -# CONFIG_IP_VS_IPV6 is not set -# CONFIG_IP_VS_DEBUG is not set -CONFIG_IP_VS_TAB_BITS=12 - -# -# IPVS transport protocol load balancing support -# -CONFIG_IP_VS_PROTO_TCP=y -CONFIG_IP_VS_PROTO_UDP=y -# CONFIG_IP_VS_PROTO_ESP is not set -# CONFIG_IP_VS_PROTO_AH is not set -# CONFIG_IP_VS_PROTO_SCTP is not set - -# -# IPVS scheduler -# -CONFIG_IP_VS_RR=m -# CONFIG_IP_VS_WRR is not set -# CONFIG_IP_VS_LC is not set -# CONFIG_IP_VS_WLC is not set -# CONFIG_IP_VS_FO is not set -# CONFIG_IP_VS_OVF is not set -# CONFIG_IP_VS_LBLC is not set -# CONFIG_IP_VS_LBLCR is not set -# CONFIG_IP_VS_DH is not set -# CONFIG_IP_VS_SH is not set -# CONFIG_IP_VS_MH is not set -# CONFIG_IP_VS_SED is not set -# CONFIG_IP_VS_NQ is not set -# CONFIG_IP_VS_TWOS is not set - -# -# IPVS SH scheduler -# -CONFIG_IP_VS_SH_TAB_BITS=8 - -# -# IPVS MH scheduler -# -CONFIG_IP_VS_MH_TAB_INDEX=12 - -# -# IPVS application helper -# -# CONFIG_IP_VS_FTP is not set -CONFIG_IP_VS_NFCT=y - -# -# IP: Netfilter Configuration -# -CONFIG_NF_DEFRAG_IPV4=m -# CONFIG_NF_SOCKET_IPV4 is not set -# CONFIG_NF_TPROXY_IPV4 is not set -# CONFIG_NF_DUP_IPV4 is not set -CONFIG_NF_LOG_ARP=m -CONFIG_NF_LOG_IPV4=m -CONFIG_NF_REJECT_IPV4=m -CONFIG_IP_NF_IPTABLES=y -# CONFIG_IP_NF_MATCH_AH is not set -# CONFIG_IP_NF_MATCH_ECN is not set -# CONFIG_IP_NF_MATCH_RPFILTER is not set -# CONFIG_IP_NF_MATCH_TTL is not set -CONFIG_IP_NF_FILTER=m -CONFIG_IP_NF_TARGET_REJECT=m -# CONFIG_IP_NF_TARGET_SYNPROXY is not set -CONFIG_IP_NF_NAT=m -CONFIG_IP_NF_TARGET_MASQUERADE=m -# CONFIG_IP_NF_TARGET_NETMAP is not set -CONFIG_IP_NF_TARGET_REDIRECT=m -CONFIG_IP_NF_MANGLE=m -# CONFIG_IP_NF_TARGET_CLUSTERIP is not set -# CONFIG_IP_NF_TARGET_ECN is not set -# CONFIG_IP_NF_TARGET_TTL is not set -# CONFIG_IP_NF_RAW is not set -# CONFIG_IP_NF_SECURITY is not set -# CONFIG_IP_NF_ARPTABLES is not set -# end of IP: Netfilter Configuration - -# -# IPv6: Netfilter Configuration -# -# CONFIG_NF_SOCKET_IPV6 is not set -# CONFIG_NF_TPROXY_IPV6 is not set -# CONFIG_NF_DUP_IPV6 is not set -CONFIG_NF_REJECT_IPV6=m -CONFIG_NF_LOG_IPV6=m -CONFIG_IP6_NF_IPTABLES=m -# CONFIG_IP6_NF_MATCH_AH is not set -# CONFIG_IP6_NF_MATCH_EUI64 is not set -# CONFIG_IP6_NF_MATCH_FRAG is not set -# CONFIG_IP6_NF_MATCH_OPTS is not set -# CONFIG_IP6_NF_MATCH_HL is not set -CONFIG_IP6_NF_MATCH_IPV6HEADER=m -# CONFIG_IP6_NF_MATCH_MH is not set -# CONFIG_IP6_NF_MATCH_RPFILTER is not set -# CONFIG_IP6_NF_MATCH_RT is not set -# CONFIG_IP6_NF_MATCH_SRH is not set -# CONFIG_IP6_NF_TARGET_HL is not set -CONFIG_IP6_NF_FILTER=m -CONFIG_IP6_NF_TARGET_REJECT=m -# CONFIG_IP6_NF_TARGET_SYNPROXY is not set -CONFIG_IP6_NF_MANGLE=m -# CONFIG_IP6_NF_RAW is not set -# CONFIG_IP6_NF_SECURITY is not set -# CONFIG_IP6_NF_NAT is not set -# end of IPv6: Netfilter Configuration - -CONFIG_NF_DEFRAG_IPV6=m -# CONFIG_NF_CONNTRACK_BRIDGE is not set -# CONFIG_BRIDGE_NF_EBTABLES is not set -# CONFIG_BPFILTER is not set -# CONFIG_IP_DCCP is not set -# CONFIG_IP_SCTP is not set -# CONFIG_RDS is not set -# CONFIG_TIPC is not set -# CONFIG_ATM is not set -# CONFIG_L2TP is not set -CONFIG_STP=m -CONFIG_BRIDGE=m -CONFIG_BRIDGE_IGMP_SNOOPING=y -CONFIG_BRIDGE_VLAN_FILTERING=y -# CONFIG_BRIDGE_MRP is not set -# CONFIG_BRIDGE_CFM is not set -# CONFIG_NET_DSA is not set -CONFIG_VLAN_8021Q=m -# CONFIG_VLAN_8021Q_GVRP is not set -# CONFIG_VLAN_8021Q_MVRP is not set -CONFIG_LLC=m -# CONFIG_LLC2 is not set -# CONFIG_ATALK is not set -# CONFIG_X25 is not set -# CONFIG_LAPB is not set -# CONFIG_PHONET is not set -# CONFIG_6LOWPAN is not set -# CONFIG_IEEE802154 is not set -CONFIG_NET_SCHED=y - -# -# Queueing/Scheduling -# -# CONFIG_NET_SCH_CBQ is not set -# CONFIG_NET_SCH_HTB is not set -# CONFIG_NET_SCH_HFSC is not set -# CONFIG_NET_SCH_PRIO is not set -# CONFIG_NET_SCH_MULTIQ is not set -# CONFIG_NET_SCH_RED is not set -# CONFIG_NET_SCH_SFB is not set -# CONFIG_NET_SCH_SFQ is not set -# CONFIG_NET_SCH_TEQL is not set -# CONFIG_NET_SCH_TBF is not set -# CONFIG_NET_SCH_CBS is not set -# CONFIG_NET_SCH_ETF is not set -# CONFIG_NET_SCH_TAPRIO is not set -# CONFIG_NET_SCH_GRED is not set -# CONFIG_NET_SCH_DSMARK is not set -# CONFIG_NET_SCH_NETEM is not set -# CONFIG_NET_SCH_DRR is not set -# CONFIG_NET_SCH_MQPRIO is not set -# CONFIG_NET_SCH_SKBPRIO is not set -# CONFIG_NET_SCH_CHOKE is not set -# CONFIG_NET_SCH_QFQ is not set -# CONFIG_NET_SCH_CODEL is not set -# CONFIG_NET_SCH_FQ_CODEL is not set -# CONFIG_NET_SCH_CAKE is not set -# CONFIG_NET_SCH_FQ is not set -# CONFIG_NET_SCH_HHF is not set -# CONFIG_NET_SCH_PIE is not set -# CONFIG_NET_SCH_PLUG is not set -# CONFIG_NET_SCH_ETS is not set -# CONFIG_NET_SCH_DEFAULT is not set - -# -# Classification -# -CONFIG_NET_CLS=y -# CONFIG_NET_CLS_BASIC is not set -# CONFIG_NET_CLS_ROUTE4 is not set -# CONFIG_NET_CLS_FW is not set -# CONFIG_NET_CLS_U32 is not set -# CONFIG_NET_CLS_RSVP is not set -# CONFIG_NET_CLS_RSVP6 is not set -# CONFIG_NET_CLS_FLOW is not set -CONFIG_NET_CLS_CGROUP=m -# CONFIG_NET_CLS_BPF is not set -# CONFIG_NET_CLS_FLOWER is not set -# CONFIG_NET_CLS_MATCHALL is not set -# CONFIG_NET_EMATCH is not set -# CONFIG_NET_CLS_ACT is not set -CONFIG_NET_SCH_FIFO=y -# CONFIG_DCB is not set -CONFIG_DNS_RESOLVER=y -# CONFIG_BATMAN_ADV is not set -# CONFIG_OPENVSWITCH is not set -# CONFIG_VSOCKETS is not set -CONFIG_NETLINK_DIAG=y -# CONFIG_MPLS is not set -# CONFIG_NET_NSH is not set -# CONFIG_HSR is not set -# CONFIG_NET_SWITCHDEV is not set -CONFIG_NET_L3_MASTER_DEV=y -# CONFIG_QRTR is not set -# CONFIG_NET_NCSI is not set -CONFIG_PCPU_DEV_REFCNT=y -CONFIG_RPS=y -CONFIG_RFS_ACCEL=y -CONFIG_SOCK_RX_QUEUE_MAPPING=y -CONFIG_XPS=y -CONFIG_CGROUP_NET_PRIO=y -CONFIG_CGROUP_NET_CLASSID=y -CONFIG_NET_RX_BUSY_POLL=y -CONFIG_BQL=y -# CONFIG_BPF_STREAM_PARSER is not set -CONFIG_NET_FLOW_LIMIT=y - -# -# Network testing -# -# CONFIG_NET_PKTGEN is not set -# end of Network testing -# end of Networking options - -# CONFIG_HAMRADIO is not set -# CONFIG_CAN is not set -# CONFIG_BT is not set -# CONFIG_AF_RXRPC is not set -# CONFIG_AF_KCM is not set -# CONFIG_MCTP is not set -CONFIG_WIRELESS=y -# CONFIG_CFG80211 is not set - -# -# CFG80211 needs to be enabled for MAC80211 -# -CONFIG_MAC80211_STA_HASH_MAX_SIZE=0 -# CONFIG_RFKILL is not set -CONFIG_NET_9P=y -CONFIG_NET_9P_FD=y -CONFIG_NET_9P_VIRTIO=y -# CONFIG_NET_9P_DEBUG is not set -# CONFIG_CAIF is not set -# CONFIG_CEPH_LIB is not set -# CONFIG_NFC is not set -# CONFIG_PSAMPLE is not set -# CONFIG_NET_IFE is not set -# CONFIG_LWTUNNEL is not set -CONFIG_DST_CACHE=y -CONFIG_GRO_CELLS=y -CONFIG_NET_SELFTESTS=y -CONFIG_NET_SOCK_MSG=y -CONFIG_PAGE_POOL=y -# CONFIG_PAGE_POOL_STATS is not set -CONFIG_FAILOVER=y -CONFIG_ETHTOOL_NETLINK=y - -# -# Device Drivers -# -CONFIG_HAVE_PCI=y -CONFIG_PCI=y -CONFIG_PCI_DOMAINS=y -CONFIG_PCI_DOMAINS_GENERIC=y -CONFIG_PCIEPORTBUS=y -# CONFIG_PCIEAER is not set -CONFIG_PCIEASPM=y -CONFIG_PCIEASPM_DEFAULT=y -# CONFIG_PCIEASPM_POWERSAVE is not set -# CONFIG_PCIEASPM_POWER_SUPERSAVE is not set -# CONFIG_PCIEASPM_PERFORMANCE is not set -CONFIG_PCIE_PME=y -# CONFIG_PCIE_PTM is not set -CONFIG_PCI_MSI=y -CONFIG_PCI_MSI_IRQ_DOMAIN=y -CONFIG_PCI_QUIRKS=y -# CONFIG_PCI_DEBUG is not set -# CONFIG_PCI_STUB is not set -CONFIG_PCI_ECAM=y -# CONFIG_PCI_IOV is not set -# CONFIG_PCI_PRI is not set -# CONFIG_PCI_PASID is not set -# CONFIG_PCIE_BUS_TUNE_OFF is not set -CONFIG_PCIE_BUS_DEFAULT=y -# CONFIG_PCIE_BUS_SAFE is not set -# CONFIG_PCIE_BUS_PERFORMANCE is not set -# CONFIG_PCIE_BUS_PEER2PEER is not set -CONFIG_VGA_ARB=y -CONFIG_VGA_ARB_MAX_GPUS=16 -# CONFIG_HOTPLUG_PCI is not set - -# -# PCI controller drivers -# -# CONFIG_PCI_FTPCI100 is not set -CONFIG_PCI_HOST_COMMON=y -CONFIG_PCI_HOST_GENERIC=y -CONFIG_PCIE_XILINX=y -CONFIG_PCIE_MICROCHIP_HOST=y - -# -# DesignWare PCI Core Support -# -CONFIG_PCIE_DW=y -CONFIG_PCIE_DW_HOST=y -# CONFIG_PCIE_DW_PLAT_HOST is not set -# CONFIG_PCI_MESON is not set -CONFIG_PCIE_FU740=y -# end of DesignWare PCI Core Support - -# -# Mobiveil PCIe Core Support -# -# end of Mobiveil PCIe Core Support - -# -# Cadence PCIe controllers support -# -# CONFIG_PCIE_CADENCE_PLAT_HOST is not set -# CONFIG_PCI_J721E_HOST is not set -# end of Cadence PCIe controllers support -# end of PCI controller drivers - -# -# PCI Endpoint -# -# CONFIG_PCI_ENDPOINT is not set -# end of PCI Endpoint - -# -# PCI switch controller drivers -# -# CONFIG_PCI_SW_SWITCHTEC is not set -# end of PCI switch controller drivers - -# CONFIG_CXL_BUS is not set -# CONFIG_PCCARD is not set -# CONFIG_RAPIDIO is not set - -# -# Generic Driver Options -# -CONFIG_AUXILIARY_BUS=y -# CONFIG_UEVENT_HELPER is not set -CONFIG_DEVTMPFS=y -CONFIG_DEVTMPFS_MOUNT=y -# CONFIG_DEVTMPFS_SAFE is not set -CONFIG_STANDALONE=y -CONFIG_PREVENT_FIRMWARE_BUILD=y - -# -# Firmware loader -# -CONFIG_FW_LOADER=y -CONFIG_EXTRA_FIRMWARE="" -# CONFIG_FW_LOADER_USER_HELPER is not set -# CONFIG_FW_LOADER_COMPRESS is not set -# CONFIG_FW_UPLOAD is not set -# end of Firmware loader - -CONFIG_WANT_DEV_COREDUMP=y -CONFIG_ALLOW_DEV_COREDUMP=y -CONFIG_DEV_COREDUMP=y -# CONFIG_DEBUG_DRIVER is not set -# CONFIG_DEBUG_DEVRES is not set -# CONFIG_DEBUG_TEST_DRIVER_REMOVE is not set -# CONFIG_TEST_ASYNC_DRIVER_PROBE is not set -CONFIG_REGMAP=y -CONFIG_REGMAP_I2C=y -CONFIG_REGMAP_MMIO=y -CONFIG_DMA_SHARED_BUFFER=y -# CONFIG_DMA_FENCE_TRACE is not set -CONFIG_GENERIC_ARCH_TOPOLOGY=y -# end of Generic Driver Options - -# -# Bus devices -# -# CONFIG_MOXTET is not set -# CONFIG_MHI_BUS is not set -# CONFIG_MHI_BUS_EP is not set -# end of Bus devices - -# CONFIG_CONNECTOR is not set - -# -# Firmware Drivers -# - -# -# ARM System Control and Management Interface Protocol -# -# end of ARM System Control and Management Interface Protocol - -# CONFIG_FIRMWARE_MEMMAP is not set -# CONFIG_SYSFB_SIMPLEFB is not set -# CONFIG_GOOGLE_FIRMWARE is not set - -# -# EFI (Extensible Firmware Interface) Support -# -CONFIG_EFI_ESRT=y -CONFIG_EFI_PARAMS_FROM_FDT=y -CONFIG_EFI_RUNTIME_WRAPPERS=y -CONFIG_EFI_GENERIC_STUB=y -# CONFIG_EFI_ZBOOT is not set -# CONFIG_EFI_BOOTLOADER_CONTROL is not set -# CONFIG_EFI_CAPSULE_LOADER is not set -# CONFIG_EFI_TEST is not set -# CONFIG_RESET_ATTACK_MITIGATION is not set -# CONFIG_EFI_DISABLE_PCI_DMA is not set -CONFIG_EFI_EARLYCON=y -# CONFIG_EFI_DISABLE_RUNTIME is not set -# CONFIG_EFI_COCO_SECRET is not set -# end of EFI (Extensible Firmware Interface) Support - -# -# Tegra firmware driver -# -# end of Tegra firmware driver -# end of Firmware Drivers - -# CONFIG_GNSS is not set -# CONFIG_MTD is not set -CONFIG_DTC=y -CONFIG_OF=y -# CONFIG_OF_UNITTEST is not set -CONFIG_OF_FLATTREE=y -CONFIG_OF_EARLY_FLATTREE=y -CONFIG_OF_KOBJ=y -CONFIG_OF_DYNAMIC=y -CONFIG_OF_ADDRESS=y -CONFIG_OF_IRQ=y -CONFIG_OF_RESERVED_MEM=y -CONFIG_OF_RESOLVE=y -CONFIG_OF_OVERLAY=y -CONFIG_OF_DMA_DEFAULT_COHERENT=y -# CONFIG_PARPORT is not set -CONFIG_BLK_DEV=y -# CONFIG_BLK_DEV_NULL_BLK is not set -CONFIG_CDROM=y -# CONFIG_BLK_DEV_PCIESSD_MTIP32XX is not set -CONFIG_BLK_DEV_LOOP=y -CONFIG_BLK_DEV_LOOP_MIN_COUNT=8 -# CONFIG_BLK_DEV_DRBD is not set -# CONFIG_BLK_DEV_NBD is not set -# CONFIG_BLK_DEV_RAM is not set -# CONFIG_CDROM_PKTCDVD is not set -# CONFIG_ATA_OVER_ETH is not set -CONFIG_VIRTIO_BLK=y -# CONFIG_BLK_DEV_RBD is not set -# CONFIG_BLK_DEV_UBLK is not set - -# -# NVME Support -# -CONFIG_NVME_CORE=m -CONFIG_BLK_DEV_NVME=m -# CONFIG_NVME_MULTIPATH is not set -# CONFIG_NVME_VERBOSE_ERRORS is not set -# CONFIG_NVME_HWMON is not set -# CONFIG_NVME_FC is not set -# CONFIG_NVME_TCP is not set -# CONFIG_NVME_AUTH is not set -# CONFIG_NVME_TARGET is not set -# end of NVME Support - -# -# Misc devices -# -# CONFIG_AD525X_DPOT is not set -# CONFIG_DUMMY_IRQ is not set -# CONFIG_PHANTOM is not set -# CONFIG_TIFM_CORE is not set -# CONFIG_ICS932S401 is not set -# CONFIG_ENCLOSURE_SERVICES is not set -# CONFIG_HP_ILO is not set -# CONFIG_APDS9802ALS is not set -# CONFIG_ISL29003 is not set -# CONFIG_ISL29020 is not set -# CONFIG_SENSORS_TSL2550 is not set -# CONFIG_SENSORS_BH1770 is not set -# CONFIG_SENSORS_APDS990X is not set -# CONFIG_HMC6352 is not set -# CONFIG_DS1682 is not set -# CONFIG_LATTICE_ECP3_CONFIG is not set -# CONFIG_SRAM is not set -# CONFIG_DW_XDATA_PCIE is not set -# CONFIG_PCI_ENDPOINT_TEST is not set -# CONFIG_XILINX_SDFEC is not set -# CONFIG_OPEN_DICE is not set -# CONFIG_VCPU_STALL_DETECTOR is not set -# CONFIG_C2PORT is not set - -# -# EEPROM support -# -CONFIG_EEPROM_AT24=y -# CONFIG_EEPROM_AT25 is not set -# CONFIG_EEPROM_LEGACY is not set -# CONFIG_EEPROM_MAX6875 is not set -# CONFIG_EEPROM_93CX6 is not set -# CONFIG_EEPROM_93XX46 is not set -# CONFIG_EEPROM_IDT_89HPESX is not set -# CONFIG_EEPROM_EE1004 is not set -# end of EEPROM support - -# CONFIG_CB710_CORE is not set - -# -# Texas Instruments shared transport line discipline -# -# CONFIG_TI_ST is not set -# end of Texas Instruments shared transport line discipline - -# CONFIG_SENSORS_LIS3_SPI is not set -# CONFIG_SENSORS_LIS3_I2C is not set -# CONFIG_ALTERA_STAPL is not set -# CONFIG_GENWQE is not set -# CONFIG_ECHO is not set -# CONFIG_BCM_VK is not set -# CONFIG_MISC_ALCOR_PCI is not set -# CONFIG_MISC_RTSX_PCI is not set -# CONFIG_MISC_RTSX_USB is not set -# CONFIG_HABANA_AI is not set -# CONFIG_PVPANIC is not set -# CONFIG_GP_PCI1XXXX is not set -# end of Misc devices - -# -# SCSI device support -# -CONFIG_SCSI_MOD=y -# CONFIG_RAID_ATTRS is not set -CONFIG_SCSI_COMMON=y -CONFIG_SCSI=y -CONFIG_SCSI_DMA=y -CONFIG_SCSI_PROC_FS=y - -# -# SCSI support type (disk, tape, CD-ROM) -# -CONFIG_BLK_DEV_SD=y -# CONFIG_CHR_DEV_ST is not set -CONFIG_BLK_DEV_SR=y -# CONFIG_CHR_DEV_SG is not set -CONFIG_BLK_DEV_BSG=y -# CONFIG_CHR_DEV_SCH is not set -# CONFIG_SCSI_CONSTANTS is not set -# CONFIG_SCSI_LOGGING is not set -# CONFIG_SCSI_SCAN_ASYNC is not set - -# -# SCSI Transports -# -# CONFIG_SCSI_SPI_ATTRS is not set -# CONFIG_SCSI_FC_ATTRS is not set -# CONFIG_SCSI_ISCSI_ATTRS is not set -# CONFIG_SCSI_SAS_ATTRS is not set -# CONFIG_SCSI_SAS_LIBSAS is not set -# CONFIG_SCSI_SRP_ATTRS is not set -# end of SCSI Transports - -CONFIG_SCSI_LOWLEVEL=y -# CONFIG_ISCSI_TCP is not set -# CONFIG_ISCSI_BOOT_SYSFS is not set -# CONFIG_SCSI_CXGB3_ISCSI is not set -# CONFIG_SCSI_CXGB4_ISCSI is not set -# CONFIG_SCSI_BNX2_ISCSI is not set -# CONFIG_BE2ISCSI is not set -# CONFIG_BLK_DEV_3W_XXXX_RAID is not set -# CONFIG_SCSI_HPSA is not set -# CONFIG_SCSI_3W_9XXX is not set -# CONFIG_SCSI_3W_SAS is not set -# CONFIG_SCSI_ACARD is not set -# CONFIG_SCSI_AACRAID is not set -# CONFIG_SCSI_AIC7XXX is not set -# CONFIG_SCSI_AIC79XX is not set -# CONFIG_SCSI_AIC94XX is not set -# CONFIG_SCSI_MVSAS is not set -# CONFIG_SCSI_MVUMI is not set -# CONFIG_SCSI_ADVANSYS is not set -# CONFIG_SCSI_ARCMSR is not set -# CONFIG_SCSI_ESAS2R is not set -# CONFIG_MEGARAID_NEWGEN is not set -# CONFIG_MEGARAID_LEGACY is not set -# CONFIG_MEGARAID_SAS is not set -# CONFIG_SCSI_MPT3SAS is not set -# CONFIG_SCSI_MPT2SAS is not set -# CONFIG_SCSI_MPI3MR is not set -# CONFIG_SCSI_SMARTPQI is not set -# CONFIG_SCSI_HPTIOP is not set -# CONFIG_SCSI_BUSLOGIC is not set -# CONFIG_SCSI_MYRB is not set -# CONFIG_SCSI_MYRS is not set -# CONFIG_SCSI_SNIC is not set -# CONFIG_SCSI_DMX3191D is not set -# CONFIG_SCSI_FDOMAIN_PCI is not set -# CONFIG_SCSI_IPS is not set -# CONFIG_SCSI_INITIO is not set -# CONFIG_SCSI_INIA100 is not set -# CONFIG_SCSI_STEX is not set -# CONFIG_SCSI_SYM53C8XX_2 is not set -# CONFIG_SCSI_IPR is not set -# CONFIG_SCSI_QLOGIC_1280 is not set -# CONFIG_SCSI_QLA_ISCSI is not set -# CONFIG_SCSI_DC395x is not set -# CONFIG_SCSI_AM53C974 is not set -# CONFIG_SCSI_WD719X is not set -# CONFIG_SCSI_DEBUG is not set -# CONFIG_SCSI_PMCRAID is not set -# CONFIG_SCSI_PM8001 is not set -CONFIG_SCSI_VIRTIO=y -# CONFIG_SCSI_DH is not set -# end of SCSI device support - -CONFIG_ATA=y -CONFIG_SATA_HOST=y -CONFIG_ATA_VERBOSE_ERROR=y -CONFIG_ATA_FORCE=y -CONFIG_SATA_PMP=y - -# -# Controllers with non-SFF native interface -# -CONFIG_SATA_AHCI=y -CONFIG_SATA_MOBILE_LPM_POLICY=0 -CONFIG_SATA_AHCI_PLATFORM=y -# CONFIG_AHCI_DWC is not set -# CONFIG_AHCI_CEVA is not set -# CONFIG_AHCI_QORIQ is not set -# CONFIG_SATA_INIC162X is not set -# CONFIG_SATA_ACARD_AHCI is not set -# CONFIG_SATA_SIL24 is not set -CONFIG_ATA_SFF=y - -# -# SFF controllers with custom DMA interface -# -# CONFIG_PDC_ADMA is not set -# CONFIG_SATA_QSTOR is not set -# CONFIG_SATA_SX4 is not set -CONFIG_ATA_BMDMA=y - -# -# SATA SFF controllers with BMDMA -# -# CONFIG_ATA_PIIX is not set -# CONFIG_SATA_MV is not set -# CONFIG_SATA_NV is not set -# CONFIG_SATA_PROMISE is not set -# CONFIG_SATA_SIL is not set -# CONFIG_SATA_SIS is not set -# CONFIG_SATA_SVW is not set -# CONFIG_SATA_ULI is not set -# CONFIG_SATA_VIA is not set -# CONFIG_SATA_VITESSE is not set - -# -# PATA SFF controllers with BMDMA -# -# CONFIG_PATA_ALI is not set -# CONFIG_PATA_AMD is not set -# CONFIG_PATA_ARTOP is not set -# CONFIG_PATA_ATIIXP is not set -# CONFIG_PATA_ATP867X is not set -# CONFIG_PATA_CMD64X is not set -# CONFIG_PATA_CYPRESS is not set -# CONFIG_PATA_EFAR is not set -# CONFIG_PATA_HPT366 is not set -# CONFIG_PATA_HPT37X is not set -# CONFIG_PATA_HPT3X2N is not set -# CONFIG_PATA_HPT3X3 is not set -# CONFIG_PATA_IT8213 is not set -# CONFIG_PATA_IT821X is not set -# CONFIG_PATA_JMICRON is not set -# CONFIG_PATA_MARVELL is not set -# CONFIG_PATA_NETCELL is not set -# CONFIG_PATA_NINJA32 is not set -# CONFIG_PATA_NS87415 is not set -# CONFIG_PATA_OLDPIIX is not set -# CONFIG_PATA_OPTIDMA is not set -# CONFIG_PATA_PDC2027X is not set -# CONFIG_PATA_PDC_OLD is not set -# CONFIG_PATA_RADISYS is not set -# CONFIG_PATA_RDC is not set -# CONFIG_PATA_SCH is not set -# CONFIG_PATA_SERVERWORKS is not set -# CONFIG_PATA_SIL680 is not set -# CONFIG_PATA_SIS is not set -# CONFIG_PATA_TOSHIBA is not set -# CONFIG_PATA_TRIFLEX is not set -# CONFIG_PATA_VIA is not set -# CONFIG_PATA_WINBOND is not set - -# -# PIO-only SFF controllers -# -# CONFIG_PATA_CMD640_PCI is not set -# CONFIG_PATA_MPIIX is not set -# CONFIG_PATA_NS87410 is not set -# CONFIG_PATA_OPTI is not set -# CONFIG_PATA_OF_PLATFORM is not set -# CONFIG_PATA_RZ1000 is not set - -# -# Generic fallback / legacy drivers -# -# CONFIG_ATA_GENERIC is not set -# CONFIG_PATA_LEGACY is not set -CONFIG_MD=y -# CONFIG_BLK_DEV_MD is not set -# CONFIG_BCACHE is not set -CONFIG_BLK_DEV_DM_BUILTIN=y -CONFIG_BLK_DEV_DM=y -# CONFIG_DM_DEBUG is not set -CONFIG_DM_BUFIO=m -# CONFIG_DM_DEBUG_BLOCK_MANAGER_LOCKING is not set -CONFIG_DM_BIO_PRISON=m -CONFIG_DM_PERSISTENT_DATA=m -# CONFIG_DM_UNSTRIPED is not set -# CONFIG_DM_CRYPT is not set -# CONFIG_DM_SNAPSHOT is not set -CONFIG_DM_THIN_PROVISIONING=m -# CONFIG_DM_CACHE is not set -# CONFIG_DM_WRITECACHE is not set -# CONFIG_DM_EBS is not set -# CONFIG_DM_ERA is not set -# CONFIG_DM_CLONE is not set -# CONFIG_DM_MIRROR is not set -# CONFIG_DM_RAID is not set -# CONFIG_DM_ZERO is not set -# CONFIG_DM_MULTIPATH is not set -# CONFIG_DM_DELAY is not set -# CONFIG_DM_DUST is not set -# CONFIG_DM_INIT is not set -# CONFIG_DM_UEVENT is not set -# CONFIG_DM_FLAKEY is not set -# CONFIG_DM_VERITY is not set -# CONFIG_DM_SWITCH is not set -# CONFIG_DM_LOG_WRITES is not set -# CONFIG_DM_INTEGRITY is not set -# CONFIG_DM_AUDIT is not set -# CONFIG_TARGET_CORE is not set -# CONFIG_FUSION is not set - -# -# IEEE 1394 (FireWire) support -# -# CONFIG_FIREWIRE is not set -# CONFIG_FIREWIRE_NOSY is not set -# end of IEEE 1394 (FireWire) support - -CONFIG_NETDEVICES=y -CONFIG_NET_CORE=y -# CONFIG_BONDING is not set -CONFIG_DUMMY=m -# CONFIG_WIREGUARD is not set -# CONFIG_EQUALIZER is not set -# CONFIG_NET_FC is not set -# CONFIG_NET_TEAM is not set -CONFIG_MACVLAN=m -# CONFIG_MACVTAP is not set -CONFIG_IPVLAN_L3S=y -CONFIG_IPVLAN=m -# CONFIG_IPVTAP is not set -CONFIG_VXLAN=m -# CONFIG_GENEVE is not set -# CONFIG_BAREUDP is not set -# CONFIG_GTP is not set -# CONFIG_AMT is not set -# CONFIG_MACSEC is not set -# CONFIG_NETCONSOLE is not set -# CONFIG_TUN is not set -# CONFIG_TUN_VNET_CROSS_LE is not set -CONFIG_VETH=m -CONFIG_VIRTIO_NET=y -# CONFIG_NLMON is not set -# CONFIG_ARCNET is not set -CONFIG_ETHERNET=y -CONFIG_NET_VENDOR_3COM=y -# CONFIG_VORTEX is not set -# CONFIG_TYPHOON is not set -CONFIG_NET_VENDOR_ADAPTEC=y -# CONFIG_ADAPTEC_STARFIRE is not set -CONFIG_NET_VENDOR_AGERE=y -# CONFIG_ET131X is not set -CONFIG_NET_VENDOR_ALACRITECH=y -# CONFIG_SLICOSS is not set -CONFIG_NET_VENDOR_ALTEON=y -# CONFIG_ACENIC is not set -# CONFIG_ALTERA_TSE is not set -CONFIG_NET_VENDOR_AMAZON=y -# CONFIG_ENA_ETHERNET is not set -CONFIG_NET_VENDOR_AMD=y -# CONFIG_AMD8111_ETH is not set -# CONFIG_PCNET32 is not set -CONFIG_NET_VENDOR_AQUANTIA=y -# CONFIG_AQTION is not set -CONFIG_NET_VENDOR_ARC=y -CONFIG_NET_VENDOR_ASIX=y -# CONFIG_SPI_AX88796C is not set -CONFIG_NET_VENDOR_ATHEROS=y -# CONFIG_ATL2 is not set -# CONFIG_ATL1 is not set -# CONFIG_ATL1E is not set -# CONFIG_ATL1C is not set -# CONFIG_ALX is not set -CONFIG_NET_VENDOR_BROADCOM=y -# CONFIG_B44 is not set -# CONFIG_BCMGENET is not set -# CONFIG_BNX2 is not set -# CONFIG_CNIC is not set -# CONFIG_TIGON3 is not set -# CONFIG_BNX2X is not set -# CONFIG_SYSTEMPORT is not set -# CONFIG_BNXT is not set -CONFIG_NET_VENDOR_CADENCE=y -CONFIG_MACB=y -# CONFIG_MACB_PCI is not set -CONFIG_NET_VENDOR_CAVIUM=y -# CONFIG_THUNDER_NIC_PF is not set -# CONFIG_THUNDER_NIC_VF is not set -# CONFIG_THUNDER_NIC_BGX is not set -# CONFIG_THUNDER_NIC_RGX is not set -# CONFIG_LIQUIDIO is not set -# CONFIG_LIQUIDIO_VF is not set -CONFIG_NET_VENDOR_CHELSIO=y -# CONFIG_CHELSIO_T1 is not set -# CONFIG_CHELSIO_T3 is not set -# CONFIG_CHELSIO_T4 is not set -# CONFIG_CHELSIO_T4VF is not set -CONFIG_NET_VENDOR_CISCO=y -# CONFIG_ENIC is not set -CONFIG_NET_VENDOR_CORTINA=y -# CONFIG_GEMINI_ETHERNET is not set -CONFIG_NET_VENDOR_DAVICOM=y -# CONFIG_DM9051 is not set -# CONFIG_DNET is not set -CONFIG_NET_VENDOR_DEC=y -# CONFIG_NET_TULIP is not set -CONFIG_NET_VENDOR_DLINK=y -# CONFIG_DL2K is not set -# CONFIG_SUNDANCE is not set -CONFIG_NET_VENDOR_EMULEX=y -# CONFIG_BE2NET is not set -CONFIG_NET_VENDOR_ENGLEDER=y -# CONFIG_TSNEP is not set -CONFIG_NET_VENDOR_EZCHIP=y -# CONFIG_EZCHIP_NPS_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_FUNGIBLE=y -# CONFIG_FUN_ETH is not set -CONFIG_NET_VENDOR_GOOGLE=y -CONFIG_NET_VENDOR_HUAWEI=y -CONFIG_NET_VENDOR_I825XX=y -CONFIG_NET_VENDOR_INTEL=y -# CONFIG_E100 is not set -# CONFIG_E1000 is not set -CONFIG_E1000E=y -# CONFIG_IGB is not set -# CONFIG_IGBVF is not set -# CONFIG_IXGB is not set -# CONFIG_IXGBE is not set -# CONFIG_IXGBEVF is not set -# CONFIG_I40E is not set -# CONFIG_I40EVF is not set -# CONFIG_ICE is not set -# CONFIG_FM10K is not set -# CONFIG_IGC is not set -CONFIG_NET_VENDOR_WANGXUN=y -# CONFIG_NGBE is not set -# CONFIG_TXGBE is not set -# CONFIG_JME is not set -CONFIG_NET_VENDOR_ADI=y -CONFIG_NET_VENDOR_LITEX=y -# CONFIG_LITEX_LITEETH is not set -CONFIG_NET_VENDOR_MARVELL=y -# CONFIG_MVMDIO is not set -# CONFIG_SKGE is not set -# CONFIG_SKY2 is not set -# CONFIG_OCTEON_EP is not set -CONFIG_NET_VENDOR_MELLANOX=y -# CONFIG_MLX4_EN is not set -# CONFIG_MLX5_CORE is not set -# CONFIG_MLXSW_CORE is not set -# CONFIG_MLXFW is not set -CONFIG_NET_VENDOR_MICREL=y -# CONFIG_KS8851 is not set -# CONFIG_KS8851_MLL is not set -# CONFIG_KSZ884X_PCI is not set -CONFIG_NET_VENDOR_MICROCHIP=y -# CONFIG_ENC28J60 is not set -# CONFIG_ENCX24J600 is not set -# CONFIG_LAN743X is not set -CONFIG_NET_VENDOR_MICROSEMI=y -CONFIG_NET_VENDOR_MICROSOFT=y -CONFIG_NET_VENDOR_MYRI=y -# CONFIG_MYRI10GE is not set -# CONFIG_FEALNX is not set -CONFIG_NET_VENDOR_NI=y -# CONFIG_NI_XGE_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_NATSEMI=y -# CONFIG_NATSEMI is not set -# CONFIG_NS83820 is not set -CONFIG_NET_VENDOR_NETERION=y -# CONFIG_S2IO is not set -CONFIG_NET_VENDOR_NETRONOME=y -# CONFIG_NFP is not set -CONFIG_NET_VENDOR_8390=y -# CONFIG_NE2K_PCI is not set -CONFIG_NET_VENDOR_NVIDIA=y -# CONFIG_FORCEDETH is not set -CONFIG_NET_VENDOR_OKI=y -# CONFIG_ETHOC is not set -CONFIG_NET_VENDOR_PACKET_ENGINES=y -# CONFIG_HAMACHI is not set -# CONFIG_YELLOWFIN is not set -CONFIG_NET_VENDOR_PENSANDO=y -# CONFIG_IONIC is not set -CONFIG_NET_VENDOR_QLOGIC=y -# CONFIG_QLA3XXX is not set -# CONFIG_QLCNIC is not set -# CONFIG_NETXEN_NIC is not set -# CONFIG_QED is not set -CONFIG_NET_VENDOR_BROCADE=y -# CONFIG_BNA is not set -CONFIG_NET_VENDOR_QUALCOMM=y -# CONFIG_QCA7000_SPI is not set -# CONFIG_QCOM_EMAC is not set -# CONFIG_RMNET is not set -CONFIG_NET_VENDOR_RDC=y -# CONFIG_R6040 is not set -CONFIG_NET_VENDOR_REALTEK=y -# CONFIG_8139CP is not set -# CONFIG_8139TOO is not set -CONFIG_R8169=y -CONFIG_NET_VENDOR_RENESAS=y -CONFIG_NET_VENDOR_ROCKER=y -CONFIG_NET_VENDOR_SAMSUNG=y -# CONFIG_SXGBE_ETH is not set -CONFIG_NET_VENDOR_SEEQ=y -CONFIG_NET_VENDOR_SILAN=y -# CONFIG_SC92031 is not set -CONFIG_NET_VENDOR_SIS=y -# CONFIG_SIS900 is not set -# CONFIG_SIS190 is not set -CONFIG_NET_VENDOR_SOLARFLARE=y -# CONFIG_SFC is not set -# CONFIG_SFC_FALCON is not set -CONFIG_NET_VENDOR_SMSC=y -# CONFIG_EPIC100 is not set -# CONFIG_SMSC911X is not set -# CONFIG_SMSC9420 is not set -CONFIG_NET_VENDOR_SOCIONEXT=y -CONFIG_NET_VENDOR_STMICRO=y -# CONFIG_STMMAC_ETH is not set -CONFIG_NET_VENDOR_SUN=y -# CONFIG_HAPPYMEAL is not set -# CONFIG_SUNGEM is not set -# CONFIG_CASSINI is not set -# CONFIG_NIU is not set -CONFIG_NET_VENDOR_SYNOPSYS=y -# CONFIG_DWC_XLGMAC is not set -CONFIG_NET_VENDOR_TEHUTI=y -# CONFIG_TEHUTI is not set -CONFIG_NET_VENDOR_TI=y -# CONFIG_TI_CPSW_PHY_SEL is not set -# CONFIG_TLAN is not set -CONFIG_NET_VENDOR_VERTEXCOM=y -# CONFIG_MSE102X is not set -CONFIG_NET_VENDOR_VIA=y -# CONFIG_VIA_RHINE is not set -# CONFIG_VIA_VELOCITY is not set -CONFIG_NET_VENDOR_WIZNET=y -# CONFIG_WIZNET_W5100 is not set -# CONFIG_WIZNET_W5300 is not set -CONFIG_NET_VENDOR_XILINX=y -# CONFIG_XILINX_EMACLITE is not set -# CONFIG_XILINX_AXI_EMAC is not set -# CONFIG_XILINX_LL_TEMAC is not set -# CONFIG_FDDI is not set -# CONFIG_HIPPI is not set -CONFIG_PHYLINK=y -CONFIG_PHYLIB=y -CONFIG_SWPHY=y -CONFIG_FIXED_PHY=y -# CONFIG_SFP is not set - -# -# MII PHY device drivers -# -# CONFIG_AMD_PHY is not set -# CONFIG_ADIN_PHY is not set -# CONFIG_ADIN1100_PHY is not set -# CONFIG_AQUANTIA_PHY is not set -# CONFIG_AX88796B_PHY is not set -# CONFIG_BROADCOM_PHY is not set -# CONFIG_BCM54140_PHY is not set -# CONFIG_BCM7XXX_PHY is not set -# CONFIG_BCM84881_PHY is not set -# CONFIG_BCM87XX_PHY is not set -# CONFIG_CICADA_PHY is not set -# CONFIG_CORTINA_PHY is not set -# CONFIG_DAVICOM_PHY is not set -# CONFIG_ICPLUS_PHY is not set -# CONFIG_LXT_PHY is not set -# CONFIG_INTEL_XWAY_PHY is not set -# CONFIG_LSI_ET1011C_PHY is not set -# CONFIG_MARVELL_PHY is not set -# CONFIG_MARVELL_10G_PHY is not set -# CONFIG_MARVELL_88X2222_PHY is not set -# CONFIG_MAXLINEAR_GPHY is not set -# CONFIG_MEDIATEK_GE_PHY is not set -# CONFIG_MICREL_PHY is not set -# CONFIG_MICROCHIP_PHY is not set -# CONFIG_MICROCHIP_T1_PHY is not set -CONFIG_MICROSEMI_PHY=y -# CONFIG_MOTORCOMM_PHY is not set -# CONFIG_NATIONAL_PHY is not set -# CONFIG_NXP_C45_TJA11XX_PHY is not set -# CONFIG_NXP_TJA11XX_PHY is not set -# CONFIG_QSEMI_PHY is not set -CONFIG_REALTEK_PHY=y -# CONFIG_RENESAS_PHY is not set -# CONFIG_ROCKCHIP_PHY is not set -# CONFIG_SMSC_PHY is not set -# CONFIG_STE10XP is not set -# CONFIG_TERANETICS_PHY is not set -# CONFIG_DP83822_PHY is not set -# CONFIG_DP83TC811_PHY is not set -# CONFIG_DP83848_PHY is not set -# CONFIG_DP83867_PHY is not set -# CONFIG_DP83869_PHY is not set -# CONFIG_DP83TD510_PHY is not set -# CONFIG_VITESSE_PHY is not set -# CONFIG_XILINX_GMII2RGMII is not set -# CONFIG_MICREL_KS8995MA is not set -# CONFIG_PSE_CONTROLLER is not set -CONFIG_MDIO_DEVICE=y -CONFIG_MDIO_BUS=y -CONFIG_FWNODE_MDIO=y -CONFIG_OF_MDIO=y -CONFIG_MDIO_DEVRES=y -# CONFIG_MDIO_BITBANG is not set -# CONFIG_MDIO_BCM_UNIMAC is not set -# CONFIG_MDIO_HISI_FEMAC is not set -# CONFIG_MDIO_MVUSB is not set -# CONFIG_MDIO_MSCC_MIIM is not set -# CONFIG_MDIO_OCTEON is not set -# CONFIG_MDIO_IPQ4019 is not set -# CONFIG_MDIO_IPQ8064 is not set -# CONFIG_MDIO_THUNDER is not set - -# -# MDIO Multiplexers -# -# CONFIG_MDIO_BUS_MUX_GPIO is not set -# CONFIG_MDIO_BUS_MUX_MULTIPLEXER is not set -# CONFIG_MDIO_BUS_MUX_MMIOREG is not set - -# -# PCS device drivers -# -# end of PCS device drivers - -# CONFIG_PPP is not set -# CONFIG_SLIP is not set -CONFIG_USB_NET_DRIVERS=y -# CONFIG_USB_CATC is not set -# CONFIG_USB_KAWETH is not set -# CONFIG_USB_PEGASUS is not set -# CONFIG_USB_RTL8150 is not set -# CONFIG_USB_RTL8152 is not set -# CONFIG_USB_LAN78XX is not set -# CONFIG_USB_USBNET is not set -# CONFIG_USB_IPHETH is not set -CONFIG_WLAN=y -CONFIG_WLAN_VENDOR_ADMTEK=y -CONFIG_WLAN_VENDOR_ATH=y -# CONFIG_ATH_DEBUG is not set -# CONFIG_ATH5K_PCI is not set -CONFIG_WLAN_VENDOR_ATMEL=y -CONFIG_WLAN_VENDOR_BROADCOM=y -CONFIG_WLAN_VENDOR_CISCO=y -CONFIG_WLAN_VENDOR_INTEL=y -CONFIG_WLAN_VENDOR_INTERSIL=y -# CONFIG_HOSTAP is not set -CONFIG_WLAN_VENDOR_MARVELL=y -CONFIG_WLAN_VENDOR_MEDIATEK=y -CONFIG_WLAN_VENDOR_MICROCHIP=y -CONFIG_WLAN_VENDOR_PURELIFI=y -CONFIG_WLAN_VENDOR_RALINK=y -CONFIG_WLAN_VENDOR_REALTEK=y -CONFIG_WLAN_VENDOR_RSI=y -CONFIG_WLAN_VENDOR_SILABS=y -CONFIG_WLAN_VENDOR_ST=y -CONFIG_WLAN_VENDOR_TI=y -CONFIG_WLAN_VENDOR_ZYDAS=y -CONFIG_WLAN_VENDOR_QUANTENNA=y -# CONFIG_WAN is not set - -# -# Wireless WAN -# -# CONFIG_WWAN is not set -# end of Wireless WAN - -# CONFIG_VMXNET3 is not set -# CONFIG_NETDEVSIM is not set -CONFIG_NET_FAILOVER=y -# CONFIG_ISDN is not set - -# -# Input device support -# -CONFIG_INPUT=y -# CONFIG_INPUT_FF_MEMLESS is not set -# CONFIG_INPUT_SPARSEKMAP is not set -# CONFIG_INPUT_MATRIXKMAP is not set -CONFIG_INPUT_VIVALDIFMAP=y - -# -# Userland interfaces -# -CONFIG_INPUT_MOUSEDEV=y -# CONFIG_INPUT_MOUSEDEV_PSAUX is not set -CONFIG_INPUT_MOUSEDEV_SCREEN_X=1024 -CONFIG_INPUT_MOUSEDEV_SCREEN_Y=768 -# CONFIG_INPUT_JOYDEV is not set -# CONFIG_INPUT_EVDEV is not set -# CONFIG_INPUT_EVBUG is not set - -# -# Input Device Drivers -# -CONFIG_INPUT_KEYBOARD=y -# CONFIG_KEYBOARD_ADC is not set -# CONFIG_KEYBOARD_ADP5588 is not set -# CONFIG_KEYBOARD_ADP5589 is not set -CONFIG_KEYBOARD_ATKBD=y -# CONFIG_KEYBOARD_QT1050 is not set -# CONFIG_KEYBOARD_QT1070 is not set -# CONFIG_KEYBOARD_QT2160 is not set -# CONFIG_KEYBOARD_DLINK_DIR685 is not set -# CONFIG_KEYBOARD_LKKBD is not set -# CONFIG_KEYBOARD_GPIO is not set -# CONFIG_KEYBOARD_GPIO_POLLED is not set -# CONFIG_KEYBOARD_TCA6416 is not set -# CONFIG_KEYBOARD_TCA8418 is not set -# CONFIG_KEYBOARD_MATRIX is not set -# CONFIG_KEYBOARD_LM8333 is not set -# CONFIG_KEYBOARD_MAX7359 is not set -# CONFIG_KEYBOARD_MCS is not set -# CONFIG_KEYBOARD_MPR121 is not set -# CONFIG_KEYBOARD_NEWTON is not set -# CONFIG_KEYBOARD_OPENCORES is not set -# CONFIG_KEYBOARD_SAMSUNG is not set -# CONFIG_KEYBOARD_GOLDFISH_EVENTS is not set -# CONFIG_KEYBOARD_STOWAWAY is not set -# CONFIG_KEYBOARD_SUNKBD is not set -# CONFIG_KEYBOARD_OMAP4 is not set -# CONFIG_KEYBOARD_XTKBD is not set -# CONFIG_KEYBOARD_CAP11XX is not set -# CONFIG_KEYBOARD_BCM is not set -# CONFIG_KEYBOARD_CYPRESS_SF is not set -CONFIG_INPUT_MOUSE=y -CONFIG_MOUSE_PS2=y -CONFIG_MOUSE_PS2_ALPS=y -CONFIG_MOUSE_PS2_BYD=y -CONFIG_MOUSE_PS2_LOGIPS2PP=y -CONFIG_MOUSE_PS2_SYNAPTICS=y -CONFIG_MOUSE_PS2_SYNAPTICS_SMBUS=y -CONFIG_MOUSE_PS2_CYPRESS=y -CONFIG_MOUSE_PS2_TRACKPOINT=y -# CONFIG_MOUSE_PS2_ELANTECH is not set -# CONFIG_MOUSE_PS2_SENTELIC is not set -# CONFIG_MOUSE_PS2_TOUCHKIT is not set -CONFIG_MOUSE_PS2_FOCALTECH=y -CONFIG_MOUSE_PS2_SMBUS=y -# CONFIG_MOUSE_SERIAL is not set -# CONFIG_MOUSE_APPLETOUCH is not set -# CONFIG_MOUSE_BCM5974 is not set -# CONFIG_MOUSE_CYAPA is not set -# CONFIG_MOUSE_ELAN_I2C is not set -# CONFIG_MOUSE_VSXXXAA is not set -# CONFIG_MOUSE_GPIO is not set -# CONFIG_MOUSE_SYNAPTICS_I2C is not set -# CONFIG_MOUSE_SYNAPTICS_USB is not set -# CONFIG_INPUT_JOYSTICK is not set -# CONFIG_INPUT_TABLET is not set -# CONFIG_INPUT_TOUCHSCREEN is not set -# CONFIG_INPUT_MISC is not set -# CONFIG_RMI4_CORE is not set - -# -# Hardware I/O ports -# -CONFIG_SERIO=y -CONFIG_SERIO_SERPORT=y -# CONFIG_SERIO_PCIPS2 is not set -CONFIG_SERIO_LIBPS2=y -# CONFIG_SERIO_RAW is not set -# CONFIG_SERIO_ALTERA_PS2 is not set -# CONFIG_SERIO_PS2MULT is not set -# CONFIG_SERIO_ARC_PS2 is not set -# CONFIG_SERIO_APBPS2 is not set -# CONFIG_SERIO_GPIO_PS2 is not set -# CONFIG_USERIO is not set -# CONFIG_GAMEPORT is not set -# end of Hardware I/O ports -# end of Input device support - -# -# Character devices -# -CONFIG_TTY=y -CONFIG_VT=y -CONFIG_CONSOLE_TRANSLATIONS=y -CONFIG_VT_CONSOLE=y -CONFIG_HW_CONSOLE=y -CONFIG_VT_HW_CONSOLE_BINDING=y -CONFIG_UNIX98_PTYS=y -CONFIG_LEGACY_PTYS=y -CONFIG_LEGACY_PTY_COUNT=256 -CONFIG_LDISC_AUTOLOAD=y - -# -# Serial drivers -# -CONFIG_SERIAL_EARLYCON=y -CONFIG_SERIAL_8250=y -CONFIG_SERIAL_8250_DEPRECATED_OPTIONS=y -CONFIG_SERIAL_8250_16550A_VARIANTS=y -# CONFIG_SERIAL_8250_FINTEK is not set -CONFIG_SERIAL_8250_CONSOLE=y -CONFIG_SERIAL_8250_PCI=y -CONFIG_SERIAL_8250_EXAR=y -CONFIG_SERIAL_8250_NR_UARTS=4 -CONFIG_SERIAL_8250_RUNTIME_UARTS=4 -# CONFIG_SERIAL_8250_EXTENDED is not set -# CONFIG_SERIAL_8250_DW is not set -# CONFIG_SERIAL_8250_RT288X is not set -CONFIG_SERIAL_8250_PERICOM=y -CONFIG_SERIAL_OF_PLATFORM=y - -# -# Non-8250 serial port support -# -# CONFIG_SERIAL_MAX3100 is not set -# CONFIG_SERIAL_MAX310X is not set -# CONFIG_SERIAL_UARTLITE is not set -CONFIG_SERIAL_CORE=y -CONFIG_SERIAL_CORE_CONSOLE=y -# CONFIG_SERIAL_JSM is not set -CONFIG_SERIAL_SIFIVE=y -CONFIG_SERIAL_SIFIVE_CONSOLE=y -# CONFIG_SERIAL_SCCNXP is not set -# CONFIG_SERIAL_SC16IS7XX is not set -# CONFIG_SERIAL_ALTERA_JTAGUART is not set -# CONFIG_SERIAL_ALTERA_UART is not set -# CONFIG_SERIAL_XILINX_PS_UART is not set -# CONFIG_SERIAL_ARC is not set -# CONFIG_SERIAL_RP2 is not set -# CONFIG_SERIAL_FSL_LPUART is not set -# CONFIG_SERIAL_FSL_LINFLEXUART is not set -# CONFIG_SERIAL_CONEXANT_DIGICOLOR is not set -# CONFIG_SERIAL_SPRD is not set -# end of Serial drivers - -CONFIG_SERIAL_MCTRL_GPIO=y -# CONFIG_SERIAL_NONSTANDARD is not set -# CONFIG_GOLDFISH_TTY is not set -# CONFIG_N_GSM is not set -# CONFIG_NOZOMI is not set -# CONFIG_NULL_TTY is not set -CONFIG_HVC_DRIVER=y -# CONFIG_RPMSG_TTY is not set -# CONFIG_SERIAL_DEV_BUS is not set -# CONFIG_TTY_PRINTK is not set -CONFIG_VIRTIO_CONSOLE=y -# CONFIG_IPMI_HANDLER is not set -CONFIG_HW_RANDOM=y -# CONFIG_HW_RANDOM_TIMERIOMEM is not set -# CONFIG_HW_RANDOM_BA431 is not set -CONFIG_HW_RANDOM_VIRTIO=y -CONFIG_HW_RANDOM_POLARFIRE_SOC=y -# CONFIG_HW_RANDOM_CCTRNG is not set -# CONFIG_HW_RANDOM_XIPHERA is not set -# CONFIG_APPLICOM is not set -CONFIG_DEVMEM=y -CONFIG_DEVPORT=y -# CONFIG_TCG_TPM is not set -# CONFIG_XILLYBUS is not set -# CONFIG_XILLYUSB is not set -CONFIG_RANDOM_TRUST_CPU=y -CONFIG_RANDOM_TRUST_BOOTLOADER=y -# end of Character devices - -# -# I2C support -# -CONFIG_I2C=y -CONFIG_I2C_BOARDINFO=y -CONFIG_I2C_COMPAT=y -# CONFIG_I2C_CHARDEV is not set -CONFIG_I2C_MUX=m - -# -# Multiplexer I2C Chip support -# -# CONFIG_I2C_ARB_GPIO_CHALLENGE is not set -# CONFIG_I2C_MUX_GPIO is not set -# CONFIG_I2C_MUX_GPMUX is not set -# CONFIG_I2C_MUX_LTC4306 is not set -# CONFIG_I2C_MUX_PCA9541 is not set -# CONFIG_I2C_MUX_PCA954x is not set -# CONFIG_I2C_MUX_PINCTRL is not set -# CONFIG_I2C_MUX_REG is not set -# CONFIG_I2C_DEMUX_PINCTRL is not set -# CONFIG_I2C_MUX_MLXCPLD is not set -# end of Multiplexer I2C Chip support - -CONFIG_I2C_HELPER_AUTO=y - -# -# I2C Hardware Bus support -# - -# -# PC SMBus host controller drivers -# -# CONFIG_I2C_ALI1535 is not set -# CONFIG_I2C_ALI1563 is not set -# CONFIG_I2C_ALI15X3 is not set -# CONFIG_I2C_AMD756 is not set -# CONFIG_I2C_AMD8111 is not set -# CONFIG_I2C_I801 is not set -# CONFIG_I2C_ISCH is not set -# CONFIG_I2C_PIIX4 is not set -# CONFIG_I2C_NFORCE2 is not set -# CONFIG_I2C_NVIDIA_GPU is not set -# CONFIG_I2C_SIS5595 is not set -# CONFIG_I2C_SIS630 is not set -# CONFIG_I2C_SIS96X is not set -# CONFIG_I2C_VIA is not set -# CONFIG_I2C_VIAPRO is not set - -# -# I2C system bus drivers (mostly embedded / system-on-chip) -# -# CONFIG_I2C_CBUS_GPIO is not set -# CONFIG_I2C_DESIGNWARE_PLATFORM is not set -# CONFIG_I2C_DESIGNWARE_PCI is not set -# CONFIG_I2C_EMEV2 is not set -# CONFIG_I2C_GPIO is not set -CONFIG_I2C_MICROCHIP_CORE=y -# CONFIG_I2C_OCORES is not set -# CONFIG_I2C_PCA_PLATFORM is not set -# CONFIG_I2C_RK3X is not set -# CONFIG_I2C_SIMTEC is not set -# CONFIG_I2C_XILINX is not set - -# -# External I2C/SMBus adapter drivers -# -# CONFIG_I2C_DIOLAN_U2C is not set -# CONFIG_I2C_CP2615 is not set -# CONFIG_I2C_PCI1XXXX is not set -# CONFIG_I2C_ROBOTFUZZ_OSIF is not set -# CONFIG_I2C_TAOS_EVM is not set -# CONFIG_I2C_TINY_USB is not set - -# -# Other I2C/SMBus bus drivers -# -# CONFIG_I2C_VIRTIO is not set -# end of I2C Hardware Bus support - -# CONFIG_I2C_STUB is not set -# CONFIG_I2C_SLAVE is not set -# CONFIG_I2C_DEBUG_CORE is not set -# CONFIG_I2C_DEBUG_ALGO is not set -# CONFIG_I2C_DEBUG_BUS is not set -# end of I2C support - -# CONFIG_I3C is not set -CONFIG_SPI=y -# CONFIG_SPI_DEBUG is not set -CONFIG_SPI_MASTER=y -# CONFIG_SPI_MEM is not set - -# -# SPI Master Controller Drivers -# -# CONFIG_SPI_ALTERA is not set -# CONFIG_SPI_AXI_SPI_ENGINE is not set -# CONFIG_SPI_BITBANG is not set -# CONFIG_SPI_CADENCE is not set -# CONFIG_SPI_DESIGNWARE is not set -# CONFIG_SPI_NXP_FLEXSPI is not set -# CONFIG_SPI_GPIO is not set -# CONFIG_SPI_FSL_SPI is not set -CONFIG_SPI_MICROCHIP_CORE=y -CONFIG_SPI_MICROCHIP_CORE_QSPI=y -# CONFIG_SPI_OC_TINY is not set -# CONFIG_SPI_PXA2XX is not set -# CONFIG_SPI_ROCKCHIP is not set -# CONFIG_SPI_SC18IS602 is not set -CONFIG_SPI_SIFIVE=y -# CONFIG_SPI_MXIC is not set -# CONFIG_SPI_XCOMM is not set -# CONFIG_SPI_XILINX is not set -# CONFIG_SPI_ZYNQMP_GQSPI is not set -# CONFIG_SPI_AMD is not set - -# -# SPI Multiplexer support -# -# CONFIG_SPI_MUX is not set - -# -# SPI Protocol Masters -# -CONFIG_SPI_SPIDEV=m -# CONFIG_SPI_LOOPBACK_TEST is not set -# CONFIG_SPI_TLE62X0 is not set -# CONFIG_SPI_SLAVE is not set -CONFIG_SPI_DYNAMIC=y -# CONFIG_SPMI is not set -# CONFIG_HSI is not set -# CONFIG_PPS is not set - -# -# PTP clock support -# -# CONFIG_PTP_1588_CLOCK is not set -CONFIG_PTP_1588_CLOCK_OPTIONAL=y - -# -# Enable PHYLIB and NETWORK_PHY_TIMESTAMPING to see the additional clocks. -# -# end of PTP clock support - -CONFIG_PINCTRL=y -CONFIG_GENERIC_PINCTRL_GROUPS=y -CONFIG_PINMUX=y -CONFIG_GENERIC_PINMUX_FUNCTIONS=y -CONFIG_PINCONF=y -CONFIG_GENERIC_PINCONF=y -# CONFIG_DEBUG_PINCTRL is not set -# CONFIG_PINCTRL_CY8C95X0 is not set -# CONFIG_PINCTRL_MCP23S08 is not set -# CONFIG_PINCTRL_MICROCHIP_SGPIO is not set -# CONFIG_PINCTRL_OCELOT is not set -# CONFIG_PINCTRL_SINGLE is not set -# CONFIG_PINCTRL_STMFX is not set -# CONFIG_PINCTRL_SX150X is not set - -# -# Renesas pinctrl drivers -# -# end of Renesas pinctrl drivers - -CONFIG_PINCTRL_STARFIVE_JH7100=y -CONFIG_GPIOLIB=y -CONFIG_GPIOLIB_FASTPATH_LIMIT=512 -CONFIG_OF_GPIO=y -CONFIG_GPIOLIB_IRQCHIP=y -# CONFIG_DEBUG_GPIO is not set -CONFIG_GPIO_SYSFS=y -CONFIG_GPIO_CDEV=y -CONFIG_GPIO_CDEV_V1=y -CONFIG_GPIO_GENERIC=y - -# -# Memory mapped GPIO drivers -# -# CONFIG_GPIO_74XX_MMIO is not set -# CONFIG_GPIO_ALTERA is not set -# CONFIG_GPIO_CADENCE is not set -# CONFIG_GPIO_DWAPB is not set -# CONFIG_GPIO_EXAR is not set -# CONFIG_GPIO_FTGPIO010 is not set -# CONFIG_GPIO_GENERIC_PLATFORM is not set -# CONFIG_GPIO_GRGPIO is not set -# CONFIG_GPIO_HLWD is not set -# CONFIG_GPIO_LOGICVC is not set -# CONFIG_GPIO_MB86S7X is not set -CONFIG_GPIO_SIFIVE=y -# CONFIG_GPIO_SYSCON is not set -# CONFIG_GPIO_XILINX is not set -# CONFIG_GPIO_AMD_FCH is not set -# end of Memory mapped GPIO drivers - -# -# I2C GPIO expanders -# -# CONFIG_GPIO_ADNP is not set -# CONFIG_GPIO_GW_PLD is not set -# CONFIG_GPIO_MAX7300 is not set -# CONFIG_GPIO_MAX732X is not set -# CONFIG_GPIO_PCA953X is not set -# CONFIG_GPIO_PCA9570 is not set -# CONFIG_GPIO_PCF857X is not set -# CONFIG_GPIO_TPIC2810 is not set -# end of I2C GPIO expanders - -# -# MFD GPIO expanders -# -# end of MFD GPIO expanders - -# -# PCI GPIO expanders -# -# CONFIG_GPIO_BT8XX is not set -# CONFIG_GPIO_PCI_IDIO_16 is not set -# CONFIG_GPIO_PCIE_IDIO_24 is not set -# CONFIG_GPIO_RDC321X is not set -# end of PCI GPIO expanders - -# -# SPI GPIO expanders -# -# CONFIG_GPIO_74X164 is not set -# CONFIG_GPIO_MAX3191X is not set -# CONFIG_GPIO_MAX7301 is not set -# CONFIG_GPIO_MC33880 is not set -# CONFIG_GPIO_PISOSR is not set -# CONFIG_GPIO_XRA1403 is not set -# end of SPI GPIO expanders - -# -# USB GPIO expanders -# -# end of USB GPIO expanders - -# -# Virtual GPIO drivers -# -# CONFIG_GPIO_AGGREGATOR is not set -# CONFIG_GPIO_MOCKUP is not set -# CONFIG_GPIO_VIRTIO is not set -# CONFIG_GPIO_SIM is not set -# end of Virtual GPIO drivers - -# CONFIG_W1 is not set -CONFIG_POWER_RESET=y -# CONFIG_POWER_RESET_GPIO is not set -# CONFIG_POWER_RESET_GPIO_RESTART is not set -# CONFIG_POWER_RESET_LTC2952 is not set -# CONFIG_POWER_RESET_RESTART is not set -CONFIG_POWER_RESET_SYSCON=y -CONFIG_POWER_RESET_SYSCON_POWEROFF=y -# CONFIG_SYSCON_REBOOT_MODE is not set -# CONFIG_NVMEM_REBOOT_MODE is not set -CONFIG_POWER_SUPPLY=y -# CONFIG_POWER_SUPPLY_DEBUG is not set -CONFIG_POWER_SUPPLY_HWMON=y -# CONFIG_PDA_POWER is not set -# CONFIG_GENERIC_ADC_BATTERY is not set -# CONFIG_IP5XXX_POWER is not set -# CONFIG_TEST_POWER is not set -# CONFIG_CHARGER_ADP5061 is not set -# CONFIG_BATTERY_CW2015 is not set -# CONFIG_BATTERY_DS2780 is not set -# CONFIG_BATTERY_DS2781 is not set -# CONFIG_BATTERY_DS2782 is not set -# CONFIG_BATTERY_SAMSUNG_SDI is not set -# CONFIG_BATTERY_SBS is not set -# CONFIG_CHARGER_SBS is not set -# CONFIG_MANAGER_SBS is not set -# CONFIG_BATTERY_BQ27XXX is not set -# CONFIG_BATTERY_MAX17040 is not set -# CONFIG_BATTERY_MAX17042 is not set -# CONFIG_CHARGER_ISP1704 is not set -# CONFIG_CHARGER_MAX8903 is not set -# CONFIG_CHARGER_LP8727 is not set -# CONFIG_CHARGER_GPIO is not set -# CONFIG_CHARGER_LT3651 is not set -# CONFIG_CHARGER_LTC4162L is not set -# CONFIG_CHARGER_DETECTOR_MAX14656 is not set -# CONFIG_CHARGER_MAX77976 is not set -# CONFIG_CHARGER_BQ2415X is not set -# CONFIG_CHARGER_BQ24190 is not set -# CONFIG_CHARGER_BQ24257 is not set -# CONFIG_CHARGER_BQ24735 is not set -# CONFIG_CHARGER_BQ2515X is not set -# CONFIG_CHARGER_BQ25890 is not set -# CONFIG_CHARGER_BQ25980 is not set -# CONFIG_CHARGER_BQ256XX is not set -# CONFIG_BATTERY_GAUGE_LTC2941 is not set -# CONFIG_BATTERY_GOLDFISH is not set -# CONFIG_BATTERY_RT5033 is not set -# CONFIG_CHARGER_RT9455 is not set -# CONFIG_CHARGER_BD99954 is not set -# CONFIG_BATTERY_UG3105 is not set -CONFIG_HWMON=y -# CONFIG_HWMON_DEBUG_CHIP is not set - -# -# Native drivers -# -# CONFIG_SENSORS_AD7314 is not set -# CONFIG_SENSORS_AD7414 is not set -# CONFIG_SENSORS_AD7418 is not set -# CONFIG_SENSORS_ADM1021 is not set -# CONFIG_SENSORS_ADM1025 is not set -# CONFIG_SENSORS_ADM1026 is not set -# CONFIG_SENSORS_ADM1029 is not set -# CONFIG_SENSORS_ADM1031 is not set -# CONFIG_SENSORS_ADM1177 is not set -# CONFIG_SENSORS_ADM9240 is not set -# CONFIG_SENSORS_ADT7310 is not set -# CONFIG_SENSORS_ADT7410 is not set -# CONFIG_SENSORS_ADT7411 is not set -# CONFIG_SENSORS_ADT7462 is not set -# CONFIG_SENSORS_ADT7470 is not set -# CONFIG_SENSORS_ADT7475 is not set -# CONFIG_SENSORS_AHT10 is not set -# CONFIG_SENSORS_AQUACOMPUTER_D5NEXT is not set -# CONFIG_SENSORS_AS370 is not set -# CONFIG_SENSORS_ASC7621 is not set -# CONFIG_SENSORS_AXI_FAN_CONTROL is not set -# CONFIG_SENSORS_ATXP1 is not set -# CONFIG_SENSORS_CORSAIR_CPRO is not set -# CONFIG_SENSORS_CORSAIR_PSU is not set -# CONFIG_SENSORS_DRIVETEMP is not set -# CONFIG_SENSORS_DS620 is not set -# CONFIG_SENSORS_DS1621 is not set -# CONFIG_SENSORS_I5K_AMB is not set -# CONFIG_SENSORS_F71805F is not set -# CONFIG_SENSORS_F71882FG is not set -# CONFIG_SENSORS_F75375S is not set -# CONFIG_SENSORS_GL518SM is not set -# CONFIG_SENSORS_GL520SM is not set -# CONFIG_SENSORS_G760A is not set -# CONFIG_SENSORS_G762 is not set -# CONFIG_SENSORS_GPIO_FAN is not set -# CONFIG_SENSORS_HIH6130 is not set -# CONFIG_SENSORS_IIO_HWMON is not set -# CONFIG_SENSORS_IT87 is not set -# CONFIG_SENSORS_JC42 is not set -# CONFIG_SENSORS_POWR1220 is not set -# CONFIG_SENSORS_LINEAGE is not set -# CONFIG_SENSORS_LTC2945 is not set -# CONFIG_SENSORS_LTC2947_I2C is not set -# CONFIG_SENSORS_LTC2947_SPI is not set -# CONFIG_SENSORS_LTC2990 is not set -# CONFIG_SENSORS_LTC2992 is not set -# CONFIG_SENSORS_LTC4151 is not set -# CONFIG_SENSORS_LTC4215 is not set -# CONFIG_SENSORS_LTC4222 is not set -# CONFIG_SENSORS_LTC4245 is not set -# CONFIG_SENSORS_LTC4260 is not set -# CONFIG_SENSORS_LTC4261 is not set -# CONFIG_SENSORS_MAX1111 is not set -# CONFIG_SENSORS_MAX127 is not set -# CONFIG_SENSORS_MAX16065 is not set -# CONFIG_SENSORS_MAX1619 is not set -# CONFIG_SENSORS_MAX1668 is not set -# CONFIG_SENSORS_MAX197 is not set -# CONFIG_SENSORS_MAX31722 is not set -# CONFIG_SENSORS_MAX31730 is not set -# CONFIG_SENSORS_MAX31760 is not set -# CONFIG_SENSORS_MAX6620 is not set -# CONFIG_SENSORS_MAX6621 is not set -# CONFIG_SENSORS_MAX6639 is not set -# CONFIG_SENSORS_MAX6642 is not set -# CONFIG_SENSORS_MAX6650 is not set -# CONFIG_SENSORS_MAX6697 is not set -# CONFIG_SENSORS_MAX31790 is not set -# CONFIG_SENSORS_MCP3021 is not set -# CONFIG_SENSORS_TC654 is not set -# CONFIG_SENSORS_TPS23861 is not set -# CONFIG_SENSORS_MR75203 is not set -# CONFIG_SENSORS_ADCXX is not set -# CONFIG_SENSORS_LM63 is not set -# CONFIG_SENSORS_LM70 is not set -# CONFIG_SENSORS_LM73 is not set -# CONFIG_SENSORS_LM75 is not set -# CONFIG_SENSORS_LM77 is not set -# CONFIG_SENSORS_LM78 is not set -# CONFIG_SENSORS_LM80 is not set -# CONFIG_SENSORS_LM83 is not set -# CONFIG_SENSORS_LM85 is not set -# CONFIG_SENSORS_LM87 is not set -# CONFIG_SENSORS_LM90 is not set -# CONFIG_SENSORS_LM92 is not set -# CONFIG_SENSORS_LM93 is not set -# CONFIG_SENSORS_LM95234 is not set -# CONFIG_SENSORS_LM95241 is not set -# CONFIG_SENSORS_LM95245 is not set -# CONFIG_SENSORS_PC87360 is not set -# CONFIG_SENSORS_PC87427 is not set -# CONFIG_SENSORS_NTC_THERMISTOR is not set -# CONFIG_SENSORS_NCT6683 is not set -# CONFIG_SENSORS_NCT6775_I2C is not set -# CONFIG_SENSORS_NCT7802 is not set -# CONFIG_SENSORS_NPCM7XX is not set -# CONFIG_SENSORS_NZXT_KRAKEN2 is not set -# CONFIG_SENSORS_NZXT_SMART2 is not set -# CONFIG_SENSORS_PCF8591 is not set -# CONFIG_PMBUS is not set -# CONFIG_SENSORS_SBTSI is not set -# CONFIG_SENSORS_SBRMI is not set -# CONFIG_SENSORS_SHT15 is not set -# CONFIG_SENSORS_SHT21 is not set -# CONFIG_SENSORS_SHT3x is not set -# CONFIG_SENSORS_SHT4x is not set -# CONFIG_SENSORS_SHTC1 is not set -# CONFIG_SENSORS_SIS5595 is not set -# CONFIG_SENSORS_DME1737 is not set -# CONFIG_SENSORS_EMC1403 is not set -# CONFIG_SENSORS_EMC2103 is not set -# CONFIG_SENSORS_EMC2305 is not set -# CONFIG_SENSORS_EMC6W201 is not set -# CONFIG_SENSORS_SMSC47M1 is not set -# CONFIG_SENSORS_SMSC47M192 is not set -# CONFIG_SENSORS_SMSC47B397 is not set -# CONFIG_SENSORS_STTS751 is not set -# CONFIG_SENSORS_SMM665 is not set -# CONFIG_SENSORS_ADC128D818 is not set -# CONFIG_SENSORS_ADS7828 is not set -# CONFIG_SENSORS_ADS7871 is not set -# CONFIG_SENSORS_AMC6821 is not set -# CONFIG_SENSORS_INA209 is not set -# CONFIG_SENSORS_INA2XX is not set -# CONFIG_SENSORS_INA238 is not set -# CONFIG_SENSORS_INA3221 is not set -# CONFIG_SENSORS_TC74 is not set -# CONFIG_SENSORS_THMC50 is not set -# CONFIG_SENSORS_TMP102 is not set -# CONFIG_SENSORS_TMP103 is not set -# CONFIG_SENSORS_TMP108 is not set -# CONFIG_SENSORS_TMP401 is not set -# CONFIG_SENSORS_TMP421 is not set -# CONFIG_SENSORS_TMP464 is not set -# CONFIG_SENSORS_TMP513 is not set -# CONFIG_SENSORS_VIA686A is not set -# CONFIG_SENSORS_VT1211 is not set -# CONFIG_SENSORS_VT8231 is not set -# CONFIG_SENSORS_W83773G is not set -# CONFIG_SENSORS_W83781D is not set -# CONFIG_SENSORS_W83791D is not set -# CONFIG_SENSORS_W83792D is not set -# CONFIG_SENSORS_W83793 is not set -# CONFIG_SENSORS_W83795 is not set -# CONFIG_SENSORS_W83L785TS is not set -# CONFIG_SENSORS_W83L786NG is not set -# CONFIG_SENSORS_W83627HF is not set -# CONFIG_SENSORS_W83627EHF is not set -# CONFIG_THERMAL is not set -# CONFIG_WATCHDOG is not set -CONFIG_SSB_POSSIBLE=y -# CONFIG_SSB is not set -CONFIG_BCMA_POSSIBLE=y -# CONFIG_BCMA is not set - -# -# Multifunction device drivers -# -# CONFIG_MFD_ACT8945A is not set -# CONFIG_MFD_AS3711 is not set -# CONFIG_MFD_AS3722 is not set -# CONFIG_PMIC_ADP5520 is not set -# CONFIG_MFD_AAT2870_CORE is not set -# CONFIG_MFD_ATMEL_FLEXCOM is not set -# CONFIG_MFD_ATMEL_HLCDC is not set -# CONFIG_MFD_BCM590XX is not set -# CONFIG_MFD_BD9571MWV is not set -# CONFIG_MFD_AXP20X_I2C is not set -# CONFIG_MFD_MADERA is not set -# CONFIG_PMIC_DA903X is not set -# CONFIG_MFD_DA9052_SPI is not set -# CONFIG_MFD_DA9052_I2C is not set -# CONFIG_MFD_DA9055 is not set -# CONFIG_MFD_DA9062 is not set -# CONFIG_MFD_DA9063 is not set -# CONFIG_MFD_DA9150 is not set -# CONFIG_MFD_DLN2 is not set -# CONFIG_MFD_GATEWORKS_GSC is not set -# CONFIG_MFD_MC13XXX_SPI is not set -# CONFIG_MFD_MC13XXX_I2C is not set -# CONFIG_MFD_MP2629 is not set -# CONFIG_MFD_HI6421_PMIC is not set -# CONFIG_HTC_PASIC3 is not set -# CONFIG_HTC_I2CPLD is not set -# CONFIG_LPC_ICH is not set -# CONFIG_LPC_SCH is not set -# CONFIG_MFD_IQS62X is not set -# CONFIG_MFD_JANZ_CMODIO is not set -# CONFIG_MFD_KEMPLD is not set -# CONFIG_MFD_88PM800 is not set -# CONFIG_MFD_88PM805 is not set -# CONFIG_MFD_88PM860X is not set -# CONFIG_MFD_MAX14577 is not set -# CONFIG_MFD_MAX77620 is not set -# CONFIG_MFD_MAX77650 is not set -# CONFIG_MFD_MAX77686 is not set -# CONFIG_MFD_MAX77693 is not set -# CONFIG_MFD_MAX77714 is not set -# CONFIG_MFD_MAX77843 is not set -# CONFIG_MFD_MAX8907 is not set -# CONFIG_MFD_MAX8925 is not set -# CONFIG_MFD_MAX8997 is not set -# CONFIG_MFD_MAX8998 is not set -# CONFIG_MFD_MT6360 is not set -# CONFIG_MFD_MT6370 is not set -# CONFIG_MFD_MT6397 is not set -# CONFIG_MFD_MENF21BMC is not set -# CONFIG_MFD_OCELOT is not set -# CONFIG_EZX_PCAP is not set -# CONFIG_MFD_CPCAP is not set -# CONFIG_MFD_VIPERBOARD is not set -# CONFIG_MFD_NTXEC is not set -# CONFIG_MFD_RETU is not set -# CONFIG_MFD_PCF50633 is not set -# CONFIG_MFD_SY7636A is not set -# CONFIG_MFD_RDC321X is not set -# CONFIG_MFD_RT4831 is not set -# CONFIG_MFD_RT5033 is not set -# CONFIG_MFD_RT5120 is not set -# CONFIG_MFD_RC5T583 is not set -# CONFIG_MFD_RK808 is not set -# CONFIG_MFD_RN5T618 is not set -# CONFIG_MFD_SEC_CORE is not set -# CONFIG_MFD_SI476X_CORE is not set -# CONFIG_MFD_SM501 is not set -# CONFIG_MFD_SKY81452 is not set -# CONFIG_MFD_STMPE is not set -CONFIG_MFD_SYSCON=y -# CONFIG_MFD_TI_AM335X_TSCADC is not set -# CONFIG_MFD_LP3943 is not set -# CONFIG_MFD_LP8788 is not set -# CONFIG_MFD_TI_LMU is not set -# CONFIG_MFD_PALMAS is not set -# CONFIG_TPS6105X is not set -# CONFIG_TPS65010 is not set -# CONFIG_TPS6507X is not set -# CONFIG_MFD_TPS65086 is not set -# CONFIG_MFD_TPS65090 is not set -# CONFIG_MFD_TPS65217 is not set -# CONFIG_MFD_TI_LP873X is not set -# CONFIG_MFD_TI_LP87565 is not set -# CONFIG_MFD_TPS65218 is not set -# CONFIG_MFD_TPS6586X is not set -# CONFIG_MFD_TPS65910 is not set -# CONFIG_MFD_TPS65912_I2C is not set -# CONFIG_MFD_TPS65912_SPI is not set -# CONFIG_TWL4030_CORE is not set -# CONFIG_TWL6040_CORE is not set -# CONFIG_MFD_WL1273_CORE is not set -# CONFIG_MFD_LM3533 is not set -# CONFIG_MFD_TC3589X is not set -# CONFIG_MFD_TQMX86 is not set -# CONFIG_MFD_VX855 is not set -# CONFIG_MFD_LOCHNAGAR is not set -# CONFIG_MFD_ARIZONA_I2C is not set -# CONFIG_MFD_ARIZONA_SPI is not set -# CONFIG_MFD_WM8400 is not set -# CONFIG_MFD_WM831X_I2C is not set -# CONFIG_MFD_WM831X_SPI is not set -# CONFIG_MFD_WM8350_I2C is not set -# CONFIG_MFD_WM8994 is not set -# CONFIG_MFD_ROHM_BD718XX is not set -# CONFIG_MFD_ROHM_BD71828 is not set -# CONFIG_MFD_ROHM_BD957XMUF is not set -# CONFIG_MFD_STPMIC1 is not set -# CONFIG_MFD_STMFX is not set -# CONFIG_MFD_ATC260X_I2C is not set -# CONFIG_MFD_QCOM_PM8008 is not set -# CONFIG_MFD_INTEL_M10_BMC is not set -# CONFIG_MFD_RSMU_I2C is not set -# CONFIG_MFD_RSMU_SPI is not set -# end of Multifunction device drivers - -# CONFIG_REGULATOR is not set -# CONFIG_RC_CORE is not set - -# -# CEC support -# -# CONFIG_MEDIA_CEC_SUPPORT is not set -# end of CEC support - -CONFIG_MEDIA_SUPPORT=m -CONFIG_MEDIA_SUPPORT_FILTER=y -CONFIG_MEDIA_SUBDRV_AUTOSELECT=y - -# -# Media device types -# -CONFIG_MEDIA_CAMERA_SUPPORT=y -# CONFIG_MEDIA_ANALOG_TV_SUPPORT is not set -# CONFIG_MEDIA_DIGITAL_TV_SUPPORT is not set -# CONFIG_MEDIA_RADIO_SUPPORT is not set -# CONFIG_MEDIA_SDR_SUPPORT is not set -# CONFIG_MEDIA_PLATFORM_SUPPORT is not set -# CONFIG_MEDIA_TEST_SUPPORT is not set -# end of Media device types - -CONFIG_VIDEO_DEV=m -CONFIG_MEDIA_CONTROLLER=y - -# -# Video4Linux options -# -CONFIG_VIDEO_V4L2_I2C=y -CONFIG_VIDEO_V4L2_SUBDEV_API=y -# CONFIG_VIDEO_ADV_DEBUG is not set -# CONFIG_VIDEO_FIXED_MINOR_RANGES is not set -CONFIG_V4L2_FWNODE=m -CONFIG_V4L2_ASYNC=m -# end of Video4Linux options - -# -# Media controller options -# -# end of Media controller options - -# -# Media drivers -# - -# -# Drivers filtered as selected at 'Filter media drivers' -# - -# -# Media drivers -# -# CONFIG_MEDIA_USB_SUPPORT is not set -# CONFIG_MEDIA_PCI_SUPPORT is not set -CONFIG_VIDEOBUF2_CORE=m -CONFIG_VIDEOBUF2_V4L2=m -CONFIG_VIDEOBUF2_MEMOPS=m -CONFIG_VIDEOBUF2_VMALLOC=m -CONFIG_VIDEOBUF2_DMA_SG=m -# end of Media drivers - -# -# Media ancillary drivers -# - -# -# Camera sensor devices -# -# CONFIG_VIDEO_AR0521 is not set -# CONFIG_VIDEO_HI556 is not set -# CONFIG_VIDEO_HI846 is not set -# CONFIG_VIDEO_HI847 is not set -# CONFIG_VIDEO_IMX208 is not set -# CONFIG_VIDEO_IMX214 is not set -CONFIG_VIDEO_IMX219=m -# CONFIG_VIDEO_IMX258 is not set -# CONFIG_VIDEO_IMX274 is not set -# CONFIG_VIDEO_IMX290 is not set -# CONFIG_VIDEO_IMX319 is not set -# CONFIG_VIDEO_IMX334 is not set -# CONFIG_VIDEO_IMX335 is not set -# CONFIG_VIDEO_IMX355 is not set -# CONFIG_VIDEO_IMX412 is not set -# CONFIG_VIDEO_MT9M001 is not set -# CONFIG_VIDEO_MT9M032 is not set -# CONFIG_VIDEO_MT9M111 is not set -# CONFIG_VIDEO_MT9P031 is not set -# CONFIG_VIDEO_MT9T001 is not set -# CONFIG_VIDEO_MT9T112 is not set -# CONFIG_VIDEO_MT9V011 is not set -# CONFIG_VIDEO_MT9V032 is not set -# CONFIG_VIDEO_MT9V111 is not set -# CONFIG_VIDEO_NOON010PC30 is not set -# CONFIG_VIDEO_OG01A1B is not set -# CONFIG_VIDEO_OV02A10 is not set -# CONFIG_VIDEO_OV08D10 is not set -# CONFIG_VIDEO_OV13858 is not set -# CONFIG_VIDEO_OV13B10 is not set -# CONFIG_VIDEO_OV2640 is not set -# CONFIG_VIDEO_OV2659 is not set -# CONFIG_VIDEO_OV2680 is not set -# CONFIG_VIDEO_OV2685 is not set -# CONFIG_VIDEO_OV5640 is not set -# CONFIG_VIDEO_OV5645 is not set -# CONFIG_VIDEO_OV5647 is not set -# CONFIG_VIDEO_OV5648 is not set -# CONFIG_VIDEO_OV5670 is not set -# CONFIG_VIDEO_OV5675 is not set -# CONFIG_VIDEO_OV5693 is not set -# CONFIG_VIDEO_OV5695 is not set -# CONFIG_VIDEO_OV6650 is not set -# CONFIG_VIDEO_OV7251 is not set -# CONFIG_VIDEO_OV7640 is not set -# CONFIG_VIDEO_OV7670 is not set -# CONFIG_VIDEO_OV772X is not set -# CONFIG_VIDEO_OV7740 is not set -# CONFIG_VIDEO_OV8856 is not set -# CONFIG_VIDEO_OV8865 is not set -# CONFIG_VIDEO_OV9282 is not set -# CONFIG_VIDEO_OV9640 is not set -# CONFIG_VIDEO_OV9650 is not set -# CONFIG_VIDEO_RDACM20 is not set -# CONFIG_VIDEO_RDACM21 is not set -# CONFIG_VIDEO_RJ54N1 is not set -# CONFIG_VIDEO_S5C73M3 is not set -# CONFIG_VIDEO_S5K4ECGX is not set -# CONFIG_VIDEO_S5K5BAF is not set -# CONFIG_VIDEO_S5K6A3 is not set -# CONFIG_VIDEO_S5K6AA is not set -# CONFIG_VIDEO_SR030PC30 is not set -# CONFIG_VIDEO_VS6624 is not set -# CONFIG_VIDEO_CCS is not set -# CONFIG_VIDEO_ET8EK8 is not set -# CONFIG_VIDEO_M5MOLS is not set -# end of Camera sensor devices - -# -# Lens drivers -# -# CONFIG_VIDEO_AD5820 is not set -# CONFIG_VIDEO_AK7375 is not set -# CONFIG_VIDEO_DW9714 is not set -# CONFIG_VIDEO_DW9768 is not set -# CONFIG_VIDEO_DW9807_VCM is not set -# end of Lens drivers - -# -# Flash devices -# -# CONFIG_VIDEO_ADP1653 is not set -# CONFIG_VIDEO_LM3560 is not set -# CONFIG_VIDEO_LM3646 is not set -# end of Flash devices - -# -# Audio decoders, processors and mixers -# -# CONFIG_VIDEO_CS3308 is not set -# CONFIG_VIDEO_CS5345 is not set -# CONFIG_VIDEO_CS53L32A is not set -# CONFIG_VIDEO_MSP3400 is not set -# CONFIG_VIDEO_SONY_BTF_MPX is not set -# CONFIG_VIDEO_TDA7432 is not set -# CONFIG_VIDEO_TDA9840 is not set -# CONFIG_VIDEO_TEA6415C is not set -# CONFIG_VIDEO_TEA6420 is not set -# CONFIG_VIDEO_TLV320AIC23B is not set -# CONFIG_VIDEO_TVAUDIO is not set -# CONFIG_VIDEO_UDA1342 is not set -# CONFIG_VIDEO_VP27SMPX is not set -# CONFIG_VIDEO_WM8739 is not set -# CONFIG_VIDEO_WM8775 is not set -# end of Audio decoders, processors and mixers - -# -# RDS decoders -# -# CONFIG_VIDEO_SAA6588 is not set -# end of RDS decoders - -# -# Video decoders -# -# CONFIG_VIDEO_ADV7180 is not set -# CONFIG_VIDEO_ADV7183 is not set -# CONFIG_VIDEO_ADV748X is not set -# CONFIG_VIDEO_ADV7604 is not set -# CONFIG_VIDEO_ADV7842 is not set -# CONFIG_VIDEO_BT819 is not set -# CONFIG_VIDEO_BT856 is not set -# CONFIG_VIDEO_BT866 is not set -# CONFIG_VIDEO_ISL7998X is not set -# CONFIG_VIDEO_KS0127 is not set -# CONFIG_VIDEO_MAX9286 is not set -# CONFIG_VIDEO_ML86V7667 is not set -# CONFIG_VIDEO_SAA7110 is not set -# CONFIG_VIDEO_SAA711X is not set -# CONFIG_VIDEO_TC358743 is not set -# CONFIG_VIDEO_TVP514X is not set -# CONFIG_VIDEO_TVP5150 is not set -# CONFIG_VIDEO_TVP7002 is not set -# CONFIG_VIDEO_TW2804 is not set -# CONFIG_VIDEO_TW9903 is not set -# CONFIG_VIDEO_TW9906 is not set -# CONFIG_VIDEO_TW9910 is not set -# CONFIG_VIDEO_VPX3220 is not set - -# -# Video and audio decoders -# -# CONFIG_VIDEO_SAA717X is not set -# CONFIG_VIDEO_CX25840 is not set -# end of Video decoders - -# -# Video encoders -# -# CONFIG_VIDEO_AD9389B is not set -# CONFIG_VIDEO_ADV7170 is not set -# CONFIG_VIDEO_ADV7175 is not set -# CONFIG_VIDEO_ADV7343 is not set -# CONFIG_VIDEO_ADV7393 is not set -# CONFIG_VIDEO_ADV7511 is not set -# CONFIG_VIDEO_AK881X is not set -# CONFIG_VIDEO_SAA7127 is not set -# CONFIG_VIDEO_SAA7185 is not set -# CONFIG_VIDEO_THS8200 is not set -# end of Video encoders - -# -# Video improvement chips -# -# CONFIG_VIDEO_UPD64031A is not set -# CONFIG_VIDEO_UPD64083 is not set -# end of Video improvement chips - -# -# Audio/Video compression chips -# -# CONFIG_VIDEO_SAA6752HS is not set -# end of Audio/Video compression chips - -# -# SDR tuner chips -# -# end of SDR tuner chips - -# -# Miscellaneous helper chips -# -# CONFIG_VIDEO_I2C is not set -# CONFIG_VIDEO_M52790 is not set -# CONFIG_VIDEO_ST_MIPID02 is not set -# CONFIG_VIDEO_THS7303 is not set -# end of Miscellaneous helper chips - -# -# Media SPI Adapters -# -# CONFIG_VIDEO_GS1662 is not set -# end of Media SPI Adapters -# end of Media ancillary drivers - -# -# Graphics support -# -CONFIG_APERTURE_HELPERS=y -# CONFIG_DRM is not set -# CONFIG_DRM_DEBUG_MODESET_LOCK is not set - -# -# ARM devices -# -# end of ARM devices - -# -# Frame buffer Devices -# -CONFIG_FB_CMDLINE=y -CONFIG_FB_NOTIFY=y -CONFIG_FB=y -# CONFIG_FIRMWARE_EDID is not set -# CONFIG_FB_FOREIGN_ENDIAN is not set -# CONFIG_FB_MODE_HELPERS is not set -# CONFIG_FB_TILEBLITTING is not set - -# -# Frame buffer hardware drivers -# -# CONFIG_FB_CIRRUS is not set -# CONFIG_FB_PM2 is not set -# CONFIG_FB_CYBER2000 is not set -# CONFIG_FB_ASILIANT is not set -# CONFIG_FB_IMSTT is not set -# CONFIG_FB_EFI is not set -# CONFIG_FB_OPENCORES is not set -# CONFIG_FB_S1D13XXX is not set -# CONFIG_FB_NVIDIA is not set -# CONFIG_FB_RIVA is not set -# CONFIG_FB_I740 is not set -# CONFIG_FB_MATROX is not set -# CONFIG_FB_RADEON is not set -# CONFIG_FB_ATY128 is not set -# CONFIG_FB_ATY is not set -# CONFIG_FB_S3 is not set -# CONFIG_FB_SAVAGE is not set -# CONFIG_FB_SIS is not set -# CONFIG_FB_NEOMAGIC is not set -# CONFIG_FB_KYRO is not set -# CONFIG_FB_3DFX is not set -# CONFIG_FB_VOODOO1 is not set -# CONFIG_FB_VT8623 is not set -# CONFIG_FB_TRIDENT is not set -# CONFIG_FB_ARK is not set -# CONFIG_FB_PM3 is not set -# CONFIG_FB_CARMINE is not set -# CONFIG_FB_SMSCUFX is not set -# CONFIG_FB_UDL is not set -# CONFIG_FB_IBM_GXT4500 is not set -# CONFIG_FB_GOLDFISH is not set -# CONFIG_FB_VIRTUAL is not set -# CONFIG_FB_METRONOME is not set -# CONFIG_FB_MB862XX is not set -# CONFIG_FB_SIMPLE is not set -# CONFIG_FB_SSD1307 is not set -# CONFIG_FB_SM712 is not set -# end of Frame buffer Devices - -# -# Backlight & LCD device support -# -# CONFIG_LCD_CLASS_DEVICE is not set -CONFIG_BACKLIGHT_CLASS_DEVICE=m -# CONFIG_BACKLIGHT_KTD253 is not set -# CONFIG_BACKLIGHT_QCOM_WLED is not set -# CONFIG_BACKLIGHT_ADP8860 is not set -# CONFIG_BACKLIGHT_ADP8870 is not set -# CONFIG_BACKLIGHT_LM3639 is not set -# CONFIG_BACKLIGHT_GPIO is not set -# CONFIG_BACKLIGHT_LV5207LP is not set -# CONFIG_BACKLIGHT_BD6107 is not set -# CONFIG_BACKLIGHT_ARCXCNN is not set -# end of Backlight & LCD device support - -# -# Console display driver support -# -CONFIG_VGA_CONSOLE=y -CONFIG_DUMMY_CONSOLE=y -CONFIG_DUMMY_CONSOLE_COLUMNS=80 -CONFIG_DUMMY_CONSOLE_ROWS=25 -CONFIG_FRAMEBUFFER_CONSOLE=y -# CONFIG_FRAMEBUFFER_CONSOLE_LEGACY_ACCELERATION is not set -CONFIG_FRAMEBUFFER_CONSOLE_DETECT_PRIMARY=y -# CONFIG_FRAMEBUFFER_CONSOLE_ROTATION is not set -# CONFIG_FRAMEBUFFER_CONSOLE_DEFERRED_TAKEOVER is not set -# end of Console display driver support - -# CONFIG_LOGO is not set -# end of Graphics support - -# CONFIG_SOUND is not set - -# -# HID support -# -CONFIG_HID=y -# CONFIG_HID_BATTERY_STRENGTH is not set -# CONFIG_HIDRAW is not set -# CONFIG_UHID is not set -CONFIG_HID_GENERIC=y - -# -# Special HID drivers -# -# CONFIG_HID_A4TECH is not set -# CONFIG_HID_ACCUTOUCH is not set -# CONFIG_HID_ACRUX is not set -# CONFIG_HID_APPLEIR is not set -# CONFIG_HID_AUREAL is not set -# CONFIG_HID_BELKIN is not set -# CONFIG_HID_BETOP_FF is not set -# CONFIG_HID_CHERRY is not set -# CONFIG_HID_CHICONY is not set -# CONFIG_HID_COUGAR is not set -# CONFIG_HID_MACALLY is not set -# CONFIG_HID_CMEDIA is not set -# CONFIG_HID_CREATIVE_SB0540 is not set -# CONFIG_HID_CYPRESS is not set -# CONFIG_HID_DRAGONRISE is not set -# CONFIG_HID_EMS_FF is not set -# CONFIG_HID_ELECOM is not set -# CONFIG_HID_ELO is not set -# CONFIG_HID_EZKEY is not set -# CONFIG_HID_GEMBIRD is not set -# CONFIG_HID_GFRM is not set -# CONFIG_HID_GLORIOUS is not set -# CONFIG_HID_HOLTEK is not set -# CONFIG_HID_VIVALDI is not set -# CONFIG_HID_KEYTOUCH is not set -# CONFIG_HID_KYE is not set -# CONFIG_HID_UCLOGIC is not set -# CONFIG_HID_WALTOP is not set -# CONFIG_HID_VIEWSONIC is not set -# CONFIG_HID_VRC2 is not set -# CONFIG_HID_XIAOMI is not set -# CONFIG_HID_GYRATION is not set -# CONFIG_HID_ICADE is not set -# CONFIG_HID_ITE is not set -# CONFIG_HID_JABRA is not set -# CONFIG_HID_TWINHAN is not set -# CONFIG_HID_KENSINGTON is not set -# CONFIG_HID_LCPOWER is not set -# CONFIG_HID_LENOVO is not set -# CONFIG_HID_LETSKETCH is not set -# CONFIG_HID_MAGICMOUSE is not set -# CONFIG_HID_MALTRON is not set -# CONFIG_HID_MAYFLASH is not set -# CONFIG_HID_MEGAWORLD_FF is not set -# CONFIG_HID_REDRAGON is not set -# CONFIG_HID_MICROSOFT is not set -# CONFIG_HID_MONTEREY is not set -# CONFIG_HID_MULTITOUCH is not set -# CONFIG_HID_NTI is not set -# CONFIG_HID_NTRIG is not set -# CONFIG_HID_ORTEK is not set -# CONFIG_HID_PANTHERLORD is not set -# CONFIG_HID_PENMOUNT is not set -# CONFIG_HID_PETALYNX is not set -# CONFIG_HID_PICOLCD is not set -# CONFIG_HID_PLANTRONICS is not set -# CONFIG_HID_PXRC is not set -# CONFIG_HID_RAZER is not set -# CONFIG_HID_PRIMAX is not set -# CONFIG_HID_RETRODE is not set -# CONFIG_HID_ROCCAT is not set -# CONFIG_HID_SAITEK is not set -# CONFIG_HID_SAMSUNG is not set -# CONFIG_HID_SEMITEK is not set -# CONFIG_HID_SIGMAMICRO is not set -# CONFIG_HID_SPEEDLINK is not set -# CONFIG_HID_STEAM is not set -# CONFIG_HID_STEELSERIES is not set -# CONFIG_HID_SUNPLUS is not set -# CONFIG_HID_RMI is not set -# CONFIG_HID_GREENASIA is not set -# CONFIG_HID_SMARTJOYPLUS is not set -# CONFIG_HID_TIVO is not set -# CONFIG_HID_TOPSEED is not set -# CONFIG_HID_TOPRE is not set -# CONFIG_HID_THRUSTMASTER is not set -# CONFIG_HID_UDRAW_PS3 is not set -# CONFIG_HID_WACOM is not set -# CONFIG_HID_XINMO is not set -# CONFIG_HID_ZEROPLUS is not set -# CONFIG_HID_ZYDACRON is not set -# CONFIG_HID_SENSOR_HUB is not set -# CONFIG_HID_ALPS is not set -# CONFIG_HID_MCP2221 is not set -# end of Special HID drivers - -# -# USB HID support -# -CONFIG_USB_HID=y -# CONFIG_HID_PID is not set -# CONFIG_USB_HIDDEV is not set -# end of USB HID support - -# -# I2C HID support -# -# CONFIG_I2C_HID_OF is not set -# CONFIG_I2C_HID_OF_ELAN is not set -# CONFIG_I2C_HID_OF_GOODIX is not set -# end of I2C HID support -# end of HID support - -CONFIG_USB_OHCI_LITTLE_ENDIAN=y -CONFIG_USB_SUPPORT=y -CONFIG_USB_COMMON=y -# CONFIG_USB_ULPI_BUS is not set -# CONFIG_USB_CONN_GPIO is not set -CONFIG_USB_ARCH_HAS_HCD=y -CONFIG_USB=y -CONFIG_USB_PCI=y -# CONFIG_USB_ANNOUNCE_NEW_DEVICES is not set - -# -# Miscellaneous USB options -# -CONFIG_USB_DEFAULT_PERSIST=y -# CONFIG_USB_FEW_INIT_RETRIES is not set -# CONFIG_USB_DYNAMIC_MINORS is not set -# CONFIG_USB_OTG is not set -# CONFIG_USB_OTG_PRODUCTLIST is not set -# CONFIG_USB_OTG_DISABLE_EXTERNAL_HUB is not set -CONFIG_USB_AUTOSUSPEND_DELAY=2 -# CONFIG_USB_MON is not set - -# -# USB Host Controller Drivers -# -# CONFIG_USB_C67X00_HCD is not set -CONFIG_USB_XHCI_HCD=y -# CONFIG_USB_XHCI_DBGCAP is not set -CONFIG_USB_XHCI_PCI=y -# CONFIG_USB_XHCI_PCI_RENESAS is not set -CONFIG_USB_XHCI_PLATFORM=y -CONFIG_USB_EHCI_HCD=y -# CONFIG_USB_EHCI_ROOT_HUB_TT is not set -CONFIG_USB_EHCI_TT_NEWSCHED=y -CONFIG_USB_EHCI_PCI=y -# CONFIG_USB_EHCI_FSL is not set -CONFIG_USB_EHCI_HCD_PLATFORM=y -# CONFIG_USB_OXU210HP_HCD is not set -# CONFIG_USB_ISP116X_HCD is not set -# CONFIG_USB_FOTG210_HCD is not set -# CONFIG_USB_MAX3421_HCD is not set -CONFIG_USB_OHCI_HCD=y -CONFIG_USB_OHCI_HCD_PCI=y -CONFIG_USB_OHCI_HCD_PLATFORM=y -# CONFIG_USB_UHCI_HCD is not set -# CONFIG_USB_SL811_HCD is not set -# CONFIG_USB_R8A66597_HCD is not set -# CONFIG_USB_HCD_TEST_MODE is not set - -# -# USB Device Class drivers -# -# CONFIG_USB_ACM is not set -# CONFIG_USB_PRINTER is not set -# CONFIG_USB_WDM is not set -# CONFIG_USB_TMC is not set - -# -# NOTE: USB_STORAGE depends on SCSI but BLK_DEV_SD may -# - -# -# also be needed; see USB_STORAGE Help for more info -# -CONFIG_USB_STORAGE=y -# CONFIG_USB_STORAGE_DEBUG is not set -# CONFIG_USB_STORAGE_REALTEK is not set -# CONFIG_USB_STORAGE_DATAFAB is not set -# CONFIG_USB_STORAGE_FREECOM is not set -# CONFIG_USB_STORAGE_ISD200 is not set -# CONFIG_USB_STORAGE_USBAT is not set -# CONFIG_USB_STORAGE_SDDR09 is not set -# CONFIG_USB_STORAGE_SDDR55 is not set -# CONFIG_USB_STORAGE_JUMPSHOT is not set -# CONFIG_USB_STORAGE_ALAUDA is not set -# CONFIG_USB_STORAGE_ONETOUCH is not set -# CONFIG_USB_STORAGE_KARMA is not set -# CONFIG_USB_STORAGE_CYPRESS_ATACB is not set -# CONFIG_USB_STORAGE_ENE_UB6250 is not set -CONFIG_USB_UAS=y - -# -# USB Imaging devices -# -# CONFIG_USB_MDC800 is not set -# CONFIG_USB_MICROTEK is not set -# CONFIG_USBIP_CORE is not set -# CONFIG_USB_CDNS_SUPPORT is not set -CONFIG_USB_MUSB_HDRC=y -# CONFIG_USB_MUSB_HOST is not set -# CONFIG_USB_MUSB_GADGET is not set -CONFIG_USB_MUSB_DUAL_ROLE=y - -# -# Platform Glue Layer -# -CONFIG_USB_MUSB_POLARFIRE_SOC=y - -# -# MUSB DMA mode -# -# CONFIG_MUSB_PIO_ONLY is not set -# CONFIG_USB_INVENTRA_DMA is not set -# CONFIG_USB_DWC3 is not set -# CONFIG_USB_DWC2 is not set -# CONFIG_USB_CHIPIDEA is not set -# CONFIG_USB_ISP1760 is not set - -# -# USB port drivers -# -# CONFIG_USB_SERIAL is not set - -# -# USB Miscellaneous drivers -# -# CONFIG_USB_EMI62 is not set -# CONFIG_USB_EMI26 is not set -# CONFIG_USB_ADUTUX is not set -# CONFIG_USB_SEVSEG is not set -# CONFIG_USB_LEGOTOWER is not set -# CONFIG_USB_LCD is not set -# CONFIG_USB_CYPRESS_CY7C63 is not set -# CONFIG_USB_CYTHERM is not set -# CONFIG_USB_IDMOUSE is not set -# CONFIG_USB_FTDI_ELAN is not set -# CONFIG_USB_APPLEDISPLAY is not set -# CONFIG_APPLE_MFI_FASTCHARGE is not set -# CONFIG_USB_SISUSBVGA is not set -# CONFIG_USB_LD is not set -# CONFIG_USB_TRANCEVIBRATOR is not set -# CONFIG_USB_IOWARRIOR is not set -# CONFIG_USB_TEST is not set -# CONFIG_USB_EHSET_TEST_FIXTURE is not set -# CONFIG_USB_ISIGHTFW is not set -# CONFIG_USB_YUREX is not set -# CONFIG_USB_EZUSB_FX2 is not set -# CONFIG_USB_HUB_USB251XB is not set -# CONFIG_USB_HSIC_USB3503 is not set -# CONFIG_USB_HSIC_USB4604 is not set -# CONFIG_USB_LINK_LAYER_TEST is not set -# CONFIG_USB_CHAOSKEY is not set -# CONFIG_USB_ONBOARD_HUB is not set - -# -# USB Physical Layer drivers -# -CONFIG_USB_PHY=y -CONFIG_NOP_USB_XCEIV=y -# CONFIG_USB_GPIO_VBUS is not set -# CONFIG_USB_ISP1301 is not set -# end of USB Physical Layer drivers - -CONFIG_USB_GADGET=y -# CONFIG_USB_GADGET_DEBUG is not set -# CONFIG_USB_GADGET_DEBUG_FILES is not set -# CONFIG_USB_GADGET_DEBUG_FS is not set -CONFIG_USB_GADGET_VBUS_DRAW=2 -CONFIG_USB_GADGET_STORAGE_NUM_BUFFERS=2 -# CONFIG_U_SERIAL_CONSOLE is not set - -# -# USB Peripheral Controller -# -# CONFIG_USB_FOTG210_UDC is not set -# CONFIG_USB_GR_UDC is not set -# CONFIG_USB_R8A66597 is not set -# CONFIG_USB_PXA27X is not set -# CONFIG_USB_MV_UDC is not set -# CONFIG_USB_MV_U3D is not set -# CONFIG_USB_SNP_UDC_PLAT is not set -# CONFIG_USB_M66592 is not set -# CONFIG_USB_BDC_UDC is not set -# CONFIG_USB_AMD5536UDC is not set -# CONFIG_USB_NET2272 is not set -# CONFIG_USB_NET2280 is not set -# CONFIG_USB_GOKU is not set -# CONFIG_USB_EG20T is not set -# CONFIG_USB_GADGET_XILINX is not set -# CONFIG_USB_MAX3420_UDC is not set -# CONFIG_USB_DUMMY_HCD is not set -# end of USB Peripheral Controller - -CONFIG_USB_LIBCOMPOSITE=y -CONFIG_USB_F_ACM=y -CONFIG_USB_F_SS_LB=y -CONFIG_USB_U_SERIAL=y -CONFIG_USB_U_ETHER=y -CONFIG_USB_F_SERIAL=y -CONFIG_USB_F_OBEX=y -CONFIG_USB_F_NCM=y -CONFIG_USB_F_ECM=y -CONFIG_USB_F_EEM=y -CONFIG_USB_F_SUBSET=y -CONFIG_USB_F_RNDIS=y -CONFIG_USB_F_MASS_STORAGE=y -CONFIG_USB_F_FS=y -CONFIG_USB_F_UVC=m -CONFIG_USB_F_HID=y -CONFIG_USB_F_PRINTER=y -CONFIG_USB_CONFIGFS=y -CONFIG_USB_CONFIGFS_SERIAL=y -CONFIG_USB_CONFIGFS_ACM=y -CONFIG_USB_CONFIGFS_OBEX=y -CONFIG_USB_CONFIGFS_NCM=y -CONFIG_USB_CONFIGFS_ECM=y -CONFIG_USB_CONFIGFS_ECM_SUBSET=y -CONFIG_USB_CONFIGFS_RNDIS=y -CONFIG_USB_CONFIGFS_EEM=y -CONFIG_USB_CONFIGFS_MASS_STORAGE=y -CONFIG_USB_CONFIGFS_F_LB_SS=y -CONFIG_USB_CONFIGFS_F_FS=y -CONFIG_USB_CONFIGFS_F_HID=y -CONFIG_USB_CONFIGFS_F_UVC=y -CONFIG_USB_CONFIGFS_F_PRINTER=y - -# -# USB Gadget precomposed configurations -# -# CONFIG_USB_ZERO is not set -# CONFIG_USB_ETH is not set -# CONFIG_USB_G_NCM is not set -# CONFIG_USB_GADGETFS is not set -# CONFIG_USB_FUNCTIONFS is not set -# CONFIG_USB_MASS_STORAGE is not set -# CONFIG_USB_G_SERIAL is not set -# CONFIG_USB_G_PRINTER is not set -# CONFIG_USB_CDC_COMPOSITE is not set -# CONFIG_USB_G_ACM_MS is not set -# CONFIG_USB_G_MULTI is not set -# CONFIG_USB_G_HID is not set -# CONFIG_USB_G_DBGP is not set -# CONFIG_USB_G_WEBCAM is not set -# CONFIG_USB_RAW_GADGET is not set -# end of USB Gadget precomposed configurations - -# CONFIG_TYPEC is not set -# CONFIG_USB_ROLE_SWITCH is not set -CONFIG_MMC=y -CONFIG_PWRSEQ_EMMC=y -CONFIG_PWRSEQ_SIMPLE=y -CONFIG_MMC_BLOCK=y -CONFIG_MMC_BLOCK_MINORS=8 -# CONFIG_SDIO_UART is not set -# CONFIG_MMC_TEST is not set - -# -# MMC/SD/SDIO Host Controller Drivers -# -# CONFIG_MMC_DEBUG is not set -CONFIG_MMC_SDHCI=y -# CONFIG_MMC_SDHCI_PCI is not set -CONFIG_MMC_SDHCI_PLTFM=y -# CONFIG_MMC_SDHCI_OF_ARASAN is not set -# CONFIG_MMC_SDHCI_OF_AT91 is not set -# CONFIG_MMC_SDHCI_OF_DWCMSHC is not set -CONFIG_MMC_SDHCI_CADENCE=y -# CONFIG_MMC_SDHCI_F_SDH30 is not set -# CONFIG_MMC_SDHCI_MILBEAUT is not set -# CONFIG_MMC_TIFM_SD is not set -CONFIG_MMC_SPI=y -# CONFIG_MMC_CB710 is not set -# CONFIG_MMC_VIA_SDMMC is not set -# CONFIG_MMC_DW is not set -# CONFIG_MMC_VUB300 is not set -# CONFIG_MMC_USHC is not set -# CONFIG_MMC_USDHI6ROL0 is not set -# CONFIG_MMC_CQHCI is not set -# CONFIG_MMC_HSQ is not set -# CONFIG_MMC_TOSHIBA_PCI is not set -# CONFIG_MMC_MTK is not set -# CONFIG_MMC_SDHCI_XENON is not set -# CONFIG_MMC_SDHCI_OMAP is not set -# CONFIG_MMC_SDHCI_AM654 is not set -# CONFIG_SCSI_UFSHCD is not set -# CONFIG_MEMSTICK is not set -# CONFIG_NEW_LEDS is not set -# CONFIG_ACCESSIBILITY is not set -# CONFIG_INFINIBAND is not set -CONFIG_EDAC_SUPPORT=y -CONFIG_RTC_LIB=y -CONFIG_RTC_CLASS=y -CONFIG_RTC_HCTOSYS=y -CONFIG_RTC_HCTOSYS_DEVICE="rtc0" -CONFIG_RTC_SYSTOHC=y -CONFIG_RTC_SYSTOHC_DEVICE="rtc0" -# CONFIG_RTC_DEBUG is not set -CONFIG_RTC_NVMEM=y - -# -# RTC interfaces -# -CONFIG_RTC_INTF_SYSFS=y -CONFIG_RTC_INTF_PROC=y -CONFIG_RTC_INTF_DEV=y -# CONFIG_RTC_INTF_DEV_UIE_EMUL is not set -# CONFIG_RTC_DRV_TEST is not set - -# -# I2C RTC drivers -# -# CONFIG_RTC_DRV_ABB5ZES3 is not set -# CONFIG_RTC_DRV_ABEOZ9 is not set -# CONFIG_RTC_DRV_ABX80X is not set -# CONFIG_RTC_DRV_DS1307 is not set -# CONFIG_RTC_DRV_DS1374 is not set -# CONFIG_RTC_DRV_DS1672 is not set -# CONFIG_RTC_DRV_HYM8563 is not set -# CONFIG_RTC_DRV_MAX6900 is not set -# CONFIG_RTC_DRV_NCT3018Y is not set -# CONFIG_RTC_DRV_RS5C372 is not set -# CONFIG_RTC_DRV_ISL1208 is not set -# CONFIG_RTC_DRV_ISL12022 is not set -# CONFIG_RTC_DRV_ISL12026 is not set -# CONFIG_RTC_DRV_X1205 is not set -# CONFIG_RTC_DRV_PCF8523 is not set -# CONFIG_RTC_DRV_PCF85063 is not set -# CONFIG_RTC_DRV_PCF85363 is not set -# CONFIG_RTC_DRV_PCF8563 is not set -# CONFIG_RTC_DRV_PCF8583 is not set -# CONFIG_RTC_DRV_M41T80 is not set -# CONFIG_RTC_DRV_BQ32K is not set -# CONFIG_RTC_DRV_S35390A is not set -# CONFIG_RTC_DRV_FM3130 is not set -# CONFIG_RTC_DRV_RX8010 is not set -# CONFIG_RTC_DRV_RX8581 is not set -# CONFIG_RTC_DRV_RX8025 is not set -# CONFIG_RTC_DRV_EM3027 is not set -# CONFIG_RTC_DRV_RV3028 is not set -# CONFIG_RTC_DRV_RV3032 is not set -# CONFIG_RTC_DRV_RV8803 is not set -# CONFIG_RTC_DRV_SD3078 is not set - -# -# SPI RTC drivers -# -# CONFIG_RTC_DRV_M41T93 is not set -# CONFIG_RTC_DRV_M41T94 is not set -# CONFIG_RTC_DRV_DS1302 is not set -# CONFIG_RTC_DRV_DS1305 is not set -# CONFIG_RTC_DRV_DS1343 is not set -# CONFIG_RTC_DRV_DS1347 is not set -# CONFIG_RTC_DRV_DS1390 is not set -# CONFIG_RTC_DRV_MAX6916 is not set -# CONFIG_RTC_DRV_R9701 is not set -# CONFIG_RTC_DRV_RX4581 is not set -# CONFIG_RTC_DRV_RS5C348 is not set -# CONFIG_RTC_DRV_MAX6902 is not set -# CONFIG_RTC_DRV_PCF2123 is not set -# CONFIG_RTC_DRV_MCP795 is not set -CONFIG_RTC_I2C_AND_SPI=y - -# -# SPI and I2C RTC drivers -# -# CONFIG_RTC_DRV_DS3232 is not set -# CONFIG_RTC_DRV_PCF2127 is not set -# CONFIG_RTC_DRV_RV3029C2 is not set -# CONFIG_RTC_DRV_RX6110 is not set - -# -# Platform RTC drivers -# -# CONFIG_RTC_DRV_DS1286 is not set -# CONFIG_RTC_DRV_DS1511 is not set -# CONFIG_RTC_DRV_DS1553 is not set -# CONFIG_RTC_DRV_DS1685_FAMILY is not set -# CONFIG_RTC_DRV_DS1742 is not set -# CONFIG_RTC_DRV_DS2404 is not set -# CONFIG_RTC_DRV_EFI is not set -# CONFIG_RTC_DRV_STK17TA8 is not set -# CONFIG_RTC_DRV_M48T86 is not set -# CONFIG_RTC_DRV_M48T35 is not set -# CONFIG_RTC_DRV_M48T59 is not set -# CONFIG_RTC_DRV_MSM6242 is not set -# CONFIG_RTC_DRV_BQ4802 is not set -# CONFIG_RTC_DRV_RP5C01 is not set -# CONFIG_RTC_DRV_V3020 is not set -# CONFIG_RTC_DRV_ZYNQMP is not set - -# -# on-CPU RTC drivers -# -# CONFIG_RTC_DRV_CADENCE is not set -# CONFIG_RTC_DRV_FTRTC010 is not set -# CONFIG_RTC_DRV_R7301 is not set - -# -# HID Sensor RTC drivers -# -CONFIG_RTC_DRV_GOLDFISH=y -# CONFIG_RTC_DRV_POLARFIRE_SOC is not set -# CONFIG_DMADEVICES is not set - -# -# DMABUF options -# -CONFIG_SYNC_FILE=y -# CONFIG_SW_SYNC is not set -# CONFIG_UDMABUF is not set -# CONFIG_DMABUF_MOVE_NOTIFY is not set -# CONFIG_DMABUF_DEBUG is not set -# CONFIG_DMABUF_SELFTESTS is not set -# CONFIG_DMABUF_HEAPS is not set -# CONFIG_DMABUF_SYSFS_STATS is not set -# end of DMABUF options - -# CONFIG_AUXDISPLAY is not set -# CONFIG_UIO is not set -# CONFIG_VFIO is not set -# CONFIG_VIRT_DRIVERS is not set -CONFIG_VIRTIO_ANCHOR=y -CONFIG_VIRTIO=y -CONFIG_VIRTIO_PCI_LIB=y -CONFIG_VIRTIO_PCI_LIB_LEGACY=y -CONFIG_VIRTIO_MENU=y -CONFIG_VIRTIO_PCI=y -CONFIG_VIRTIO_PCI_LEGACY=y -CONFIG_VIRTIO_BALLOON=y -CONFIG_VIRTIO_INPUT=y -CONFIG_VIRTIO_MMIO=y -# CONFIG_VIRTIO_MMIO_CMDLINE_DEVICES is not set -# CONFIG_VDPA is not set -CONFIG_VHOST_MENU=y -# CONFIG_VHOST_NET is not set -# CONFIG_VHOST_CROSS_ENDIAN_LEGACY is not set - -# -# Microsoft Hyper-V guest support -# -# end of Microsoft Hyper-V guest support - -# CONFIG_GREYBUS is not set -# CONFIG_COMEDI is not set -# CONFIG_STAGING is not set -CONFIG_GOLDFISH=y -# CONFIG_GOLDFISH_PIPE is not set -CONFIG_HAVE_CLK=y -CONFIG_HAVE_CLK_PREPARE=y -CONFIG_COMMON_CLK=y -# CONFIG_LMK04832 is not set -# CONFIG_COMMON_CLK_MAX9485 is not set -# CONFIG_COMMON_CLK_SI5341 is not set -# CONFIG_COMMON_CLK_SI5351 is not set -# CONFIG_COMMON_CLK_SI514 is not set -# CONFIG_COMMON_CLK_SI544 is not set -# CONFIG_COMMON_CLK_SI570 is not set -# CONFIG_COMMON_CLK_CDCE706 is not set -# CONFIG_COMMON_CLK_CDCE925 is not set -# CONFIG_COMMON_CLK_CS2000_CP is not set -# CONFIG_COMMON_CLK_AXI_CLKGEN is not set -# CONFIG_COMMON_CLK_RS9_PCIE is not set -# CONFIG_COMMON_CLK_VC5 is not set -# CONFIG_COMMON_CLK_VC7 is not set -# CONFIG_COMMON_CLK_FIXED_MMIO is not set -CONFIG_CLK_ANALOGBITS_WRPLL_CLN28HPC=y -CONFIG_MCHP_CLK_MPFS=y -CONFIG_CLK_SIFIVE=y -CONFIG_CLK_SIFIVE_PRCI=y -CONFIG_CLK_STARFIVE_JH7100=y -CONFIG_CLK_STARFIVE_JH7100_AUDIO=m -# CONFIG_XILINX_VCU is not set -# CONFIG_COMMON_CLK_XLNX_CLKWZRD is not set -# CONFIG_HWSPINLOCK is not set - -# -# Clock Source drivers -# -CONFIG_TIMER_OF=y -CONFIG_TIMER_PROBE=y -CONFIG_RISCV_TIMER=y -# CONFIG_MICROCHIP_PIT64B is not set -# end of Clock Source drivers - -CONFIG_MAILBOX=y -# CONFIG_PLATFORM_MHU is not set -# CONFIG_ALTERA_MBOX is not set -# CONFIG_MAILBOX_TEST is not set -CONFIG_POLARFIRE_SOC_MAILBOX=y -CONFIG_IOMMU_SUPPORT=y - -# -# Generic IOMMU Pagetable Support -# -# end of Generic IOMMU Pagetable Support - -# CONFIG_IOMMU_DEBUGFS is not set - -# -# Remoteproc drivers -# -CONFIG_REMOTEPROC=y -CONFIG_REMOTEPROC_CDEV=y -# end of Remoteproc drivers - -# -# Rpmsg drivers -# -CONFIG_RPMSG=y -CONFIG_RPMSG_CHAR=y -CONFIG_RPMSG_CTRL=y -CONFIG_RPMSG_NS=y -# CONFIG_RPMSG_QCOM_GLINK_RPM is not set -CONFIG_RPMSG_VIRTIO=y -# end of Rpmsg drivers - -# CONFIG_SOUNDWIRE is not set - -# -# SOC (System On Chip) specific Drivers -# - -# -# Amlogic SoC drivers -# -# end of Amlogic SoC drivers - -# -# Broadcom SoC drivers -# -# end of Broadcom SoC drivers - -# -# NXP/Freescale QorIQ SoC drivers -# -# end of NXP/Freescale QorIQ SoC drivers - -# -# fujitsu SoC drivers -# -# end of fujitsu SoC drivers - -# -# i.MX SoC drivers -# -# end of i.MX SoC drivers - -# -# Enable LiteX SoC Builder specific drivers -# -# CONFIG_LITEX_SOC_CONTROLLER is not set -# end of Enable LiteX SoC Builder specific drivers - -CONFIG_POLARFIRE_SOC_SYS_CTRL=y - -# -# Qualcomm SoC drivers -# -# end of Qualcomm SoC drivers - -# CONFIG_SIFIVE_CCACHE is not set -# CONFIG_SOC_TI is not set - -# -# Xilinx SoC drivers -# -# end of Xilinx SoC drivers -# end of SOC (System On Chip) specific Drivers - -# CONFIG_PM_DEVFREQ is not set -CONFIG_EXTCON=y - -# -# Extcon Device Drivers -# -# CONFIG_EXTCON_ADC_JACK is not set -# CONFIG_EXTCON_FSA9480 is not set -# CONFIG_EXTCON_GPIO is not set -# CONFIG_EXTCON_MAX3355 is not set -# CONFIG_EXTCON_PTN5150 is not set -# CONFIG_EXTCON_RT8973A is not set -# CONFIG_EXTCON_SM5502 is not set -# CONFIG_EXTCON_USB_GPIO is not set -# CONFIG_MEMORY is not set -CONFIG_IIO=m -# CONFIG_IIO_BUFFER is not set -# CONFIG_IIO_CONFIGFS is not set -# CONFIG_IIO_TRIGGER is not set -# CONFIG_IIO_SW_DEVICE is not set -# CONFIG_IIO_SW_TRIGGER is not set -# CONFIG_IIO_TRIGGERED_EVENT is not set - -# -# Accelerometers -# -# CONFIG_ADIS16201 is not set -# CONFIG_ADIS16209 is not set -# CONFIG_ADXL313_I2C is not set -# CONFIG_ADXL313_SPI is not set -# CONFIG_ADXL345_I2C is not set -# CONFIG_ADXL345_SPI is not set -# CONFIG_ADXL355_I2C is not set -# CONFIG_ADXL355_SPI is not set -# CONFIG_ADXL367_SPI is not set -# CONFIG_ADXL367_I2C is not set -# CONFIG_ADXL372_SPI is not set -# CONFIG_ADXL372_I2C is not set -# CONFIG_BMA180 is not set -# CONFIG_BMA220 is not set -# CONFIG_BMA400 is not set -# CONFIG_BMC150_ACCEL is not set -# CONFIG_BMI088_ACCEL is not set -# CONFIG_DA280 is not set -# CONFIG_DA311 is not set -# CONFIG_DMARD06 is not set -# CONFIG_DMARD09 is not set -# CONFIG_DMARD10 is not set -# CONFIG_FXLS8962AF_I2C is not set -# CONFIG_FXLS8962AF_SPI is not set -# CONFIG_IIO_ST_ACCEL_3AXIS is not set -# CONFIG_KXSD9 is not set -# CONFIG_KXCJK1013 is not set -# CONFIG_MC3230 is not set -# CONFIG_MMA7455_I2C is not set -# CONFIG_MMA7455_SPI is not set -# CONFIG_MMA7660 is not set -# CONFIG_MMA8452 is not set -# CONFIG_MMA9551 is not set -# CONFIG_MMA9553 is not set -# CONFIG_MSA311 is not set -# CONFIG_MXC4005 is not set -# CONFIG_MXC6255 is not set -# CONFIG_SCA3000 is not set -# CONFIG_SCA3300 is not set -# CONFIG_STK8312 is not set -# CONFIG_STK8BA50 is not set -# end of Accelerometers - -# -# Analog to digital converters -# -# CONFIG_AD7091R5 is not set -# CONFIG_AD7124 is not set -# CONFIG_AD7192 is not set -# CONFIG_AD7266 is not set -# CONFIG_AD7280 is not set -# CONFIG_AD7291 is not set -# CONFIG_AD7292 is not set -# CONFIG_AD7298 is not set -# CONFIG_AD7476 is not set -# CONFIG_AD7606_IFACE_PARALLEL is not set -# CONFIG_AD7606_IFACE_SPI is not set -# CONFIG_AD7766 is not set -# CONFIG_AD7768_1 is not set -# CONFIG_AD7780 is not set -# CONFIG_AD7791 is not set -# CONFIG_AD7793 is not set -# CONFIG_AD7887 is not set -# CONFIG_AD7923 is not set -# CONFIG_AD7949 is not set -# CONFIG_AD799X is not set -# CONFIG_ADI_AXI_ADC is not set -# CONFIG_ENVELOPE_DETECTOR is not set -# CONFIG_HI8435 is not set -# CONFIG_HX711 is not set -# CONFIG_INA2XX_ADC is not set -# CONFIG_LTC2471 is not set -# CONFIG_LTC2485 is not set -# CONFIG_LTC2496 is not set -# CONFIG_LTC2497 is not set -# CONFIG_MAX1027 is not set -# CONFIG_MAX11100 is not set -# CONFIG_MAX1118 is not set -# CONFIG_MAX11205 is not set -# CONFIG_MAX1241 is not set -# CONFIG_MAX1363 is not set -# CONFIG_MAX9611 is not set -# CONFIG_MCP320X is not set -# CONFIG_MCP3422 is not set -# CONFIG_MCP3911 is not set -# CONFIG_NAU7802 is not set -# CONFIG_RICHTEK_RTQ6056 is not set -# CONFIG_SD_ADC_MODULATOR is not set -# CONFIG_TI_ADC081C is not set -# CONFIG_TI_ADC0832 is not set -# CONFIG_TI_ADC084S021 is not set -# CONFIG_TI_ADC12138 is not set -# CONFIG_TI_ADC108S102 is not set -# CONFIG_TI_ADC128S052 is not set -# CONFIG_TI_ADC161S626 is not set -# CONFIG_TI_ADS1015 is not set -# CONFIG_TI_ADS7950 is not set -# CONFIG_TI_ADS8344 is not set -# CONFIG_TI_ADS8688 is not set -# CONFIG_TI_ADS124S08 is not set -# CONFIG_TI_ADS131E08 is not set -# CONFIG_TI_TLC4541 is not set -# CONFIG_TI_TSC2046 is not set -# CONFIG_VF610_ADC is not set -# CONFIG_XILINX_XADC is not set -# end of Analog to digital converters - -# -# Analog to digital and digital to analog converters -# -# CONFIG_AD74413R is not set -# end of Analog to digital and digital to analog converters - -# -# Analog Front Ends -# -# CONFIG_IIO_RESCALE is not set -# end of Analog Front Ends - -# -# Amplifiers -# -# CONFIG_AD8366 is not set -# CONFIG_ADA4250 is not set -# CONFIG_HMC425 is not set -# end of Amplifiers - -# -# Capacitance to digital converters -# -# CONFIG_AD7150 is not set -# CONFIG_AD7746 is not set -# end of Capacitance to digital converters - -# -# Chemical Sensors -# -# CONFIG_ATLAS_PH_SENSOR is not set -# CONFIG_ATLAS_EZO_SENSOR is not set -# CONFIG_BME680 is not set -# CONFIG_CCS811 is not set -# CONFIG_IAQCORE is not set -# CONFIG_SCD30_CORE is not set -# CONFIG_SCD4X is not set -# CONFIG_SENSIRION_SGP30 is not set -# CONFIG_SENSIRION_SGP40 is not set -# CONFIG_SPS30_I2C is not set -# CONFIG_SENSEAIR_SUNRISE_CO2 is not set -# CONFIG_VZ89X is not set -# end of Chemical Sensors - -# -# Hid Sensor IIO Common -# -# end of Hid Sensor IIO Common - -# -# IIO SCMI Sensors -# -# end of IIO SCMI Sensors - -# -# SSP Sensor Common -# -# CONFIG_IIO_SSP_SENSORHUB is not set -# end of SSP Sensor Common - -# -# Digital to analog converters -# -# CONFIG_AD3552R is not set -# CONFIG_AD5064 is not set -# CONFIG_AD5360 is not set -# CONFIG_AD5380 is not set -# CONFIG_AD5421 is not set -# CONFIG_AD5446 is not set -# CONFIG_AD5449 is not set -# CONFIG_AD5592R is not set -# CONFIG_AD5593R is not set -# CONFIG_AD5504 is not set -# CONFIG_AD5624R_SPI is not set -# CONFIG_LTC2688 is not set -# CONFIG_AD5686_SPI is not set -# CONFIG_AD5696_I2C is not set -# CONFIG_AD5755 is not set -# CONFIG_AD5758 is not set -# CONFIG_AD5761 is not set -# CONFIG_AD5764 is not set -# CONFIG_AD5766 is not set -# CONFIG_AD5770R is not set -# CONFIG_AD5791 is not set -# CONFIG_AD7293 is not set -# CONFIG_AD7303 is not set -# CONFIG_AD8801 is not set -# CONFIG_DPOT_DAC is not set -# CONFIG_DS4424 is not set -# CONFIG_LTC1660 is not set -# CONFIG_LTC2632 is not set -# CONFIG_M62332 is not set -# CONFIG_MAX517 is not set -# CONFIG_MAX5821 is not set -# CONFIG_MCP4725 is not set -# CONFIG_MCP4922 is not set -# CONFIG_TI_DAC082S085 is not set -# CONFIG_TI_DAC5571 is not set -# CONFIG_TI_DAC7311 is not set -# CONFIG_TI_DAC7612 is not set -# CONFIG_VF610_DAC is not set -# end of Digital to analog converters - -# -# IIO dummy driver -# -# end of IIO dummy driver - -# -# Filters -# -# CONFIG_ADMV8818 is not set -# end of Filters - -# -# Frequency Synthesizers DDS/PLL -# - -# -# Clock Generator/Distribution -# -# CONFIG_AD9523 is not set -# end of Clock Generator/Distribution - -# -# Phase-Locked Loop (PLL) frequency synthesizers -# -# CONFIG_ADF4350 is not set -# CONFIG_ADF4371 is not set -# CONFIG_ADMV1013 is not set -# CONFIG_ADMV1014 is not set -# CONFIG_ADMV4420 is not set -# CONFIG_ADRF6780 is not set -# end of Phase-Locked Loop (PLL) frequency synthesizers -# end of Frequency Synthesizers DDS/PLL - -# -# Digital gyroscope sensors -# -# CONFIG_ADIS16080 is not set -# CONFIG_ADIS16130 is not set -# CONFIG_ADIS16136 is not set -# CONFIG_ADIS16260 is not set -# CONFIG_ADXRS290 is not set -# CONFIG_ADXRS450 is not set -# CONFIG_BMG160 is not set -# CONFIG_FXAS21002C is not set -# CONFIG_MPU3050_I2C is not set -# CONFIG_IIO_ST_GYRO_3AXIS is not set -# CONFIG_ITG3200 is not set -# end of Digital gyroscope sensors - -# -# Health Sensors -# - -# -# Heart Rate Monitors -# -# CONFIG_AFE4403 is not set -# CONFIG_AFE4404 is not set -# CONFIG_MAX30100 is not set -# CONFIG_MAX30102 is not set -# end of Heart Rate Monitors -# end of Health Sensors - -# -# Humidity sensors -# -# CONFIG_AM2315 is not set -# CONFIG_DHT11 is not set -# CONFIG_HDC100X is not set -# CONFIG_HDC2010 is not set -# CONFIG_HTS221 is not set -# CONFIG_HTU21 is not set -# CONFIG_SI7005 is not set -# CONFIG_SI7020 is not set -# end of Humidity sensors - -# -# Inertial measurement units -# -# CONFIG_ADIS16400 is not set -# CONFIG_ADIS16460 is not set -# CONFIG_ADIS16475 is not set -# CONFIG_ADIS16480 is not set -# CONFIG_BMI160_I2C is not set -# CONFIG_BMI160_SPI is not set -# CONFIG_BOSCH_BNO055_I2C is not set -# CONFIG_FXOS8700_I2C is not set -# CONFIG_FXOS8700_SPI is not set -# CONFIG_KMX61 is not set -# CONFIG_INV_ICM42600_I2C is not set -# CONFIG_INV_ICM42600_SPI is not set -# CONFIG_INV_MPU6050_I2C is not set -# CONFIG_INV_MPU6050_SPI is not set -# CONFIG_IIO_ST_LSM6DSX is not set -# CONFIG_IIO_ST_LSM9DS0 is not set -# end of Inertial measurement units - -# -# Light sensors -# -# CONFIG_ADJD_S311 is not set -# CONFIG_ADUX1020 is not set -# CONFIG_AL3010 is not set -# CONFIG_AL3320A is not set -# CONFIG_APDS9300 is not set -# CONFIG_APDS9960 is not set -# CONFIG_AS73211 is not set -# CONFIG_BH1750 is not set -# CONFIG_BH1780 is not set -# CONFIG_CM32181 is not set -# CONFIG_CM3232 is not set -# CONFIG_CM3323 is not set -# CONFIG_CM3605 is not set -# CONFIG_CM36651 is not set -# CONFIG_GP2AP002 is not set -# CONFIG_GP2AP020A00F is not set -# CONFIG_SENSORS_ISL29018 is not set -# CONFIG_SENSORS_ISL29028 is not set -# CONFIG_ISL29125 is not set -# CONFIG_JSA1212 is not set -# CONFIG_RPR0521 is not set -# CONFIG_LTR501 is not set -# CONFIG_LTRF216A is not set -# CONFIG_LV0104CS is not set -# CONFIG_MAX44000 is not set -# CONFIG_MAX44009 is not set -# CONFIG_NOA1305 is not set -# CONFIG_OPT3001 is not set -# CONFIG_PA12203001 is not set -# CONFIG_SI1133 is not set -# CONFIG_SI1145 is not set -# CONFIG_STK3310 is not set -# CONFIG_ST_UVIS25 is not set -# CONFIG_TCS3414 is not set -# CONFIG_TCS3472 is not set -# CONFIG_SENSORS_TSL2563 is not set -# CONFIG_TSL2583 is not set -# CONFIG_TSL2591 is not set -# CONFIG_TSL2772 is not set -# CONFIG_TSL4531 is not set -# CONFIG_US5182D is not set -# CONFIG_VCNL4000 is not set -# CONFIG_VCNL4035 is not set -# CONFIG_VEML6030 is not set -# CONFIG_VEML6070 is not set -# CONFIG_VL6180 is not set -# CONFIG_ZOPT2201 is not set -# end of Light sensors - -# -# Magnetometer sensors -# -# CONFIG_AK8974 is not set -# CONFIG_AK8975 is not set -# CONFIG_AK09911 is not set -# CONFIG_BMC150_MAGN_I2C is not set -# CONFIG_BMC150_MAGN_SPI is not set -# CONFIG_MAG3110 is not set -# CONFIG_MMC35240 is not set -# CONFIG_IIO_ST_MAGN_3AXIS is not set -# CONFIG_SENSORS_HMC5843_I2C is not set -# CONFIG_SENSORS_HMC5843_SPI is not set -# CONFIG_SENSORS_RM3100_I2C is not set -# CONFIG_SENSORS_RM3100_SPI is not set -# CONFIG_YAMAHA_YAS530 is not set -# end of Magnetometer sensors - -# -# Multiplexers -# -# CONFIG_IIO_MUX is not set -# end of Multiplexers - -# -# Inclinometer sensors -# -# end of Inclinometer sensors - -# -# Linear and angular position sensors -# -# end of Linear and angular position sensors - -# -# Digital potentiometers -# -# CONFIG_AD5110 is not set -# CONFIG_AD5272 is not set -# CONFIG_DS1803 is not set -# CONFIG_MAX5432 is not set -# CONFIG_MAX5481 is not set -# CONFIG_MAX5487 is not set -# CONFIG_MCP4018 is not set -# CONFIG_MCP4131 is not set -# CONFIG_MCP4531 is not set -# CONFIG_MCP41010 is not set -# CONFIG_TPL0102 is not set -# end of Digital potentiometers - -# -# Digital potentiostats -# -# CONFIG_LMP91000 is not set -# end of Digital potentiostats - -# -# Pressure sensors -# -# CONFIG_ABP060MG is not set -# CONFIG_BMP280 is not set -# CONFIG_DLHL60D is not set -# CONFIG_DPS310 is not set -# CONFIG_HP03 is not set -# CONFIG_ICP10100 is not set -# CONFIG_MPL115_I2C is not set -# CONFIG_MPL115_SPI is not set -# CONFIG_MPL3115 is not set -# CONFIG_MS5611 is not set -# CONFIG_MS5637 is not set -# CONFIG_IIO_ST_PRESS is not set -# CONFIG_T5403 is not set -# CONFIG_HP206C is not set -# CONFIG_ZPA2326 is not set -# end of Pressure sensors - -# -# Lightning sensors -# -# CONFIG_AS3935 is not set -# end of Lightning sensors - -# -# Proximity and distance sensors -# -# CONFIG_ISL29501 is not set -# CONFIG_LIDAR_LITE_V2 is not set -# CONFIG_MB1232 is not set -# CONFIG_PING is not set -# CONFIG_RFD77402 is not set -# CONFIG_SRF04 is not set -# CONFIG_SX9310 is not set -# CONFIG_SX9324 is not set -# CONFIG_SX9360 is not set -# CONFIG_SX9500 is not set -# CONFIG_SRF08 is not set -# CONFIG_VCNL3020 is not set -# CONFIG_VL53L0X_I2C is not set -# end of Proximity and distance sensors - -# -# Resolver to digital converters -# -# CONFIG_AD2S90 is not set -# CONFIG_AD2S1200 is not set -# end of Resolver to digital converters - -# -# Temperature sensors -# -# CONFIG_LTC2983 is not set -# CONFIG_MAXIM_THERMOCOUPLE is not set -# CONFIG_MLX90614 is not set -# CONFIG_MLX90632 is not set -# CONFIG_TMP006 is not set -# CONFIG_TMP007 is not set -# CONFIG_TMP117 is not set -# CONFIG_TSYS01 is not set -# CONFIG_TSYS02D is not set -# CONFIG_MAX31856 is not set -# CONFIG_MAX31865 is not set -# end of Temperature sensors - -# CONFIG_NTB is not set -# CONFIG_PWM is not set - -# -# IRQ chip support -# -CONFIG_IRQCHIP=y -# CONFIG_AL_FIC is not set -# CONFIG_XILINX_INTC is not set -CONFIG_RISCV_INTC=y -CONFIG_SIFIVE_PLIC=y -# end of IRQ chip support - -# CONFIG_IPACK_BUS is not set -CONFIG_RESET_CONTROLLER=y -CONFIG_RESET_POLARFIRE_SOC=y -CONFIG_RESET_SIMPLE=y -CONFIG_RESET_STARFIVE_JH7100=y -# CONFIG_RESET_TI_SYSCON is not set -# CONFIG_RESET_TI_TPS380X is not set - -# -# PHY Subsystem -# -# CONFIG_GENERIC_PHY is not set -# CONFIG_PHY_CAN_TRANSCEIVER is not set - -# -# PHY drivers for Broadcom platforms -# -# CONFIG_BCM_KONA_USB2_PHY is not set -# end of PHY drivers for Broadcom platforms - -# CONFIG_PHY_CADENCE_TORRENT is not set -# CONFIG_PHY_CADENCE_DPHY is not set -# CONFIG_PHY_CADENCE_DPHY_RX is not set -# CONFIG_PHY_CADENCE_SIERRA is not set -# CONFIG_PHY_CADENCE_SALVO is not set -# CONFIG_PHY_PXA_28NM_HSIC is not set -# CONFIG_PHY_PXA_28NM_USB2 is not set -# CONFIG_PHY_LAN966X_SERDES is not set -# CONFIG_PHY_CPCAP_USB is not set -# CONFIG_PHY_MAPPHONE_MDM6600 is not set -# CONFIG_PHY_OCELOT_SERDES is not set -# end of PHY Subsystem - -# CONFIG_POWERCAP is not set -# CONFIG_MCB is not set - -# -# Performance monitor support -# -CONFIG_RISCV_PMU=y -CONFIG_RISCV_PMU_LEGACY=y -CONFIG_RISCV_PMU_SBI=y -# end of Performance monitor support - -# CONFIG_RAS is not set -# CONFIG_USB4 is not set - -# -# Android -# -# CONFIG_ANDROID_BINDER_IPC is not set -# end of Android - -# CONFIG_LIBNVDIMM is not set -# CONFIG_DAX is not set -CONFIG_NVMEM=y -CONFIG_NVMEM_SYSFS=y -# CONFIG_NVMEM_RMEM is not set - -# -# HW tracing support -# -# CONFIG_STM is not set -# CONFIG_INTEL_TH is not set -# end of HW tracing support - -# CONFIG_FPGA is not set -# CONFIG_FSI is not set -# CONFIG_SIOX is not set -# CONFIG_SLIMBUS is not set -# CONFIG_INTERCONNECT is not set -# CONFIG_COUNTER is not set -# CONFIG_MOST is not set -# CONFIG_PECI is not set -# CONFIG_HTE is not set -# end of Device Drivers - -# -# File systems -# -# CONFIG_VALIDATE_FS_PARSER is not set -CONFIG_FS_IOMAP=y -# CONFIG_EXT2_FS is not set -# CONFIG_EXT3_FS is not set -CONFIG_EXT4_FS=y -CONFIG_EXT4_USE_FOR_EXT2=y -CONFIG_EXT4_FS_POSIX_ACL=y -CONFIG_EXT4_FS_SECURITY=y -# CONFIG_EXT4_DEBUG is not set -CONFIG_JBD2=y -# CONFIG_JBD2_DEBUG is not set -CONFIG_FS_MBCACHE=y -# CONFIG_REISERFS_FS is not set -# CONFIG_JFS_FS is not set -# CONFIG_XFS_FS is not set -# CONFIG_GFS2_FS is not set -# CONFIG_OCFS2_FS is not set -CONFIG_BTRFS_FS=m -CONFIG_BTRFS_FS_POSIX_ACL=y -# CONFIG_BTRFS_FS_CHECK_INTEGRITY is not set -# CONFIG_BTRFS_FS_RUN_SANITY_TESTS is not set -# CONFIG_BTRFS_DEBUG is not set -# CONFIG_BTRFS_ASSERT is not set -# CONFIG_BTRFS_FS_REF_VERIFY is not set -# CONFIG_NILFS2_FS is not set -# CONFIG_F2FS_FS is not set -CONFIG_FS_POSIX_ACL=y -CONFIG_EXPORTFS=y -# CONFIG_EXPORTFS_BLOCK_OPS is not set -CONFIG_FILE_LOCKING=y -# CONFIG_FS_ENCRYPTION is not set -# CONFIG_FS_VERITY is not set -CONFIG_FSNOTIFY=y -CONFIG_DNOTIFY=y -CONFIG_INOTIFY_USER=y -# CONFIG_FANOTIFY is not set -# CONFIG_QUOTA is not set -CONFIG_AUTOFS4_FS=y -CONFIG_AUTOFS_FS=y -# CONFIG_FUSE_FS is not set -CONFIG_OVERLAY_FS=m -# CONFIG_OVERLAY_FS_REDIRECT_DIR is not set -CONFIG_OVERLAY_FS_REDIRECT_ALWAYS_FOLLOW=y -# CONFIG_OVERLAY_FS_INDEX is not set -# CONFIG_OVERLAY_FS_XINO_AUTO is not set -# CONFIG_OVERLAY_FS_METACOPY is not set - -# -# Caches -# -CONFIG_NETFS_SUPPORT=y -# CONFIG_NETFS_STATS is not set -# CONFIG_FSCACHE is not set -# end of Caches - -# -# CD-ROM/DVD Filesystems -# -CONFIG_ISO9660_FS=y -CONFIG_JOLIET=y -CONFIG_ZISOFS=y -# CONFIG_UDF_FS is not set -# end of CD-ROM/DVD Filesystems - -# -# DOS/FAT/EXFAT/NT Filesystems -# -CONFIG_FAT_FS=y -CONFIG_MSDOS_FS=y -CONFIG_VFAT_FS=y -CONFIG_FAT_DEFAULT_CODEPAGE=437 -CONFIG_FAT_DEFAULT_IOCHARSET="iso8859-1" -# CONFIG_FAT_DEFAULT_UTF8 is not set -# CONFIG_EXFAT_FS is not set -# CONFIG_NTFS_FS is not set -# CONFIG_NTFS3_FS is not set -# end of DOS/FAT/EXFAT/NT Filesystems - -# -# Pseudo filesystems -# -CONFIG_PROC_FS=y -# CONFIG_PROC_KCORE is not set -CONFIG_PROC_SYSCTL=y -CONFIG_PROC_PAGE_MONITOR=y -CONFIG_PROC_CHILDREN=y -CONFIG_KERNFS=y -CONFIG_SYSFS=y -CONFIG_TMPFS=y -CONFIG_TMPFS_POSIX_ACL=y -CONFIG_TMPFS_XATTR=y -# CONFIG_TMPFS_INODE64 is not set -CONFIG_ARCH_SUPPORTS_HUGETLBFS=y -CONFIG_HUGETLBFS=y -CONFIG_HUGETLB_PAGE=y -CONFIG_MEMFD_CREATE=y -CONFIG_ARCH_HAS_GIGANTIC_PAGE=y -CONFIG_CONFIGFS_FS=y -CONFIG_EFIVAR_FS=m -# end of Pseudo filesystems - -CONFIG_MISC_FILESYSTEMS=y -# CONFIG_ORANGEFS_FS is not set -# CONFIG_ADFS_FS is not set -# CONFIG_AFFS_FS is not set -# CONFIG_ECRYPT_FS is not set -# CONFIG_HFS_FS is not set -# CONFIG_HFSPLUS_FS is not set -# CONFIG_BEFS_FS is not set -# CONFIG_BFS_FS is not set -# CONFIG_EFS_FS is not set -# CONFIG_CRAMFS is not set -# CONFIG_SQUASHFS is not set -# CONFIG_VXFS_FS is not set -# CONFIG_MINIX_FS is not set -# CONFIG_OMFS_FS is not set -# CONFIG_HPFS_FS is not set -# CONFIG_QNX4FS_FS is not set -# CONFIG_QNX6FS_FS is not set -# CONFIG_ROMFS_FS is not set -# CONFIG_PSTORE is not set -# CONFIG_SYSV_FS is not set -# CONFIG_UFS_FS is not set -# CONFIG_EROFS_FS is not set -CONFIG_NETWORK_FILESYSTEMS=y -CONFIG_NFS_FS=y -CONFIG_NFS_V2=y -CONFIG_NFS_V3=y -# CONFIG_NFS_V3_ACL is not set -CONFIG_NFS_V4=y -# CONFIG_NFS_SWAP is not set -CONFIG_NFS_V4_1=y -CONFIG_NFS_V4_2=y -CONFIG_PNFS_FILE_LAYOUT=y -CONFIG_PNFS_BLOCK=y -CONFIG_PNFS_FLEXFILE_LAYOUT=y -CONFIG_NFS_V4_1_IMPLEMENTATION_ID_DOMAIN="kernel.org" -# CONFIG_NFS_V4_1_MIGRATION is not set -CONFIG_NFS_V4_SECURITY_LABEL=y -CONFIG_ROOT_NFS=y -# CONFIG_NFS_USE_LEGACY_DNS is not set -CONFIG_NFS_USE_KERNEL_DNS=y -CONFIG_NFS_DISABLE_UDP_SUPPORT=y -# CONFIG_NFS_V4_2_READ_PLUS is not set -# CONFIG_NFSD is not set -CONFIG_GRACE_PERIOD=y -CONFIG_LOCKD=y -CONFIG_LOCKD_V4=y -CONFIG_NFS_COMMON=y -CONFIG_NFS_V4_2_SSC_HELPER=y -CONFIG_SUNRPC=y -CONFIG_SUNRPC_GSS=y -CONFIG_SUNRPC_BACKCHANNEL=y -# CONFIG_SUNRPC_DEBUG is not set -# CONFIG_CEPH_FS is not set -# CONFIG_CIFS is not set -# CONFIG_SMB_SERVER is not set -# CONFIG_CODA_FS is not set -# CONFIG_AFS_FS is not set -CONFIG_9P_FS=y -# CONFIG_9P_FS_POSIX_ACL is not set -# CONFIG_9P_FS_SECURITY is not set -CONFIG_NLS=y -CONFIG_NLS_DEFAULT="iso8859-1" -CONFIG_NLS_CODEPAGE_437=y -# CONFIG_NLS_CODEPAGE_737 is not set -# CONFIG_NLS_CODEPAGE_775 is not set -# CONFIG_NLS_CODEPAGE_850 is not set -# CONFIG_NLS_CODEPAGE_852 is not set -# CONFIG_NLS_CODEPAGE_855 is not set -# CONFIG_NLS_CODEPAGE_857 is not set -# CONFIG_NLS_CODEPAGE_860 is not set -# CONFIG_NLS_CODEPAGE_861 is not set -# CONFIG_NLS_CODEPAGE_862 is not set -# CONFIG_NLS_CODEPAGE_863 is not set -# CONFIG_NLS_CODEPAGE_864 is not set -# CONFIG_NLS_CODEPAGE_865 is not set -# CONFIG_NLS_CODEPAGE_866 is not set -# CONFIG_NLS_CODEPAGE_869 is not set -# CONFIG_NLS_CODEPAGE_936 is not set -# CONFIG_NLS_CODEPAGE_950 is not set -# CONFIG_NLS_CODEPAGE_932 is not set -# CONFIG_NLS_CODEPAGE_949 is not set -# CONFIG_NLS_CODEPAGE_874 is not set -# CONFIG_NLS_ISO8859_8 is not set -# CONFIG_NLS_CODEPAGE_1250 is not set -# CONFIG_NLS_CODEPAGE_1251 is not set -# CONFIG_NLS_ASCII is not set -CONFIG_NLS_ISO8859_1=y -# CONFIG_NLS_ISO8859_2 is not set -# CONFIG_NLS_ISO8859_3 is not set -# CONFIG_NLS_ISO8859_4 is not set -# CONFIG_NLS_ISO8859_5 is not set -# CONFIG_NLS_ISO8859_6 is not set -# CONFIG_NLS_ISO8859_7 is not set -# CONFIG_NLS_ISO8859_9 is not set -# CONFIG_NLS_ISO8859_13 is not set -# CONFIG_NLS_ISO8859_14 is not set -# CONFIG_NLS_ISO8859_15 is not set -# CONFIG_NLS_KOI8_R is not set -# CONFIG_NLS_KOI8_U is not set -# CONFIG_NLS_MAC_ROMAN is not set -# CONFIG_NLS_MAC_CELTIC is not set -# CONFIG_NLS_MAC_CENTEURO is not set -# CONFIG_NLS_MAC_CROATIAN is not set -# CONFIG_NLS_MAC_CYRILLIC is not set -# CONFIG_NLS_MAC_GAELIC is not set -# CONFIG_NLS_MAC_GREEK is not set -# CONFIG_NLS_MAC_ICELAND is not set -# CONFIG_NLS_MAC_INUIT is not set -# CONFIG_NLS_MAC_ROMANIAN is not set -# CONFIG_NLS_MAC_TURKISH is not set -# CONFIG_NLS_UTF8 is not set -# CONFIG_DLM is not set -# CONFIG_UNICODE is not set -CONFIG_IO_WQ=y -# end of File systems - -# -# Security options -# -CONFIG_KEYS=y -# CONFIG_KEYS_REQUEST_CACHE is not set -# CONFIG_PERSISTENT_KEYRINGS is not set -# CONFIG_TRUSTED_KEYS is not set -# CONFIG_ENCRYPTED_KEYS is not set -# CONFIG_KEY_DH_OPERATIONS is not set -# CONFIG_SECURITY_DMESG_RESTRICT is not set -CONFIG_SECURITY=y -CONFIG_SECURITYFS=y -CONFIG_SECURITY_NETWORK=y -# CONFIG_SECURITY_NETWORK_XFRM is not set -CONFIG_SECURITY_PATH=y -CONFIG_LSM_MMAP_MIN_ADDR=65536 -CONFIG_HAVE_HARDENED_USERCOPY_ALLOCATOR=y -# CONFIG_HARDENED_USERCOPY is not set -# CONFIG_FORTIFY_SOURCE is not set -# CONFIG_STATIC_USERMODEHELPER is not set -CONFIG_SECURITY_SELINUX=y -# CONFIG_SECURITY_SELINUX_BOOTPARAM is not set -# CONFIG_SECURITY_SELINUX_DISABLE is not set -CONFIG_SECURITY_SELINUX_DEVELOP=y -CONFIG_SECURITY_SELINUX_AVC_STATS=y -CONFIG_SECURITY_SELINUX_CHECKREQPROT_VALUE=0 -CONFIG_SECURITY_SELINUX_SIDTAB_HASH_BITS=9 -CONFIG_SECURITY_SELINUX_SID2STR_CACHE_SIZE=256 -# CONFIG_SECURITY_SMACK is not set -# CONFIG_SECURITY_TOMOYO is not set -CONFIG_SECURITY_APPARMOR=y -# CONFIG_SECURITY_APPARMOR_DEBUG is not set -CONFIG_SECURITY_APPARMOR_INTROSPECT_POLICY=y -CONFIG_SECURITY_APPARMOR_HASH=y -CONFIG_SECURITY_APPARMOR_HASH_DEFAULT=y -CONFIG_SECURITY_APPARMOR_EXPORT_BINARY=y -CONFIG_SECURITY_APPARMOR_PARANOID_LOAD=y -# CONFIG_SECURITY_LOADPIN is not set -# CONFIG_SECURITY_YAMA is not set -# CONFIG_SECURITY_SAFESETID is not set -# CONFIG_SECURITY_LOCKDOWN_LSM is not set -# CONFIG_SECURITY_LANDLOCK is not set -CONFIG_INTEGRITY=y -# CONFIG_INTEGRITY_SIGNATURE is not set -CONFIG_INTEGRITY_AUDIT=y -# CONFIG_IMA is not set -# CONFIG_EVM is not set -# CONFIG_DEFAULT_SECURITY_SELINUX is not set -# CONFIG_DEFAULT_SECURITY_APPARMOR is not set -CONFIG_DEFAULT_SECURITY_DAC=y -CONFIG_LSM="landlock,lockdown,yama,loadpin,safesetid,integrity,bpf" - -# -# Kernel hardening options -# - -# -# Memory initialization -# -CONFIG_INIT_STACK_NONE=y -# CONFIG_GCC_PLUGIN_STRUCTLEAK_USER is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF_ALL is not set -# CONFIG_INIT_ON_ALLOC_DEFAULT_ON is not set -# CONFIG_INIT_ON_FREE_DEFAULT_ON is not set -CONFIG_CC_HAS_ZERO_CALL_USED_REGS=y -# CONFIG_ZERO_CALL_USED_REGS is not set -# end of Memory initialization - -CONFIG_RANDSTRUCT_NONE=y -# CONFIG_RANDSTRUCT_FULL is not set -# CONFIG_RANDSTRUCT_PERFORMANCE is not set -# end of Kernel hardening options -# end of Security options - -CONFIG_XOR_BLOCKS=m -CONFIG_CRYPTO=y - -# -# Crypto core or helper -# -CONFIG_CRYPTO_ALGAPI=y -CONFIG_CRYPTO_ALGAPI2=y -CONFIG_CRYPTO_AEAD=y -CONFIG_CRYPTO_AEAD2=y -CONFIG_CRYPTO_SKCIPHER=y -CONFIG_CRYPTO_SKCIPHER2=y -CONFIG_CRYPTO_HASH=y -CONFIG_CRYPTO_HASH2=y -CONFIG_CRYPTO_RNG=m -CONFIG_CRYPTO_RNG2=y -CONFIG_CRYPTO_RNG_DEFAULT=m -CONFIG_CRYPTO_AKCIPHER2=y -CONFIG_CRYPTO_AKCIPHER=y -CONFIG_CRYPTO_KPP2=y -CONFIG_CRYPTO_ACOMP2=y -CONFIG_CRYPTO_MANAGER=y -CONFIG_CRYPTO_MANAGER2=y -# CONFIG_CRYPTO_USER is not set -CONFIG_CRYPTO_MANAGER_DISABLE_TESTS=y -CONFIG_CRYPTO_GF128MUL=m -CONFIG_CRYPTO_NULL=m -CONFIG_CRYPTO_NULL2=y -# CONFIG_CRYPTO_PCRYPT is not set -# CONFIG_CRYPTO_CRYPTD is not set -CONFIG_CRYPTO_AUTHENC=m -# CONFIG_CRYPTO_TEST is not set -CONFIG_CRYPTO_ENGINE=y -# end of Crypto core or helper - -# -# Public-key cryptography -# -CONFIG_CRYPTO_RSA=y -# CONFIG_CRYPTO_DH is not set -# CONFIG_CRYPTO_ECDH is not set -# CONFIG_CRYPTO_ECDSA is not set -# CONFIG_CRYPTO_ECRDSA is not set -# CONFIG_CRYPTO_SM2 is not set -# CONFIG_CRYPTO_CURVE25519 is not set -# end of Public-key cryptography - -# -# Block ciphers -# -CONFIG_CRYPTO_AES=m -# CONFIG_CRYPTO_AES_TI is not set -# CONFIG_CRYPTO_ANUBIS is not set -# CONFIG_CRYPTO_ARIA is not set -# CONFIG_CRYPTO_BLOWFISH is not set -# CONFIG_CRYPTO_CAMELLIA is not set -# CONFIG_CRYPTO_CAST5 is not set -# CONFIG_CRYPTO_CAST6 is not set -# CONFIG_CRYPTO_DES is not set -# CONFIG_CRYPTO_FCRYPT is not set -# CONFIG_CRYPTO_KHAZAD is not set -# CONFIG_CRYPTO_SEED is not set -# CONFIG_CRYPTO_SERPENT is not set -# CONFIG_CRYPTO_SM4_GENERIC is not set -# CONFIG_CRYPTO_TEA is not set -# CONFIG_CRYPTO_TWOFISH is not set -# end of Block ciphers - -# -# Length-preserving ciphers and modes -# -# CONFIG_CRYPTO_ADIANTUM is not set -# CONFIG_CRYPTO_ARC4 is not set -# CONFIG_CRYPTO_CHACHA20 is not set -CONFIG_CRYPTO_CBC=m -# CONFIG_CRYPTO_CFB is not set -CONFIG_CRYPTO_CTR=m -# CONFIG_CRYPTO_CTS is not set -# CONFIG_CRYPTO_ECB is not set -# CONFIG_CRYPTO_HCTR2 is not set -# CONFIG_CRYPTO_KEYWRAP is not set -# CONFIG_CRYPTO_LRW is not set -# CONFIG_CRYPTO_OFB is not set -# CONFIG_CRYPTO_PCBC is not set -# CONFIG_CRYPTO_XTS is not set -# end of Length-preserving ciphers and modes - -# -# AEAD (authenticated encryption with associated data) ciphers -# -# CONFIG_CRYPTO_AEGIS128 is not set -# CONFIG_CRYPTO_CHACHA20POLY1305 is not set -# CONFIG_CRYPTO_CCM is not set -CONFIG_CRYPTO_GCM=m -CONFIG_CRYPTO_SEQIV=m -CONFIG_CRYPTO_ECHAINIV=m -# CONFIG_CRYPTO_ESSIV is not set -# end of AEAD (authenticated encryption with associated data) ciphers - -# -# Hashes, digests, and MACs -# -CONFIG_CRYPTO_BLAKE2B=m -# CONFIG_CRYPTO_CMAC is not set -CONFIG_CRYPTO_GHASH=m -CONFIG_CRYPTO_HMAC=m -# CONFIG_CRYPTO_MD4 is not set -# CONFIG_CRYPTO_MD5 is not set -# CONFIG_CRYPTO_MICHAEL_MIC is not set -# CONFIG_CRYPTO_POLY1305 is not set -# CONFIG_CRYPTO_RMD160 is not set -CONFIG_CRYPTO_SHA1=y -CONFIG_CRYPTO_SHA256=m -CONFIG_CRYPTO_SHA512=m -# CONFIG_CRYPTO_SHA3 is not set -# CONFIG_CRYPTO_SM3_GENERIC is not set -# CONFIG_CRYPTO_STREEBOG is not set -# CONFIG_CRYPTO_VMAC is not set -# CONFIG_CRYPTO_WP512 is not set -# CONFIG_CRYPTO_XCBC is not set -CONFIG_CRYPTO_XXHASH=m -# end of Hashes, digests, and MACs - -# -# CRCs (cyclic redundancy checks) -# -CONFIG_CRYPTO_CRC32C=y -# CONFIG_CRYPTO_CRC32 is not set -# CONFIG_CRYPTO_CRCT10DIF is not set -# end of CRCs (cyclic redundancy checks) - -# -# Compression -# -# CONFIG_CRYPTO_DEFLATE is not set -# CONFIG_CRYPTO_LZO is not set -# CONFIG_CRYPTO_842 is not set -# CONFIG_CRYPTO_LZ4 is not set -# CONFIG_CRYPTO_LZ4HC is not set -# CONFIG_CRYPTO_ZSTD is not set -# end of Compression - -# -# Random number generation -# -# CONFIG_CRYPTO_ANSI_CPRNG is not set -CONFIG_CRYPTO_DRBG_MENU=m -CONFIG_CRYPTO_DRBG_HMAC=y -# CONFIG_CRYPTO_DRBG_HASH is not set -# CONFIG_CRYPTO_DRBG_CTR is not set -CONFIG_CRYPTO_DRBG=m -CONFIG_CRYPTO_JITTERENTROPY=m -# end of Random number generation - -# -# Userspace interface -# -CONFIG_CRYPTO_USER_API=y -CONFIG_CRYPTO_USER_API_HASH=y -# CONFIG_CRYPTO_USER_API_SKCIPHER is not set -# CONFIG_CRYPTO_USER_API_RNG is not set -# CONFIG_CRYPTO_USER_API_AEAD is not set -CONFIG_CRYPTO_USER_API_ENABLE_OBSOLETE=y -# end of Userspace interface - -CONFIG_CRYPTO_HW=y -# CONFIG_CRYPTO_DEV_ATMEL_ECC is not set -# CONFIG_CRYPTO_DEV_ATMEL_SHA204A is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCC is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXX is not set -# CONFIG_CRYPTO_DEV_QAT_C62X is not set -# CONFIG_CRYPTO_DEV_QAT_4XXX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCCVF is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXXVF is not set -# CONFIG_CRYPTO_DEV_QAT_C62XVF is not set -# CONFIG_CRYPTO_DEV_NITROX_CNN55XX is not set -CONFIG_CRYPTO_DEV_VIRTIO=y -# CONFIG_CRYPTO_DEV_SAFEXCEL is not set -# CONFIG_CRYPTO_DEV_CCREE is not set -# CONFIG_CRYPTO_DEV_AMLOGIC_GXL is not set -# CONFIG_ASYMMETRIC_KEY_TYPE is not set - -# -# Certificates for signature checking -# -# CONFIG_SYSTEM_BLACKLIST_KEYRING is not set -# end of Certificates for signature checking - -CONFIG_BINARY_PRINTF=y - -# -# Library routines -# -CONFIG_RAID6_PQ=m -CONFIG_RAID6_PQ_BENCHMARK=y -# CONFIG_PACKING is not set -CONFIG_BITREVERSE=y -CONFIG_GENERIC_STRNCPY_FROM_USER=y -CONFIG_GENERIC_STRNLEN_USER=y -CONFIG_GENERIC_NET_UTILS=y -# CONFIG_CORDIC is not set -# CONFIG_PRIME_NUMBERS is not set -CONFIG_RATIONAL=y -CONFIG_GENERIC_PCI_IOMAP=y - -# -# Crypto library routines -# -CONFIG_CRYPTO_LIB_UTILS=y -CONFIG_CRYPTO_LIB_AES=m -CONFIG_CRYPTO_LIB_BLAKE2S_GENERIC=y -# CONFIG_CRYPTO_LIB_CHACHA is not set -# CONFIG_CRYPTO_LIB_CURVE25519 is not set -CONFIG_CRYPTO_LIB_POLY1305_RSIZE=1 -# CONFIG_CRYPTO_LIB_POLY1305 is not set -# CONFIG_CRYPTO_LIB_CHACHA20POLY1305 is not set -CONFIG_CRYPTO_LIB_SHA1=y -CONFIG_CRYPTO_LIB_SHA256=m -# end of Crypto library routines - -# CONFIG_CRC_CCITT is not set -CONFIG_CRC16=y -# CONFIG_CRC_T10DIF is not set -# CONFIG_CRC64_ROCKSOFT is not set -CONFIG_CRC_ITU_T=y -CONFIG_CRC32=y -# CONFIG_CRC32_SELFTEST is not set -CONFIG_CRC32_SLICEBY8=y -# CONFIG_CRC32_SLICEBY4 is not set -# CONFIG_CRC32_SARWATE is not set -# CONFIG_CRC32_BIT is not set -# CONFIG_CRC64 is not set -# CONFIG_CRC4 is not set -CONFIG_CRC7=y -CONFIG_LIBCRC32C=m -# CONFIG_CRC8 is not set -CONFIG_XXHASH=y -CONFIG_AUDIT_GENERIC=y -# CONFIG_RANDOM32_SELFTEST is not set -CONFIG_ZLIB_INFLATE=y -CONFIG_ZLIB_DEFLATE=y -CONFIG_LZO_COMPRESS=m -CONFIG_LZO_DECOMPRESS=y -CONFIG_LZ4_DECOMPRESS=y -CONFIG_ZSTD_COMMON=y -CONFIG_ZSTD_COMPRESS=m -CONFIG_ZSTD_DECOMPRESS=y -CONFIG_XZ_DEC=y -CONFIG_XZ_DEC_X86=y -CONFIG_XZ_DEC_POWERPC=y -CONFIG_XZ_DEC_IA64=y -CONFIG_XZ_DEC_ARM=y -CONFIG_XZ_DEC_ARMTHUMB=y -CONFIG_XZ_DEC_SPARC=y -# CONFIG_XZ_DEC_MICROLZMA is not set -CONFIG_XZ_DEC_BCJ=y -# CONFIG_XZ_DEC_TEST is not set -CONFIG_DECOMPRESS_GZIP=y -CONFIG_DECOMPRESS_BZIP2=y -CONFIG_DECOMPRESS_LZMA=y -CONFIG_DECOMPRESS_XZ=y -CONFIG_DECOMPRESS_LZO=y -CONFIG_DECOMPRESS_LZ4=y -CONFIG_DECOMPRESS_ZSTD=y -CONFIG_GENERIC_ALLOCATOR=y -CONFIG_INTERVAL_TREE=y -CONFIG_ASSOCIATIVE_ARRAY=y -CONFIG_HAS_IOMEM=y -CONFIG_HAS_IOPORT_MAP=y -CONFIG_HAS_DMA=y -CONFIG_NEED_DMA_MAP_STATE=y -CONFIG_ARCH_DMA_ADDR_T_64BIT=y -CONFIG_DMA_DECLARE_COHERENT=y -CONFIG_ARCH_HAS_SETUP_DMA_OPS=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_DEVICE=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_CPU=y -CONFIG_ARCH_HAS_DMA_PREP_COHERENT=y -CONFIG_SWIOTLB=y -# CONFIG_DMA_RESTRICTED_POOL is not set -CONFIG_DMA_NONCOHERENT_MMAP=y -CONFIG_DMA_COHERENT_POOL=y -CONFIG_DMA_DIRECT_REMAP=y -# CONFIG_DMA_API_DEBUG is not set -# CONFIG_DMA_MAP_BENCHMARK is not set -CONFIG_SGL_ALLOC=y -# CONFIG_CPUMASK_OFFSTACK is not set -# CONFIG_FORCE_NR_CPUS is not set -CONFIG_CPU_RMAP=y -CONFIG_DQL=y -CONFIG_GLOB=y -# CONFIG_GLOB_SELFTEST is not set -CONFIG_NLATTR=y -CONFIG_CLZ_TAB=y -# CONFIG_IRQ_POLL is not set -CONFIG_MPILIB=y -CONFIG_LIBFDT=y -CONFIG_OID_REGISTRY=y -CONFIG_UCS2_STRING=y -CONFIG_HAVE_GENERIC_VDSO=y -CONFIG_GENERIC_GETTIMEOFDAY=y -CONFIG_GENERIC_VDSO_TIME_NS=y -CONFIG_FONT_SUPPORT=y -# CONFIG_FONTS is not set -CONFIG_FONT_8x8=y -CONFIG_FONT_8x16=y -CONFIG_SG_POOL=y -CONFIG_ARCH_STACKWALK=y -CONFIG_STACKDEPOT=y -CONFIG_SBITMAP=y -# end of Library routines - -CONFIG_GENERIC_IOREMAP=y -CONFIG_GENERIC_LIB_DEVMEM_IS_ALLOWED=y - -# -# Kernel hacking -# - -# -# printk and dmesg options -# -CONFIG_PRINTK_TIME=y -# CONFIG_PRINTK_CALLER is not set -# CONFIG_STACKTRACE_BUILD_ID is not set -CONFIG_CONSOLE_LOGLEVEL_DEFAULT=7 -CONFIG_CONSOLE_LOGLEVEL_QUIET=4 -CONFIG_MESSAGE_LOGLEVEL_DEFAULT=4 -# CONFIG_BOOT_PRINTK_DELAY is not set -# CONFIG_DYNAMIC_DEBUG is not set -# CONFIG_DYNAMIC_DEBUG_CORE is not set -CONFIG_SYMBOLIC_ERRNAME=y -CONFIG_DEBUG_BUGVERBOSE=y -# end of printk and dmesg options - -CONFIG_DEBUG_KERNEL=y -CONFIG_DEBUG_MISC=y - -# -# Compile-time checks and compiler options -# -CONFIG_DEBUG_INFO_NONE=y -# CONFIG_DEBUG_INFO_DWARF_TOOLCHAIN_DEFAULT is not set -# CONFIG_DEBUG_INFO_DWARF4 is not set -# CONFIG_DEBUG_INFO_DWARF5 is not set -CONFIG_FRAME_WARN=2048 -# CONFIG_STRIP_ASM_SYMS is not set -# CONFIG_READABLE_ASM is not set -# CONFIG_HEADERS_INSTALL is not set -# CONFIG_DEBUG_SECTION_MISMATCH is not set -CONFIG_SECTION_MISMATCH_WARN_ONLY=y -CONFIG_ARCH_WANT_FRAME_POINTERS=y -CONFIG_FRAME_POINTER=y -# CONFIG_VMLINUX_MAP is not set -# CONFIG_DEBUG_FORCE_WEAK_PER_CPU is not set -# end of Compile-time checks and compiler options - -# -# Generic Kernel Debugging Instruments -# -# CONFIG_MAGIC_SYSRQ is not set -CONFIG_DEBUG_FS=y -CONFIG_DEBUG_FS_ALLOW_ALL=y -# CONFIG_DEBUG_FS_DISALLOW_MOUNT is not set -# CONFIG_DEBUG_FS_ALLOW_NONE is not set -CONFIG_HAVE_ARCH_KGDB=y -CONFIG_HAVE_ARCH_KGDB_QXFER_PKT=y -# CONFIG_KGDB is not set -CONFIG_ARCH_HAS_UBSAN_SANITIZE_ALL=y -# CONFIG_UBSAN is not set -CONFIG_HAVE_KCSAN_COMPILER=y -# end of Generic Kernel Debugging Instruments - -# -# Networking Debugging -# -# CONFIG_NET_DEV_REFCNT_TRACKER is not set -# CONFIG_NET_NS_REFCNT_TRACKER is not set -# CONFIG_DEBUG_NET is not set -# end of Networking Debugging - -# -# Memory Debugging -# -# CONFIG_PAGE_EXTENSION is not set -CONFIG_DEBUG_PAGEALLOC=y -# CONFIG_DEBUG_PAGEALLOC_ENABLE_DEFAULT is not set -CONFIG_SLUB_DEBUG=y -# CONFIG_SLUB_DEBUG_ON is not set -# CONFIG_PAGE_OWNER is not set -# CONFIG_PAGE_POISONING is not set -# CONFIG_DEBUG_RODATA_TEST is not set -CONFIG_ARCH_HAS_DEBUG_WX=y -# CONFIG_DEBUG_WX is not set -CONFIG_GENERIC_PTDUMP=y -# CONFIG_PTDUMP_DEBUGFS is not set -# CONFIG_DEBUG_OBJECTS is not set -# CONFIG_SHRINKER_DEBUG is not set -CONFIG_HAVE_DEBUG_KMEMLEAK=y -# CONFIG_DEBUG_KMEMLEAK is not set -# CONFIG_DEBUG_STACK_USAGE is not set -CONFIG_SCHED_STACK_END_CHECK=y -CONFIG_ARCH_HAS_DEBUG_VM_PGTABLE=y -CONFIG_DEBUG_VM_IRQSOFF=y -CONFIG_DEBUG_VM=y -# CONFIG_DEBUG_VM_MAPLE_TREE is not set -# CONFIG_DEBUG_VM_RB is not set -CONFIG_DEBUG_VM_PGFLAGS=y -CONFIG_DEBUG_VM_PGTABLE=y -CONFIG_ARCH_HAS_DEBUG_VIRTUAL=y -# CONFIG_DEBUG_VIRTUAL is not set -CONFIG_DEBUG_MEMORY_INIT=y -CONFIG_DEBUG_PER_CPU_MAPS=y -CONFIG_HAVE_ARCH_KASAN=y -CONFIG_HAVE_ARCH_KASAN_VMALLOC=y -CONFIG_CC_HAS_KASAN_GENERIC=y -CONFIG_CC_HAS_WORKING_NOSANITIZE_ADDRESS=y -# CONFIG_KASAN is not set -CONFIG_HAVE_ARCH_KFENCE=y -# CONFIG_KFENCE is not set -# end of Memory Debugging - -# CONFIG_DEBUG_SHIRQ is not set - -# -# Debug Oops, Lockups and Hangs -# -# CONFIG_PANIC_ON_OOPS is not set -CONFIG_PANIC_ON_OOPS_VALUE=0 -CONFIG_PANIC_TIMEOUT=0 -CONFIG_LOCKUP_DETECTOR=y -CONFIG_SOFTLOCKUP_DETECTOR=y -# CONFIG_BOOTPARAM_SOFTLOCKUP_PANIC is not set -CONFIG_DETECT_HUNG_TASK=y -CONFIG_DEFAULT_HUNG_TASK_TIMEOUT=120 -# CONFIG_BOOTPARAM_HUNG_TASK_PANIC is not set -CONFIG_WQ_WATCHDOG=y -# CONFIG_TEST_LOCKUP is not set -# end of Debug Oops, Lockups and Hangs - -# -# Scheduler Debugging -# -CONFIG_SCHED_DEBUG=y -# CONFIG_SCHEDSTATS is not set -# end of Scheduler Debugging - -CONFIG_DEBUG_TIMEKEEPING=y - -# -# Lock Debugging (spinlocks, mutexes, etc...) -# -CONFIG_LOCK_DEBUGGING_SUPPORT=y -# CONFIG_PROVE_LOCKING is not set -# CONFIG_LOCK_STAT is not set -CONFIG_DEBUG_RT_MUTEXES=y -CONFIG_DEBUG_SPINLOCK=y -CONFIG_DEBUG_MUTEXES=y -# CONFIG_DEBUG_WW_MUTEX_SLOWPATH is not set -CONFIG_DEBUG_RWSEMS=y -# CONFIG_DEBUG_LOCK_ALLOC is not set -CONFIG_DEBUG_ATOMIC_SLEEP=y -# CONFIG_DEBUG_LOCKING_API_SELFTESTS is not set -# CONFIG_LOCK_TORTURE_TEST is not set -# CONFIG_WW_MUTEX_SELFTEST is not set -# CONFIG_SCF_TORTURE_TEST is not set -# CONFIG_CSD_LOCK_WAIT_DEBUG is not set -# end of Lock Debugging (spinlocks, mutexes, etc...) - -# CONFIG_DEBUG_IRQFLAGS is not set -CONFIG_STACKTRACE=y -# CONFIG_WARN_ALL_UNSEEDED_RANDOM is not set -# CONFIG_DEBUG_KOBJECT is not set - -# -# Debug kernel data structures -# -CONFIG_DEBUG_LIST=y -CONFIG_DEBUG_PLIST=y -CONFIG_DEBUG_SG=y -# CONFIG_DEBUG_NOTIFIERS is not set -# CONFIG_BUG_ON_DATA_CORRUPTION is not set -# CONFIG_DEBUG_MAPLE_TREE is not set -# end of Debug kernel data structures - -# CONFIG_DEBUG_CREDENTIALS is not set - -# -# RCU Debugging -# -# CONFIG_RCU_SCALE_TEST is not set -# CONFIG_RCU_TORTURE_TEST is not set -# CONFIG_RCU_REF_SCALE_TEST is not set -CONFIG_RCU_CPU_STALL_TIMEOUT=21 -CONFIG_RCU_EXP_CPU_STALL_TIMEOUT=0 -# CONFIG_RCU_TRACE is not set -CONFIG_RCU_EQS_DEBUG=y -# end of RCU Debugging - -# CONFIG_DEBUG_WQ_FORCE_RR_CPU is not set -# CONFIG_CPU_HOTPLUG_STATE_CONTROL is not set -# CONFIG_LATENCYTOP is not set -CONFIG_HAVE_FUNCTION_TRACER=y -CONFIG_HAVE_FUNCTION_GRAPH_TRACER=y -CONFIG_HAVE_DYNAMIC_FTRACE=y -CONFIG_HAVE_DYNAMIC_FTRACE_WITH_REGS=y -CONFIG_HAVE_FTRACE_MCOUNT_RECORD=y -CONFIG_HAVE_SYSCALL_TRACEPOINTS=y -CONFIG_TRACING_SUPPORT=y -# CONFIG_FTRACE is not set -# CONFIG_SAMPLES is not set -# CONFIG_STRICT_DEVMEM is not set - -# -# riscv Debugging -# -# end of riscv Debugging - -# -# Kernel Testing and Coverage -# -# CONFIG_KUNIT is not set -# CONFIG_NOTIFIER_ERROR_INJECTION is not set -# CONFIG_FAULT_INJECTION is not set -CONFIG_ARCH_HAS_KCOV=y -CONFIG_CC_HAS_SANCOV_TRACE_PC=y -# CONFIG_KCOV is not set -# CONFIG_RUNTIME_TESTING_MENU is not set -CONFIG_ARCH_USE_MEMTEST=y -CONFIG_MEMTEST=y -# end of Kernel Testing and Coverage - -# -# Rust hacking -# -# end of Rust hacking -# end of Kernel hacking diff --git a/patches/linux/linux-6.1.y/dts/mpfs-beaglev-fire-fabric.dtsi b/patches/linux/linux-6.1.y/dts/mpfs-beaglev-fire-fabric.dtsi deleted file mode 100644 index 5d3e524..0000000 --- a/patches/linux/linux-6.1.y/dts/mpfs-beaglev-fire-fabric.dtsi +++ /dev/null @@ -1,70 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/ { - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs-icicle-kit", - "microchip,mpfs"; - - core_pwm0: pwm@40000000 { - compatible = "microchip,corepwm-rtl-v4"; - reg = <0x0 0x40000000 0x0 0xF0>; - microchip,sync-update-mask = /bits/ 32 <0>; - #pwm-cells = <3>; - clocks = <&fabric_clk3>; - status = "disabled"; - }; - - i2c2: i2c@40000200 { - compatible = "microchip,corei2c-rtl-v7"; - reg = <0x0 0x40000200 0x0 0x100>; - #address-cells = <1>; - #size-cells = <0>; - clocks = <&fabric_clk3>; - interrupt-parent = <&plic>; - interrupts = <122>; - clock-frequency = <100000>; - status = "disabled"; - }; - - fabric_clk3: fabric-clk3 { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <50000000>; - }; - - fabric_clk1: fabric-clk1 { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <125000000>; - }; - - pcie: pcie@3000000000 { - compatible = "microchip,pcie-host-1.0"; - #address-cells = <0x3>; - #interrupt-cells = <0x1>; - #size-cells = <0x2>; - device_type = "pci"; - reg = <0x30 0x0 0x0 0x8000000>, <0x0 0x43000000 0x0 0x10000>; - reg-names = "cfg", "apb"; - bus-range = <0x0 0x7f>; - interrupt-parent = <&plic>; - interrupts = <119>; - interrupt-map = <0 0 0 1 &pcie_intc 0>, - <0 0 0 2 &pcie_intc 1>, - <0 0 0 3 &pcie_intc 2>, - <0 0 0 4 &pcie_intc 3>; - interrupt-map-mask = <0 0 0 7>; - clocks = <&fabric_clk1>, <&fabric_clk3>; - clock-names = "fic1", "fic3"; - ranges = <0x3000000 0x0 0x8000000 0x30 0x8000000 0x0 0x80000000>; - dma-ranges = <0x02000000 0x0 0x00000000 0x0 0x00000000 0x1 0x00000000>; - msi-parent = <&pcie>; - msi-controller; - status = "disabled"; - pcie_intc: interrupt-controller { - #address-cells = <0>; - #interrupt-cells = <1>; - interrupt-controller; - }; - }; -}; diff --git a/patches/linux/linux-6.1.y/dts/mpfs-beaglev-fire.dts b/patches/linux/linux-6.1.y/dts/mpfs-beaglev-fire.dts deleted file mode 100644 index 7c195f8..0000000 --- a/patches/linux/linux-6.1.y/dts/mpfs-beaglev-fire.dts +++ /dev/null @@ -1,319 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/dts-v1/; - -#include "mpfs.dtsi" -#include "mpfs-beaglev-fire-fabric.dtsi" -#include -#include - -/* Clock frequency (in Hz) of the rtcclk */ -#define RTCCLK_FREQ 1000000 - -/ { - #address-cells = <2>; - #size-cells = <2>; - model = "BeagleBoard BeagleV-Fire"; - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs"; - - aliases { - mmc0 = &mmc; - ethernet0 = &mac1; - serial0 = &mmuart0; - serial1 = &mmuart1; - serial2 = &mmuart2; - serial3 = &mmuart3; - serial4 = &mmuart4; - }; - - chosen { - stdout-path = "serial0:115200n8"; - }; - - cpus { - timebase-frequency = ; - }; - - ddrc_cache_lo: memory@80000000 { - device_type = "memory"; - reg = <0x0 0x80000000 0x0 0x40000000>; - status = "okay"; - }; - - ddrc_cache_hi: memory@1040000000 { - device_type = "memory"; - reg = <0x10 0x40000000 0x0 0x40000000>; - status = "okay"; - }; - - reserved-memory { - #address-cells = <2>; - #size-cells = <2>; - ranges; - - hss_payload: region@BFC00000 { - reg = <0x0 0xBFC00000 0x0 0x400000>; - no-map; - }; - }; - - imx219_vana: fixedregulator@0 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vana"; - regulator-min-microvolt = <2800000>; - regulator-max-microvolt = <2800000>; - }; - imx219_vdig: fixedregulator@1 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vdig"; - regulator-min-microvolt = <1800000>; - regulator-max-microvolt = <1800000>; - }; - imx219_vddl: fixedregulator@2 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vddl"; - regulator-min-microvolt = <1200000>; - regulator-max-microvolt = <1200000>; - }; - - imx219_clk: camera-clk { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <24000000>; - }; -}; - -&gpio0 { - ngpios=<14>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", "", "", "SD_CARD_CS", "USER_BUTTON"; - status = "okay"; - - sd_card_cs { - gpio-hog; - gpios = <12 12>; - output_high; - line-name = "SD_CARD_CS"; - }; - - user_button { - gpio-hog; - gpios = <13 13>; - input; - line-name = "USER_BUTTON"; - }; -}; - -&gpio1 { - ngpios=<24>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", - "", "", "", "", "", "", "", "", "", "", - "ADC_IRQn", "", "", "USB_OCn"; - status = "okay"; - - adc_irqn { - gpio-hog; - gpios = <20 20>; - input; - line-name = "ADC_IRQn"; - }; - - user_button { - gpio-hog; - gpios = <23 23>; - input; - line-name = "USB_OCn"; - }; - -}; - -&gpio2 { - interrupts = <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>; - gpio-line-names = "P8_PIN3_USER_LED_0", "P8_PIN4_USER_LED_1", "P8_PIN5_USER_LED_2", - "P8_PIN6_USER_LED_3", "P8_PIN7_USER_LED_4", "P8_PIN8_USER_LED_5", - "P8_PIN9_USER_LED_6", "P8_PIN10_USER_LED_7", "P8_PIN11_USER_LED_8", - "P8_PIN12_USER_LED_9", "P8_PIN13_USER_LED_10", "P8_PIN14_USER_LED_11", - "P8_PIN15", "P8_PIN16", "P8_PIN17", "P8_PIN18", "P8_PIN19", - "P8_PIN20", "P8_PIN21", "P8_PIN22", "P8_PIN23", "P8_PIN24", - "P8_PIN25", "P8_PIN26", "P8_PIN27", "P8_PIN28", "P8_PIN29", - "P8_PIN30", - "M2_W_DISABLE1", "M2_W_DISABLE2", - "VIO_ENABLE", "SD_DET"; - status = "okay"; - - vio_enable { - gpio-hog; - gpios = <30 30>; - output_high; - line-name = "VIO_ENABLE"; - }; - - sd_det { - gpio-hog; - gpios = <31 31>; - input; - line-name = "SD_DET"; - }; -}; - -&i2c0 { - status = "okay"; -}; - -&i2c1 { - status = "okay"; - eeprom: eeprom@50 { - compatible = "at,24c32"; - reg = <0x50>; - }; - - imx219: sensor@10 { - compatible = "sony,imx219"; - reg = <0x10>; - clocks = <&imx219_clk>; - VANA-supply = <&imx219_vana>; /* 2.8v */ - VDIG-supply = <&imx219_vdig>; /* 1.8v */ - VDDL-supply = <&imx219_vddl>; /* 1.2v */ - - port { - imx219_0: endpoint { -// remote-endpoint = <&csi1_ep>; - data-lanes = <1 2>; - clock-noncontinuous; - link-frequencies = /bits/ 64 <456000000>; - }; - }; - }; -}; - -&mac0 { - phy-mode = "sgmii"; - phy-handle = <&phy0>; - status = "okay"; - - phy0: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mac1 { - phy-mode = "sgmii"; - phy-handle = <&phy1>; - status = "okay"; - - phy1: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mbox { - status = "okay"; -}; - -//&mmc { -// status = "okay"; -// bus-width = <8>; -// disable-wp; -// cap-mmc-highspeed; -// mmc-ddr-1_8v; -// mmc-hs200-1_8v; -//}; - -&mmc { - //dma-noncoherent; - bus-width = <4>; - disable-wp; - cap-sd-highspeed; - cap-mmc-highspeed; - mmc-ddr-1_8v; - mmc-hs200-1_8v; - sd-uhs-sdr12; - sd-uhs-sdr25; - sd-uhs-sdr50; - sd-uhs-sdr104; - status = "okay"; -}; - - -&mmuart0 { - status = "okay"; -}; - -&mmuart1 { - status = "okay"; -}; - -//&mmuart2 { -// status = "okay"; -//}; - -//&mmuart3 //{ -// statu//s = "okay"; -//};// -// -//&mmuart4 { -// status = "okay"; -//}; - -//&pcie { -// status = "okay"; -//}; - -&qspi { - status = "okay"; - cs-gpios = <&gpio1 17 GPIO_ACTIVE_LOW>, <&gpio0 12 GPIO_ACTIVE_LOW>; - num-cs = <2>; - - - mcp3464: mcp3464@0 { - compatible = "microchip,mcp3464r"; - reg = <0>; /* CE0 */ - spi-cpol; - spi-cpha; - spi-max-frequency = <15000000>; - status = "okay"; - microchip,hw-device-address = <1>; - }; - - mmc-slot@1 { - compatible = "mmc-spi-slot"; - reg = <1>; - gpios = <&gpio2 31 1>; - voltage-ranges = <3300 3300>; - spi-max-frequency = <15000000>; - disable-wp; - }; -}; - -&refclk { - clock-frequency = <125000000>; -}; - -&rtc { - status = "okay"; -}; - -&spi0 { - status = "okay"; -}; - -&spi1 { - status = "okay"; -}; - -&syscontroller { - status = "okay"; -}; - -&usb { - //dma-noncoherent; - status = "okay"; - dr_mode = "otg"; -}; diff --git a/patches/linux/linux-6.2.y/Makefile b/patches/linux/linux-6.2.y/Makefile deleted file mode 100644 index 7042363..0000000 --- a/patches/linux/linux-6.2.y/Makefile +++ /dev/null @@ -1,7 +0,0 @@ -# SPDX-License-Identifier: GPL-2.0 -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-icicle-kit.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-m100pfsevp.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-polarberry.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-sev-kit.dtb -dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-beaglev-fire.dtb -obj-$(CONFIG_BUILTIN_DTB) += $(addsuffix .o, $(dtb-y)) diff --git a/patches/linux/linux-6.2.y/defconfig b/patches/linux/linux-6.2.y/defconfig deleted file mode 100644 index 0d43b6e..0000000 --- a/patches/linux/linux-6.2.y/defconfig +++ /dev/null @@ -1,5246 +0,0 @@ -# -# Automatically generated file; DO NOT EDIT. -# Linux/riscv 6.2.16 Kernel Configuration -# -CONFIG_CC_VERSION_TEXT="riscv64-linux-gcc (GCC) 11.4.0" -CONFIG_CC_IS_GCC=y -CONFIG_GCC_VERSION=110400 -CONFIG_CLANG_VERSION=0 -CONFIG_AS_IS_GNU=y -CONFIG_AS_VERSION=24000 -CONFIG_LD_IS_BFD=y -CONFIG_LD_VERSION=24000 -CONFIG_LLD_VERSION=0 -CONFIG_CC_HAS_ASM_GOTO_OUTPUT=y -CONFIG_CC_HAS_ASM_GOTO_TIED_OUTPUT=y -CONFIG_CC_HAS_ASM_INLINE=y -CONFIG_CC_HAS_NO_PROFILE_FN_ATTR=y -CONFIG_PAHOLE_VERSION=0 -CONFIG_IRQ_WORK=y -CONFIG_BUILDTIME_TABLE_SORT=y -CONFIG_THREAD_INFO_IN_TASK=y - -# -# General setup -# -CONFIG_INIT_ENV_ARG_LIMIT=32 -# CONFIG_COMPILE_TEST is not set -# CONFIG_WERROR is not set -CONFIG_LOCALVERSION="" -CONFIG_LOCALVERSION_AUTO=y -CONFIG_BUILD_SALT="" -CONFIG_DEFAULT_INIT="" -CONFIG_DEFAULT_HOSTNAME="(none)" -CONFIG_SYSVIPC=y -CONFIG_SYSVIPC_SYSCTL=y -CONFIG_SYSVIPC_COMPAT=y -CONFIG_POSIX_MQUEUE=y -CONFIG_POSIX_MQUEUE_SYSCTL=y -# CONFIG_WATCH_QUEUE is not set -CONFIG_CROSS_MEMORY_ATTACH=y -# CONFIG_USELIB is not set -CONFIG_AUDIT=y -CONFIG_HAVE_ARCH_AUDITSYSCALL=y -CONFIG_AUDITSYSCALL=y - -# -# IRQ subsystem -# -CONFIG_GENERIC_IRQ_SHOW=y -CONFIG_GENERIC_IRQ_SHOW_LEVEL=y -CONFIG_GENERIC_IRQ_EFFECTIVE_AFF_MASK=y -CONFIG_GENERIC_IRQ_MIGRATION=y -CONFIG_HARDIRQS_SW_RESEND=y -CONFIG_GENERIC_IRQ_CHIP=y -CONFIG_IRQ_DOMAIN=y -CONFIG_IRQ_DOMAIN_HIERARCHY=y -CONFIG_GENERIC_MSI_IRQ=y -CONFIG_IRQ_FORCED_THREADING=y -CONFIG_SPARSE_IRQ=y -# CONFIG_GENERIC_IRQ_DEBUGFS is not set -# end of IRQ subsystem - -CONFIG_GENERIC_IRQ_MULTI_HANDLER=y -CONFIG_ARCH_CLOCKSOURCE_INIT=y -CONFIG_GENERIC_TIME_VSYSCALL=y -CONFIG_GENERIC_CLOCKEVENTS=y -CONFIG_ARCH_HAS_TICK_BROADCAST=y -CONFIG_GENERIC_CLOCKEVENTS_BROADCAST=y -CONFIG_HAVE_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_CONTEXT_TRACKING=y -CONFIG_CONTEXT_TRACKING_IDLE=y - -# -# Timers subsystem -# -CONFIG_TICK_ONESHOT=y -CONFIG_NO_HZ_COMMON=y -# CONFIG_HZ_PERIODIC is not set -CONFIG_NO_HZ_IDLE=y -# CONFIG_NO_HZ_FULL is not set -# CONFIG_NO_HZ is not set -CONFIG_HIGH_RES_TIMERS=y -# end of Timers subsystem - -CONFIG_BPF=y -CONFIG_HAVE_EBPF_JIT=y - -# -# BPF subsystem -# -CONFIG_BPF_SYSCALL=y -# CONFIG_BPF_JIT is not set -CONFIG_BPF_UNPRIV_DEFAULT_OFF=y -# CONFIG_BPF_PRELOAD is not set -# end of BPF subsystem - -CONFIG_PREEMPT_NONE_BUILD=y -CONFIG_PREEMPT_NONE=y -# CONFIG_PREEMPT_VOLUNTARY is not set -# CONFIG_PREEMPT is not set -CONFIG_PREEMPT_COUNT=y - -# -# CPU/Task time and stats accounting -# -CONFIG_TICK_CPU_ACCOUNTING=y -# CONFIG_VIRT_CPU_ACCOUNTING_GEN is not set -# CONFIG_IRQ_TIME_ACCOUNTING is not set -# CONFIG_BSD_PROCESS_ACCT is not set -# CONFIG_TASKSTATS is not set -# CONFIG_PSI is not set -# end of CPU/Task time and stats accounting - -CONFIG_CPU_ISOLATION=y - -# -# RCU Subsystem -# -CONFIG_TREE_RCU=y -# CONFIG_RCU_EXPERT is not set -CONFIG_SRCU=y -CONFIG_TREE_SRCU=y -CONFIG_TASKS_RCU_GENERIC=y -CONFIG_TASKS_TRACE_RCU=y -CONFIG_RCU_STALL_COMMON=y -CONFIG_RCU_NEED_SEGCBLIST=y -# end of RCU Subsystem - -CONFIG_IKCONFIG=y -CONFIG_IKCONFIG_PROC=y -# CONFIG_IKHEADERS is not set -CONFIG_LOG_BUF_SHIFT=17 -CONFIG_LOG_CPU_MAX_BUF_SHIFT=12 -CONFIG_PRINTK_SAFE_LOG_BUF_SHIFT=13 -# CONFIG_PRINTK_INDEX is not set -CONFIG_GENERIC_SCHED_CLOCK=y - -# -# Scheduler features -# -# end of Scheduler features - -CONFIG_CC_HAS_INT128=y -CONFIG_CC_IMPLICIT_FALLTHROUGH="-Wimplicit-fallthrough=5" -CONFIG_GCC11_NO_ARRAY_BOUNDS=y -CONFIG_CC_NO_ARRAY_BOUNDS=y -CONFIG_ARCH_SUPPORTS_INT128=y -CONFIG_CGROUPS=y -CONFIG_PAGE_COUNTER=y -# CONFIG_CGROUP_FAVOR_DYNMODS is not set -CONFIG_MEMCG=y -CONFIG_MEMCG_KMEM=y -# CONFIG_BLK_CGROUP is not set -CONFIG_CGROUP_SCHED=y -CONFIG_FAIR_GROUP_SCHED=y -CONFIG_CFS_BANDWIDTH=y -CONFIG_RT_GROUP_SCHED=y -CONFIG_CGROUP_PIDS=y -# CONFIG_CGROUP_RDMA is not set -CONFIG_CGROUP_FREEZER=y -CONFIG_CGROUP_HUGETLB=y -CONFIG_CPUSETS=y -CONFIG_PROC_PID_CPUSET=y -CONFIG_CGROUP_DEVICE=y -CONFIG_CGROUP_CPUACCT=y -CONFIG_CGROUP_PERF=y -CONFIG_CGROUP_BPF=y -# CONFIG_CGROUP_MISC is not set -# CONFIG_CGROUP_DEBUG is not set -CONFIG_SOCK_CGROUP_DATA=y -CONFIG_NAMESPACES=y -CONFIG_UTS_NS=y -CONFIG_TIME_NS=y -CONFIG_IPC_NS=y -CONFIG_USER_NS=y -CONFIG_PID_NS=y -CONFIG_NET_NS=y -CONFIG_CHECKPOINT_RESTORE=y -# CONFIG_SCHED_AUTOGROUP is not set -# CONFIG_SYSFS_DEPRECATED is not set -# CONFIG_RELAY is not set -CONFIG_BLK_DEV_INITRD=y -CONFIG_INITRAMFS_SOURCE="" -CONFIG_RD_GZIP=y -CONFIG_RD_BZIP2=y -CONFIG_RD_LZMA=y -CONFIG_RD_XZ=y -CONFIG_RD_LZO=y -CONFIG_RD_LZ4=y -CONFIG_RD_ZSTD=y -# CONFIG_BOOT_CONFIG is not set -CONFIG_INITRAMFS_PRESERVE_MTIME=y -CONFIG_CC_OPTIMIZE_FOR_PERFORMANCE=y -# CONFIG_CC_OPTIMIZE_FOR_SIZE is not set -CONFIG_SYSCTL=y -CONFIG_SYSCTL_EXCEPTION_TRACE=y -CONFIG_EXPERT=y -CONFIG_MULTIUSER=y -# CONFIG_SGETMASK_SYSCALL is not set -# CONFIG_SYSFS_SYSCALL is not set -CONFIG_FHANDLE=y -CONFIG_POSIX_TIMERS=y -CONFIG_PRINTK=y -CONFIG_BUG=y -CONFIG_ELF_CORE=y -CONFIG_BASE_FULL=y -CONFIG_FUTEX=y -CONFIG_FUTEX_PI=y -CONFIG_EPOLL=y -CONFIG_SIGNALFD=y -CONFIG_TIMERFD=y -CONFIG_EVENTFD=y -CONFIG_SHMEM=y -CONFIG_AIO=y -CONFIG_IO_URING=y -CONFIG_ADVISE_SYSCALLS=y -CONFIG_MEMBARRIER=y -CONFIG_KALLSYMS=y -# CONFIG_KALLSYMS_SELFTEST is not set -# CONFIG_KALLSYMS_ALL is not set -CONFIG_KALLSYMS_BASE_RELATIVE=y -CONFIG_KCMP=y -CONFIG_RSEQ=y -# CONFIG_DEBUG_RSEQ is not set -# CONFIG_EMBEDDED is not set -CONFIG_HAVE_PERF_EVENTS=y -# CONFIG_PC104 is not set - -# -# Kernel Performance Events And Counters -# -CONFIG_PERF_EVENTS=y -# CONFIG_DEBUG_PERF_USE_VMALLOC is not set -# end of Kernel Performance Events And Counters - -CONFIG_PROFILING=y -# end of General setup - -CONFIG_64BIT=y -CONFIG_RISCV=y -CONFIG_ARCH_MMAP_RND_BITS_MIN=18 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MIN=8 -CONFIG_ARCH_MMAP_RND_BITS_MAX=24 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MAX=17 -CONFIG_RISCV_SBI=y -CONFIG_MMU=y -CONFIG_PAGE_OFFSET=0xff60000000000000 -CONFIG_ARCH_FLATMEM_ENABLE=y -CONFIG_ARCH_SPARSEMEM_ENABLE=y -CONFIG_ARCH_SELECT_MEMORY_MODEL=y -CONFIG_ARCH_SUPPORTS_UPROBES=y -CONFIG_STACKTRACE_SUPPORT=y -CONFIG_GENERIC_BUG=y -CONFIG_GENERIC_BUG_RELATIVE_POINTERS=y -CONFIG_GENERIC_CALIBRATE_DELAY=y -CONFIG_GENERIC_CSUM=y -CONFIG_GENERIC_HWEIGHT=y -CONFIG_FIX_EARLYCON_MEM=y -CONFIG_PGTABLE_LEVELS=5 -CONFIG_LOCKDEP_SUPPORT=y -CONFIG_RISCV_DMA_NONCOHERENT=y -CONFIG_AS_HAS_INSN=y - -# -# SoC selection -# -CONFIG_SOC_MICROCHIP_POLARFIRE=y -CONFIG_ARCH_RENESAS=y -CONFIG_SOC_SIFIVE=y -CONFIG_SOC_STARFIVE=y -CONFIG_SOC_VIRT=y -# end of SoC selection - -# -# CPU errata selection -# -CONFIG_ERRATA_SIFIVE=y -CONFIG_ERRATA_SIFIVE_CIP_453=y -CONFIG_ERRATA_SIFIVE_CIP_1200=y -# CONFIG_ERRATA_THEAD is not set -# end of CPU errata selection - -# -# Platform type -# -# CONFIG_NONPORTABLE is not set -CONFIG_ARCH_RV64I=y -# CONFIG_CMODEL_MEDLOW is not set -CONFIG_CMODEL_MEDANY=y -CONFIG_MODULE_SECTIONS=y -CONFIG_SMP=y -CONFIG_NR_CPUS=64 -CONFIG_HOTPLUG_CPU=y -CONFIG_TUNE_GENERIC=y -# CONFIG_NUMA is not set -CONFIG_RISCV_ALTERNATIVE=y -CONFIG_RISCV_ISA_C=y -CONFIG_RISCV_ISA_SVPBMT=y -CONFIG_TOOLCHAIN_HAS_ZICBOM=y -CONFIG_RISCV_ISA_ZICBOM=y -CONFIG_TOOLCHAIN_HAS_ZIHINTPAUSE=y -CONFIG_TOOLCHAIN_NEEDS_EXPLICIT_ZICSR_ZIFENCEI=y -CONFIG_FPU=y -# end of Platform type - -# -# Kernel features -# -# CONFIG_HZ_100 is not set -CONFIG_HZ_250=y -# CONFIG_HZ_300 is not set -# CONFIG_HZ_1000 is not set -CONFIG_HZ=250 -CONFIG_SCHED_HRTICK=y -# CONFIG_RISCV_SBI_V01 is not set -# CONFIG_RISCV_BOOT_SPINWAIT is not set -# CONFIG_KEXEC is not set -# CONFIG_KEXEC_FILE is not set -# CONFIG_CRASH_DUMP is not set -CONFIG_COMPAT=y -# end of Kernel features - -# -# Boot options -# -CONFIG_CMDLINE="" -CONFIG_EFI_STUB=y -CONFIG_EFI=y -CONFIG_CC_HAVE_STACKPROTECTOR_TLS=y -CONFIG_STACKPROTECTOR_PER_TASK=y -# end of Boot options - -CONFIG_PORTABLE=y - -# -# Power management options -# -CONFIG_PM=y -# CONFIG_PM_DEBUG is not set -CONFIG_PM_CLK=y -CONFIG_PM_GENERIC_DOMAINS=y -# CONFIG_WQ_POWER_EFFICIENT_DEFAULT is not set -CONFIG_PM_GENERIC_DOMAINS_OF=y -CONFIG_CPU_PM=y -# end of Power management options - -# -# CPU Power Management -# - -# -# CPU Idle -# -CONFIG_CPU_IDLE=y -CONFIG_CPU_IDLE_MULTIPLE_DRIVERS=y -# CONFIG_CPU_IDLE_GOV_LADDER is not set -CONFIG_CPU_IDLE_GOV_MENU=y -# CONFIG_CPU_IDLE_GOV_TEO is not set -CONFIG_DT_IDLE_STATES=y -CONFIG_DT_IDLE_GENPD=y - -# -# RISC-V CPU Idle Drivers -# -CONFIG_RISCV_SBI_CPUIDLE=y -# end of RISC-V CPU Idle Drivers -# end of CPU Idle - -# -# CPU Frequency scaling -# -# CONFIG_CPU_FREQ is not set -# end of CPU Frequency scaling -# end of CPU Power Management - -CONFIG_HAVE_KVM_EVENTFD=y -CONFIG_KVM_MMIO=y -CONFIG_KVM_GENERIC_DIRTYLOG_READ_PROTECT=y -CONFIG_HAVE_KVM_VCPU_ASYNC_IOCTL=y -CONFIG_KVM_XFER_TO_GUEST_WORK=y -CONFIG_VIRTUALIZATION=y -CONFIG_KVM=m - -# -# General architecture-dependent options -# -# CONFIG_KPROBES is not set -CONFIG_JUMP_LABEL=y -# CONFIG_STATIC_KEYS_SELFTEST is not set -CONFIG_HAVE_64BIT_ALIGNED_ACCESS=y -CONFIG_HAVE_KPROBES=y -CONFIG_HAVE_KRETPROBES=y -CONFIG_HAVE_KPROBES_ON_FTRACE=y -CONFIG_HAVE_FUNCTION_ERROR_INJECTION=y -CONFIG_TRACE_IRQFLAGS_SUPPORT=y -CONFIG_HAVE_ARCH_TRACEHOOK=y -CONFIG_HAVE_DMA_CONTIGUOUS=y -CONFIG_GENERIC_SMP_IDLE_THREAD=y -CONFIG_GENERIC_IDLE_POLL_SETUP=y -CONFIG_ARCH_HAS_FORTIFY_SOURCE=y -CONFIG_ARCH_HAS_SET_MEMORY=y -CONFIG_ARCH_HAS_SET_DIRECT_MAP=y -CONFIG_HAVE_ARCH_THREAD_STRUCT_WHITELIST=y -CONFIG_HAVE_ASM_MODVERSIONS=y -CONFIG_HAVE_REGS_AND_STACK_ACCESS_API=y -CONFIG_HAVE_RSEQ=y -CONFIG_HAVE_FUNCTION_ARG_ACCESS_API=y -CONFIG_HAVE_PERF_REGS=y -CONFIG_HAVE_PERF_USER_STACK_DUMP=y -CONFIG_HAVE_ARCH_JUMP_LABEL=y -CONFIG_HAVE_ARCH_JUMP_LABEL_RELATIVE=y -CONFIG_HAVE_ARCH_SECCOMP=y -CONFIG_HAVE_ARCH_SECCOMP_FILTER=y -CONFIG_SECCOMP=y -CONFIG_SECCOMP_FILTER=y -# CONFIG_SECCOMP_CACHE_DEBUG is not set -CONFIG_HAVE_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR_STRONG=y -CONFIG_LTO_NONE=y -CONFIG_HAVE_CONTEXT_TRACKING_USER=y -CONFIG_HAVE_VIRT_CPU_ACCOUNTING_GEN=y -CONFIG_HAVE_IRQ_TIME_ACCOUNTING=y -CONFIG_HAVE_MOVE_PUD=y -CONFIG_HAVE_MOVE_PMD=y -CONFIG_HAVE_ARCH_TRANSPARENT_HUGEPAGE=y -CONFIG_HAVE_ARCH_HUGE_VMAP=y -CONFIG_HAVE_ARCH_HUGE_VMALLOC=y -CONFIG_ARCH_WANT_HUGE_PMD_SHARE=y -CONFIG_HAVE_MOD_ARCH_SPECIFIC=y -CONFIG_MODULES_USE_ELF_RELA=y -CONFIG_ARCH_HAS_ELF_RANDOMIZE=y -CONFIG_HAVE_ARCH_MMAP_RND_BITS=y -CONFIG_ARCH_MMAP_RND_BITS=18 -CONFIG_HAVE_ARCH_MMAP_RND_COMPAT_BITS=y -CONFIG_ARCH_MMAP_RND_COMPAT_BITS=8 -CONFIG_PAGE_SIZE_LESS_THAN_64KB=y -CONFIG_PAGE_SIZE_LESS_THAN_256KB=y -CONFIG_ARCH_WANT_DEFAULT_TOPDOWN_MMAP_LAYOUT=y -CONFIG_CLONE_BACKWARDS=y -CONFIG_COMPAT_32BIT_TIME=y -CONFIG_HAVE_ARCH_VMAP_STACK=y -CONFIG_VMAP_STACK=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX_DEFAULT=y -CONFIG_ARCH_HAS_STRICT_KERNEL_RWX=y -CONFIG_STRICT_KERNEL_RWX=y -CONFIG_ARCH_HAS_STRICT_MODULE_RWX=y -CONFIG_STRICT_MODULE_RWX=y -CONFIG_ARCH_USE_MEMREMAP_PROT=y -# CONFIG_LOCK_EVENT_COUNTS is not set -CONFIG_ARCH_SUPPORTS_DEBUG_PAGEALLOC=y -CONFIG_ARCH_SUPPORTS_PAGE_TABLE_CHECK=y - -# -# GCOV-based kernel profiling -# -# CONFIG_GCOV_KERNEL is not set -CONFIG_ARCH_HAS_GCOV_PROFILE_ALL=y -# end of GCOV-based kernel profiling - -CONFIG_HAVE_GCC_PLUGINS=y -CONFIG_GCC_PLUGINS=y -# CONFIG_GCC_PLUGIN_LATENT_ENTROPY is not set -CONFIG_FUNCTION_ALIGNMENT=0 -# end of General architecture-dependent options - -CONFIG_RT_MUTEXES=y -CONFIG_BASE_SMALL=0 -CONFIG_MODULES=y -# CONFIG_MODULE_FORCE_LOAD is not set -CONFIG_MODULE_UNLOAD=y -# CONFIG_MODULE_FORCE_UNLOAD is not set -# CONFIG_MODULE_UNLOAD_TAINT_TRACKING is not set -# CONFIG_MODVERSIONS is not set -# CONFIG_MODULE_SRCVERSION_ALL is not set -# CONFIG_MODULE_SIG is not set -CONFIG_MODULE_COMPRESS_NONE=y -# CONFIG_MODULE_COMPRESS_GZIP is not set -# CONFIG_MODULE_COMPRESS_XZ is not set -# CONFIG_MODULE_COMPRESS_ZSTD is not set -# CONFIG_MODULE_ALLOW_MISSING_NAMESPACE_IMPORTS is not set -CONFIG_MODPROBE_PATH="/sbin/modprobe" -# CONFIG_TRIM_UNUSED_KSYMS is not set -CONFIG_MODULES_TREE_LOOKUP=y -CONFIG_BLOCK=y -CONFIG_BLOCK_LEGACY_AUTOLOAD=y -CONFIG_BLK_DEV_BSG_COMMON=y -# CONFIG_BLK_DEV_BSGLIB is not set -# CONFIG_BLK_DEV_INTEGRITY is not set -# CONFIG_BLK_DEV_ZONED is not set -# CONFIG_BLK_WBT is not set -CONFIG_BLK_DEBUG_FS=y -# CONFIG_BLK_SED_OPAL is not set -# CONFIG_BLK_INLINE_ENCRYPTION is not set - -# -# Partition Types -# -# CONFIG_PARTITION_ADVANCED is not set -CONFIG_MSDOS_PARTITION=y -CONFIG_EFI_PARTITION=y -# end of Partition Types - -CONFIG_BLOCK_COMPAT=y -CONFIG_BLK_MQ_PCI=y -CONFIG_BLK_MQ_VIRTIO=y -CONFIG_BLK_PM=y -CONFIG_BLOCK_HOLDER_DEPRECATED=y -CONFIG_BLK_MQ_STACKING=y - -# -# IO Schedulers -# -CONFIG_MQ_IOSCHED_DEADLINE=y -CONFIG_MQ_IOSCHED_KYBER=y -# CONFIG_IOSCHED_BFQ is not set -# end of IO Schedulers - -CONFIG_PREEMPT_NOTIFIERS=y -CONFIG_ASN1=y -CONFIG_UNINLINE_SPIN_UNLOCK=y -CONFIG_ARCH_SUPPORTS_ATOMIC_RMW=y -CONFIG_MUTEX_SPIN_ON_OWNER=y -CONFIG_RWSEM_SPIN_ON_OWNER=y -CONFIG_LOCK_SPIN_ON_OWNER=y -CONFIG_ARCH_USE_QUEUED_RWLOCKS=y -CONFIG_QUEUED_RWLOCKS=y -CONFIG_ARCH_HAS_MMIOWB=y -CONFIG_MMIOWB=y -CONFIG_FREEZER=y - -# -# Executable file formats -# -CONFIG_BINFMT_ELF=y -CONFIG_COMPAT_BINFMT_ELF=y -CONFIG_ELFCORE=y -CONFIG_CORE_DUMP_DEFAULT_ELF_HEADERS=y -CONFIG_BINFMT_SCRIPT=y -CONFIG_ARCH_HAS_BINFMT_FLAT=y -# CONFIG_BINFMT_FLAT is not set -# CONFIG_BINFMT_MISC is not set -CONFIG_COREDUMP=y -# end of Executable file formats - -# -# Memory Management options -# -CONFIG_SWAP=y -# CONFIG_ZSWAP is not set - -# -# SLAB allocator options -# -# CONFIG_SLAB is not set -CONFIG_SLUB=y -# CONFIG_SLOB_DEPRECATED is not set -# CONFIG_SLUB_TINY is not set -CONFIG_SLAB_MERGE_DEFAULT=y -# CONFIG_SLAB_FREELIST_RANDOM is not set -# CONFIG_SLAB_FREELIST_HARDENED is not set -# CONFIG_SLUB_STATS is not set -CONFIG_SLUB_CPU_PARTIAL=y -# end of SLAB allocator options - -# CONFIG_SHUFFLE_PAGE_ALLOCATOR is not set -CONFIG_COMPAT_BRK=y -CONFIG_SELECT_MEMORY_MODEL=y -# CONFIG_FLATMEM_MANUAL is not set -CONFIG_SPARSEMEM_MANUAL=y -CONFIG_SPARSEMEM=y -CONFIG_SPARSEMEM_EXTREME=y -CONFIG_SPARSEMEM_VMEMMAP_ENABLE=y -CONFIG_SPARSEMEM_VMEMMAP=y -CONFIG_SPLIT_PTLOCK_CPUS=4 -CONFIG_ARCH_ENABLE_SPLIT_PMD_PTLOCK=y -CONFIG_MEMORY_BALLOON=y -CONFIG_BALLOON_COMPACTION=y -CONFIG_COMPACTION=y -CONFIG_COMPACT_UNEVICTABLE_DEFAULT=1 -CONFIG_PAGE_REPORTING=y -CONFIG_MIGRATION=y -CONFIG_ARCH_ENABLE_HUGEPAGE_MIGRATION=y -CONFIG_PHYS_ADDR_T_64BIT=y -CONFIG_MMU_NOTIFIER=y -# CONFIG_KSM is not set -CONFIG_DEFAULT_MMAP_MIN_ADDR=4096 -CONFIG_ARCH_WANT_GENERAL_HUGETLB=y -CONFIG_ARCH_WANTS_THP_SWAP=y -# CONFIG_TRANSPARENT_HUGEPAGE is not set -# CONFIG_CMA is not set -CONFIG_GENERIC_EARLY_IOREMAP=y -# CONFIG_DEFERRED_STRUCT_PAGE_INIT is not set -# CONFIG_IDLE_PAGE_TRACKING is not set -CONFIG_ARCH_HAS_CURRENT_STACK_POINTER=y -CONFIG_ZONE_DMA32=y -CONFIG_VM_EVENT_COUNTERS=y -# CONFIG_PERCPU_STATS is not set -# CONFIG_GUP_TEST is not set -CONFIG_ARCH_HAS_PTE_SPECIAL=y -CONFIG_SECRETMEM=y -# CONFIG_ANON_VMA_NAME is not set -# CONFIG_USERFAULTFD is not set -# CONFIG_LRU_GEN is not set - -# -# Data Access Monitoring -# -# CONFIG_DAMON is not set -# end of Data Access Monitoring -# end of Memory Management options - -CONFIG_NET=y -CONFIG_NET_INGRESS=y -CONFIG_NET_EGRESS=y -CONFIG_SKB_EXTENSIONS=y - -# -# Networking options -# -CONFIG_PACKET=y -# CONFIG_PACKET_DIAG is not set -CONFIG_UNIX=y -CONFIG_UNIX_SCM=y -CONFIG_AF_UNIX_OOB=y -# CONFIG_UNIX_DIAG is not set -# CONFIG_TLS is not set -CONFIG_XFRM=y -CONFIG_XFRM_ALGO=m -CONFIG_XFRM_USER=m -# CONFIG_XFRM_INTERFACE is not set -# CONFIG_XFRM_SUB_POLICY is not set -# CONFIG_XFRM_MIGRATE is not set -# CONFIG_XFRM_STATISTICS is not set -CONFIG_XFRM_ESP=m -# CONFIG_NET_KEY is not set -# CONFIG_XDP_SOCKETS is not set -CONFIG_INET=y -CONFIG_IP_MULTICAST=y -CONFIG_IP_ADVANCED_ROUTER=y -# CONFIG_IP_FIB_TRIE_STATS is not set -# CONFIG_IP_MULTIPLE_TABLES is not set -# CONFIG_IP_ROUTE_MULTIPATH is not set -# CONFIG_IP_ROUTE_VERBOSE is not set -CONFIG_IP_PNP=y -CONFIG_IP_PNP_DHCP=y -CONFIG_IP_PNP_BOOTP=y -CONFIG_IP_PNP_RARP=y -# CONFIG_NET_IPIP is not set -# CONFIG_NET_IPGRE_DEMUX is not set -CONFIG_NET_IP_TUNNEL=y -# CONFIG_IP_MROUTE is not set -# CONFIG_SYN_COOKIES is not set -# CONFIG_NET_IPVTI is not set -CONFIG_NET_UDP_TUNNEL=m -# CONFIG_NET_FOU is not set -# CONFIG_NET_FOU_IP_TUNNELS is not set -# CONFIG_INET_AH is not set -CONFIG_INET_ESP=m -# CONFIG_INET_ESP_OFFLOAD is not set -# CONFIG_INET_ESPINTCP is not set -# CONFIG_INET_IPCOMP is not set -CONFIG_INET_TABLE_PERTURB_ORDER=16 -CONFIG_INET_TUNNEL=y -CONFIG_INET_DIAG=y -CONFIG_INET_TCP_DIAG=y -# CONFIG_INET_UDP_DIAG is not set -# CONFIG_INET_RAW_DIAG is not set -# CONFIG_INET_DIAG_DESTROY is not set -# CONFIG_TCP_CONG_ADVANCED is not set -CONFIG_TCP_CONG_CUBIC=y -CONFIG_DEFAULT_TCP_CONG="cubic" -# CONFIG_TCP_MD5SIG is not set -CONFIG_IPV6=y -# CONFIG_IPV6_ROUTER_PREF is not set -# CONFIG_IPV6_OPTIMISTIC_DAD is not set -# CONFIG_INET6_AH is not set -# CONFIG_INET6_ESP is not set -# CONFIG_INET6_IPCOMP is not set -# CONFIG_IPV6_MIP6 is not set -# CONFIG_IPV6_ILA is not set -# CONFIG_IPV6_VTI is not set -CONFIG_IPV6_SIT=y -# CONFIG_IPV6_SIT_6RD is not set -CONFIG_IPV6_NDISC_NODETYPE=y -# CONFIG_IPV6_TUNNEL is not set -# CONFIG_IPV6_MULTIPLE_TABLES is not set -# CONFIG_IPV6_MROUTE is not set -# CONFIG_IPV6_SEG6_LWTUNNEL is not set -# CONFIG_IPV6_SEG6_HMAC is not set -# CONFIG_IPV6_RPL_LWTUNNEL is not set -# CONFIG_IPV6_IOAM6_LWTUNNEL is not set -# CONFIG_NETLABEL is not set -# CONFIG_MPTCP is not set -CONFIG_NETWORK_SECMARK=y -# CONFIG_NETWORK_PHY_TIMESTAMPING is not set -CONFIG_NETFILTER=y -CONFIG_NETFILTER_ADVANCED=y -CONFIG_BRIDGE_NETFILTER=m - -# -# Core Netfilter Configuration -# -CONFIG_NETFILTER_INGRESS=y -CONFIG_NETFILTER_EGRESS=y -CONFIG_NETFILTER_FAMILY_BRIDGE=y -# CONFIG_NETFILTER_NETLINK_ACCT is not set -# CONFIG_NETFILTER_NETLINK_QUEUE is not set -# CONFIG_NETFILTER_NETLINK_LOG is not set -# CONFIG_NETFILTER_NETLINK_OSF is not set -CONFIG_NF_CONNTRACK=m -CONFIG_NF_LOG_SYSLOG=m -# CONFIG_NF_CONNTRACK_MARK is not set -# CONFIG_NF_CONNTRACK_SECMARK is not set -# CONFIG_NF_CONNTRACK_ZONES is not set -# CONFIG_NF_CONNTRACK_PROCFS is not set -# CONFIG_NF_CONNTRACK_EVENTS is not set -# CONFIG_NF_CONNTRACK_TIMEOUT is not set -# CONFIG_NF_CONNTRACK_TIMESTAMP is not set -# CONFIG_NF_CONNTRACK_LABELS is not set -CONFIG_NF_CT_PROTO_DCCP=y -CONFIG_NF_CT_PROTO_SCTP=y -CONFIG_NF_CT_PROTO_UDPLITE=y -# CONFIG_NF_CONNTRACK_AMANDA is not set -CONFIG_NF_CONNTRACK_FTP=m -# CONFIG_NF_CONNTRACK_H323 is not set -# CONFIG_NF_CONNTRACK_IRC is not set -# CONFIG_NF_CONNTRACK_NETBIOS_NS is not set -# CONFIG_NF_CONNTRACK_SNMP is not set -# CONFIG_NF_CONNTRACK_PPTP is not set -# CONFIG_NF_CONNTRACK_SANE is not set -# CONFIG_NF_CONNTRACK_SIP is not set -CONFIG_NF_CONNTRACK_TFTP=m -# CONFIG_NF_CT_NETLINK is not set -CONFIG_NF_NAT=m -CONFIG_NF_NAT_FTP=m -CONFIG_NF_NAT_TFTP=m -CONFIG_NF_NAT_REDIRECT=y -CONFIG_NF_NAT_MASQUERADE=y -# CONFIG_NF_TABLES is not set -CONFIG_NETFILTER_XTABLES=y -CONFIG_NETFILTER_XTABLES_COMPAT=y - -# -# Xtables combined modules -# -CONFIG_NETFILTER_XT_MARK=m -# CONFIG_NETFILTER_XT_CONNMARK is not set - -# -# Xtables targets -# -# CONFIG_NETFILTER_XT_TARGET_AUDIT is not set -# CONFIG_NETFILTER_XT_TARGET_CHECKSUM is not set -# CONFIG_NETFILTER_XT_TARGET_CLASSIFY is not set -# CONFIG_NETFILTER_XT_TARGET_CONNMARK is not set -# CONFIG_NETFILTER_XT_TARGET_DSCP is not set -# CONFIG_NETFILTER_XT_TARGET_HL is not set -# CONFIG_NETFILTER_XT_TARGET_HMARK is not set -# CONFIG_NETFILTER_XT_TARGET_IDLETIMER is not set -# CONFIG_NETFILTER_XT_TARGET_LOG is not set -# CONFIG_NETFILTER_XT_TARGET_MARK is not set -CONFIG_NETFILTER_XT_NAT=m -# CONFIG_NETFILTER_XT_TARGET_NETMAP is not set -# CONFIG_NETFILTER_XT_TARGET_NFLOG is not set -# CONFIG_NETFILTER_XT_TARGET_NFQUEUE is not set -# CONFIG_NETFILTER_XT_TARGET_RATEEST is not set -CONFIG_NETFILTER_XT_TARGET_REDIRECT=m -CONFIG_NETFILTER_XT_TARGET_MASQUERADE=m -# CONFIG_NETFILTER_XT_TARGET_TEE is not set -# CONFIG_NETFILTER_XT_TARGET_TPROXY is not set -# CONFIG_NETFILTER_XT_TARGET_SECMARK is not set -# CONFIG_NETFILTER_XT_TARGET_TCPMSS is not set -# CONFIG_NETFILTER_XT_TARGET_TCPOPTSTRIP is not set - -# -# Xtables matches -# -CONFIG_NETFILTER_XT_MATCH_ADDRTYPE=m -# CONFIG_NETFILTER_XT_MATCH_BPF is not set -# CONFIG_NETFILTER_XT_MATCH_CGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_CLUSTER is not set -# CONFIG_NETFILTER_XT_MATCH_COMMENT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNBYTES is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLABEL is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNMARK is not set -CONFIG_NETFILTER_XT_MATCH_CONNTRACK=m -# CONFIG_NETFILTER_XT_MATCH_CPU is not set -# CONFIG_NETFILTER_XT_MATCH_DCCP is not set -# CONFIG_NETFILTER_XT_MATCH_DEVGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_DSCP is not set -# CONFIG_NETFILTER_XT_MATCH_ECN is not set -# CONFIG_NETFILTER_XT_MATCH_ESP is not set -# CONFIG_NETFILTER_XT_MATCH_HASHLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_HELPER is not set -# CONFIG_NETFILTER_XT_MATCH_HL is not set -# CONFIG_NETFILTER_XT_MATCH_IPCOMP is not set -# CONFIG_NETFILTER_XT_MATCH_IPRANGE is not set -CONFIG_NETFILTER_XT_MATCH_IPVS=m -# CONFIG_NETFILTER_XT_MATCH_L2TP is not set -# CONFIG_NETFILTER_XT_MATCH_LENGTH is not set -# CONFIG_NETFILTER_XT_MATCH_LIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_MAC is not set -# CONFIG_NETFILTER_XT_MATCH_MARK is not set -# CONFIG_NETFILTER_XT_MATCH_MULTIPORT is not set -# CONFIG_NETFILTER_XT_MATCH_NFACCT is not set -# CONFIG_NETFILTER_XT_MATCH_OSF is not set -# CONFIG_NETFILTER_XT_MATCH_OWNER is not set -# CONFIG_NETFILTER_XT_MATCH_POLICY is not set -# CONFIG_NETFILTER_XT_MATCH_PHYSDEV is not set -# CONFIG_NETFILTER_XT_MATCH_PKTTYPE is not set -# CONFIG_NETFILTER_XT_MATCH_QUOTA is not set -# CONFIG_NETFILTER_XT_MATCH_RATEEST is not set -# CONFIG_NETFILTER_XT_MATCH_REALM is not set -# CONFIG_NETFILTER_XT_MATCH_RECENT is not set -# CONFIG_NETFILTER_XT_MATCH_SCTP is not set -# CONFIG_NETFILTER_XT_MATCH_SOCKET is not set -# CONFIG_NETFILTER_XT_MATCH_STATE is not set -# CONFIG_NETFILTER_XT_MATCH_STATISTIC is not set -# CONFIG_NETFILTER_XT_MATCH_STRING is not set -# CONFIG_NETFILTER_XT_MATCH_TCPMSS is not set -# CONFIG_NETFILTER_XT_MATCH_TIME is not set -# CONFIG_NETFILTER_XT_MATCH_U32 is not set -# end of Core Netfilter Configuration - -# CONFIG_IP_SET is not set -CONFIG_IP_VS=m -# CONFIG_IP_VS_IPV6 is not set -# CONFIG_IP_VS_DEBUG is not set -CONFIG_IP_VS_TAB_BITS=12 - -# -# IPVS transport protocol load balancing support -# -CONFIG_IP_VS_PROTO_TCP=y -CONFIG_IP_VS_PROTO_UDP=y -# CONFIG_IP_VS_PROTO_ESP is not set -# CONFIG_IP_VS_PROTO_AH is not set -# CONFIG_IP_VS_PROTO_SCTP is not set - -# -# IPVS scheduler -# -CONFIG_IP_VS_RR=m -# CONFIG_IP_VS_WRR is not set -# CONFIG_IP_VS_LC is not set -# CONFIG_IP_VS_WLC is not set -# CONFIG_IP_VS_FO is not set -# CONFIG_IP_VS_OVF is not set -# CONFIG_IP_VS_LBLC is not set -# CONFIG_IP_VS_LBLCR is not set -# CONFIG_IP_VS_DH is not set -# CONFIG_IP_VS_SH is not set -# CONFIG_IP_VS_MH is not set -# CONFIG_IP_VS_SED is not set -# CONFIG_IP_VS_NQ is not set -# CONFIG_IP_VS_TWOS is not set - -# -# IPVS SH scheduler -# -CONFIG_IP_VS_SH_TAB_BITS=8 - -# -# IPVS MH scheduler -# -CONFIG_IP_VS_MH_TAB_INDEX=12 - -# -# IPVS application helper -# -# CONFIG_IP_VS_FTP is not set -CONFIG_IP_VS_NFCT=y - -# -# IP: Netfilter Configuration -# -CONFIG_NF_DEFRAG_IPV4=m -# CONFIG_NF_SOCKET_IPV4 is not set -# CONFIG_NF_TPROXY_IPV4 is not set -# CONFIG_NF_DUP_IPV4 is not set -CONFIG_NF_LOG_ARP=m -CONFIG_NF_LOG_IPV4=m -CONFIG_NF_REJECT_IPV4=m -CONFIG_IP_NF_IPTABLES=y -# CONFIG_IP_NF_MATCH_AH is not set -# CONFIG_IP_NF_MATCH_ECN is not set -# CONFIG_IP_NF_MATCH_RPFILTER is not set -# CONFIG_IP_NF_MATCH_TTL is not set -CONFIG_IP_NF_FILTER=m -CONFIG_IP_NF_TARGET_REJECT=m -# CONFIG_IP_NF_TARGET_SYNPROXY is not set -CONFIG_IP_NF_NAT=m -CONFIG_IP_NF_TARGET_MASQUERADE=m -# CONFIG_IP_NF_TARGET_NETMAP is not set -CONFIG_IP_NF_TARGET_REDIRECT=m -CONFIG_IP_NF_MANGLE=m -# CONFIG_IP_NF_TARGET_CLUSTERIP is not set -# CONFIG_IP_NF_TARGET_ECN is not set -# CONFIG_IP_NF_TARGET_TTL is not set -# CONFIG_IP_NF_RAW is not set -# CONFIG_IP_NF_SECURITY is not set -# CONFIG_IP_NF_ARPTABLES is not set -# end of IP: Netfilter Configuration - -# -# IPv6: Netfilter Configuration -# -# CONFIG_NF_SOCKET_IPV6 is not set -# CONFIG_NF_TPROXY_IPV6 is not set -# CONFIG_NF_DUP_IPV6 is not set -CONFIG_NF_REJECT_IPV6=m -CONFIG_NF_LOG_IPV6=m -CONFIG_IP6_NF_IPTABLES=m -# CONFIG_IP6_NF_MATCH_AH is not set -# CONFIG_IP6_NF_MATCH_EUI64 is not set -# CONFIG_IP6_NF_MATCH_FRAG is not set -# CONFIG_IP6_NF_MATCH_OPTS is not set -# CONFIG_IP6_NF_MATCH_HL is not set -CONFIG_IP6_NF_MATCH_IPV6HEADER=m -# CONFIG_IP6_NF_MATCH_MH is not set -# CONFIG_IP6_NF_MATCH_RPFILTER is not set -# CONFIG_IP6_NF_MATCH_RT is not set -# CONFIG_IP6_NF_MATCH_SRH is not set -# CONFIG_IP6_NF_TARGET_HL is not set -CONFIG_IP6_NF_FILTER=m -CONFIG_IP6_NF_TARGET_REJECT=m -# CONFIG_IP6_NF_TARGET_SYNPROXY is not set -CONFIG_IP6_NF_MANGLE=m -# CONFIG_IP6_NF_RAW is not set -# CONFIG_IP6_NF_SECURITY is not set -# CONFIG_IP6_NF_NAT is not set -# end of IPv6: Netfilter Configuration - -CONFIG_NF_DEFRAG_IPV6=m -# CONFIG_NF_CONNTRACK_BRIDGE is not set -# CONFIG_BRIDGE_NF_EBTABLES is not set -# CONFIG_BPFILTER is not set -# CONFIG_IP_DCCP is not set -# CONFIG_IP_SCTP is not set -# CONFIG_RDS is not set -# CONFIG_TIPC is not set -# CONFIG_ATM is not set -# CONFIG_L2TP is not set -CONFIG_STP=m -CONFIG_BRIDGE=m -CONFIG_BRIDGE_IGMP_SNOOPING=y -CONFIG_BRIDGE_VLAN_FILTERING=y -# CONFIG_BRIDGE_MRP is not set -# CONFIG_BRIDGE_CFM is not set -# CONFIG_NET_DSA is not set -CONFIG_VLAN_8021Q=m -# CONFIG_VLAN_8021Q_GVRP is not set -# CONFIG_VLAN_8021Q_MVRP is not set -CONFIG_LLC=m -# CONFIG_LLC2 is not set -# CONFIG_ATALK is not set -# CONFIG_X25 is not set -# CONFIG_LAPB is not set -# CONFIG_PHONET is not set -# CONFIG_6LOWPAN is not set -# CONFIG_IEEE802154 is not set -CONFIG_NET_SCHED=y - -# -# Queueing/Scheduling -# -# CONFIG_NET_SCH_CBQ is not set -# CONFIG_NET_SCH_HTB is not set -# CONFIG_NET_SCH_HFSC is not set -# CONFIG_NET_SCH_PRIO is not set -# CONFIG_NET_SCH_MULTIQ is not set -# CONFIG_NET_SCH_RED is not set -# CONFIG_NET_SCH_SFB is not set -# CONFIG_NET_SCH_SFQ is not set -# CONFIG_NET_SCH_TEQL is not set -# CONFIG_NET_SCH_TBF is not set -# CONFIG_NET_SCH_CBS is not set -# CONFIG_NET_SCH_ETF is not set -# CONFIG_NET_SCH_TAPRIO is not set -# CONFIG_NET_SCH_GRED is not set -# CONFIG_NET_SCH_DSMARK is not set -# CONFIG_NET_SCH_NETEM is not set -# CONFIG_NET_SCH_DRR is not set -# CONFIG_NET_SCH_MQPRIO is not set -# CONFIG_NET_SCH_SKBPRIO is not set -# CONFIG_NET_SCH_CHOKE is not set -# CONFIG_NET_SCH_QFQ is not set -# CONFIG_NET_SCH_CODEL is not set -# CONFIG_NET_SCH_FQ_CODEL is not set -# CONFIG_NET_SCH_CAKE is not set -# CONFIG_NET_SCH_FQ is not set -# CONFIG_NET_SCH_HHF is not set -# CONFIG_NET_SCH_PIE is not set -# CONFIG_NET_SCH_PLUG is not set -# CONFIG_NET_SCH_ETS is not set -# CONFIG_NET_SCH_DEFAULT is not set - -# -# Classification -# -CONFIG_NET_CLS=y -# CONFIG_NET_CLS_BASIC is not set -# CONFIG_NET_CLS_ROUTE4 is not set -# CONFIG_NET_CLS_FW is not set -# CONFIG_NET_CLS_U32 is not set -# CONFIG_NET_CLS_RSVP is not set -# CONFIG_NET_CLS_RSVP6 is not set -# CONFIG_NET_CLS_FLOW is not set -CONFIG_NET_CLS_CGROUP=m -# CONFIG_NET_CLS_BPF is not set -# CONFIG_NET_CLS_FLOWER is not set -# CONFIG_NET_CLS_MATCHALL is not set -# CONFIG_NET_EMATCH is not set -# CONFIG_NET_CLS_ACT is not set -CONFIG_NET_SCH_FIFO=y -# CONFIG_DCB is not set -CONFIG_DNS_RESOLVER=y -# CONFIG_BATMAN_ADV is not set -# CONFIG_OPENVSWITCH is not set -# CONFIG_VSOCKETS is not set -CONFIG_NETLINK_DIAG=y -# CONFIG_MPLS is not set -# CONFIG_NET_NSH is not set -# CONFIG_HSR is not set -# CONFIG_NET_SWITCHDEV is not set -CONFIG_NET_L3_MASTER_DEV=y -# CONFIG_QRTR is not set -# CONFIG_NET_NCSI is not set -CONFIG_PCPU_DEV_REFCNT=y -CONFIG_RPS=y -CONFIG_RFS_ACCEL=y -CONFIG_SOCK_RX_QUEUE_MAPPING=y -CONFIG_XPS=y -CONFIG_CGROUP_NET_PRIO=y -CONFIG_CGROUP_NET_CLASSID=y -CONFIG_NET_RX_BUSY_POLL=y -CONFIG_BQL=y -# CONFIG_BPF_STREAM_PARSER is not set -CONFIG_NET_FLOW_LIMIT=y - -# -# Network testing -# -# CONFIG_NET_PKTGEN is not set -# end of Network testing -# end of Networking options - -# CONFIG_HAMRADIO is not set -# CONFIG_CAN is not set -# CONFIG_BT is not set -# CONFIG_AF_RXRPC is not set -# CONFIG_AF_KCM is not set -# CONFIG_MCTP is not set -CONFIG_WIRELESS=y -# CONFIG_CFG80211 is not set - -# -# CFG80211 needs to be enabled for MAC80211 -# -CONFIG_MAC80211_STA_HASH_MAX_SIZE=0 -# CONFIG_RFKILL is not set -CONFIG_NET_9P=y -CONFIG_NET_9P_FD=y -CONFIG_NET_9P_VIRTIO=y -# CONFIG_NET_9P_DEBUG is not set -# CONFIG_CAIF is not set -# CONFIG_CEPH_LIB is not set -# CONFIG_NFC is not set -# CONFIG_PSAMPLE is not set -# CONFIG_NET_IFE is not set -# CONFIG_LWTUNNEL is not set -CONFIG_DST_CACHE=y -CONFIG_GRO_CELLS=y -CONFIG_NET_SELFTESTS=y -CONFIG_NET_SOCK_MSG=y -CONFIG_PAGE_POOL=y -# CONFIG_PAGE_POOL_STATS is not set -CONFIG_FAILOVER=y -CONFIG_ETHTOOL_NETLINK=y - -# -# Device Drivers -# -CONFIG_HAVE_PCI=y -CONFIG_PCI=y -CONFIG_PCI_DOMAINS=y -CONFIG_PCI_DOMAINS_GENERIC=y -CONFIG_PCIEPORTBUS=y -# CONFIG_PCIEAER is not set -CONFIG_PCIEASPM=y -CONFIG_PCIEASPM_DEFAULT=y -# CONFIG_PCIEASPM_POWERSAVE is not set -# CONFIG_PCIEASPM_POWER_SUPERSAVE is not set -# CONFIG_PCIEASPM_PERFORMANCE is not set -CONFIG_PCIE_PME=y -# CONFIG_PCIE_PTM is not set -CONFIG_PCI_MSI=y -CONFIG_PCI_QUIRKS=y -# CONFIG_PCI_DEBUG is not set -# CONFIG_PCI_STUB is not set -CONFIG_PCI_ECAM=y -# CONFIG_PCI_IOV is not set -# CONFIG_PCI_PRI is not set -# CONFIG_PCI_PASID is not set -# CONFIG_PCIE_BUS_TUNE_OFF is not set -CONFIG_PCIE_BUS_DEFAULT=y -# CONFIG_PCIE_BUS_SAFE is not set -# CONFIG_PCIE_BUS_PERFORMANCE is not set -# CONFIG_PCIE_BUS_PEER2PEER is not set -CONFIG_VGA_ARB=y -CONFIG_VGA_ARB_MAX_GPUS=16 -# CONFIG_HOTPLUG_PCI is not set - -# -# PCI controller drivers -# -# CONFIG_PCI_FTPCI100 is not set -# CONFIG_PCIE_RCAR_HOST is not set -CONFIG_PCI_HOST_COMMON=y -CONFIG_PCI_HOST_GENERIC=y -CONFIG_PCIE_XILINX=y -CONFIG_PCIE_MICROCHIP_HOST=y - -# -# DesignWare PCI Core Support -# -CONFIG_PCIE_DW=y -CONFIG_PCIE_DW_HOST=y -# CONFIG_PCIE_DW_PLAT_HOST is not set -# CONFIG_PCI_MESON is not set -CONFIG_PCIE_FU740=y -# end of DesignWare PCI Core Support - -# -# Mobiveil PCIe Core Support -# -# end of Mobiveil PCIe Core Support - -# -# Cadence PCIe controllers support -# -# CONFIG_PCIE_CADENCE_PLAT_HOST is not set -# CONFIG_PCI_J721E_HOST is not set -# end of Cadence PCIe controllers support -# end of PCI controller drivers - -# -# PCI Endpoint -# -# CONFIG_PCI_ENDPOINT is not set -# end of PCI Endpoint - -# -# PCI switch controller drivers -# -# CONFIG_PCI_SW_SWITCHTEC is not set -# end of PCI switch controller drivers - -# CONFIG_CXL_BUS is not set -# CONFIG_PCCARD is not set -# CONFIG_RAPIDIO is not set - -# -# Generic Driver Options -# -CONFIG_AUXILIARY_BUS=y -# CONFIG_UEVENT_HELPER is not set -CONFIG_DEVTMPFS=y -CONFIG_DEVTMPFS_MOUNT=y -# CONFIG_DEVTMPFS_SAFE is not set -CONFIG_STANDALONE=y -CONFIG_PREVENT_FIRMWARE_BUILD=y - -# -# Firmware loader -# -CONFIG_FW_LOADER=y -CONFIG_EXTRA_FIRMWARE="" -# CONFIG_FW_LOADER_USER_HELPER is not set -# CONFIG_FW_LOADER_COMPRESS is not set -# CONFIG_FW_UPLOAD is not set -# end of Firmware loader - -CONFIG_WANT_DEV_COREDUMP=y -CONFIG_ALLOW_DEV_COREDUMP=y -CONFIG_DEV_COREDUMP=y -# CONFIG_DEBUG_DRIVER is not set -# CONFIG_DEBUG_DEVRES is not set -# CONFIG_DEBUG_TEST_DRIVER_REMOVE is not set -# CONFIG_TEST_ASYNC_DRIVER_PROBE is not set -CONFIG_SOC_BUS=y -CONFIG_REGMAP=y -CONFIG_REGMAP_I2C=y -CONFIG_REGMAP_MMIO=y -CONFIG_DMA_SHARED_BUFFER=y -# CONFIG_DMA_FENCE_TRACE is not set -CONFIG_GENERIC_ARCH_TOPOLOGY=y -# end of Generic Driver Options - -# -# Bus devices -# -# CONFIG_MOXTET is not set -# CONFIG_MHI_BUS is not set -# CONFIG_MHI_BUS_EP is not set -# end of Bus devices - -# CONFIG_CONNECTOR is not set - -# -# Firmware Drivers -# - -# -# ARM System Control and Management Interface Protocol -# -# end of ARM System Control and Management Interface Protocol - -# CONFIG_FIRMWARE_MEMMAP is not set -# CONFIG_SYSFB_SIMPLEFB is not set -# CONFIG_GOOGLE_FIRMWARE is not set - -# -# EFI (Extensible Firmware Interface) Support -# -CONFIG_EFI_ESRT=y -CONFIG_EFI_PARAMS_FROM_FDT=y -CONFIG_EFI_RUNTIME_WRAPPERS=y -CONFIG_EFI_GENERIC_STUB=y -# CONFIG_EFI_ZBOOT is not set -# CONFIG_EFI_BOOTLOADER_CONTROL is not set -# CONFIG_EFI_CAPSULE_LOADER is not set -# CONFIG_EFI_TEST is not set -# CONFIG_RESET_ATTACK_MITIGATION is not set -# CONFIG_EFI_DISABLE_PCI_DMA is not set -CONFIG_EFI_EARLYCON=y -# CONFIG_EFI_DISABLE_RUNTIME is not set -# CONFIG_EFI_COCO_SECRET is not set -# end of EFI (Extensible Firmware Interface) Support - -# -# Tegra firmware driver -# -# end of Tegra firmware driver -# end of Firmware Drivers - -# CONFIG_GNSS is not set -# CONFIG_MTD is not set -CONFIG_DTC=y -CONFIG_OF=y -# CONFIG_OF_UNITTEST is not set -CONFIG_OF_FLATTREE=y -CONFIG_OF_EARLY_FLATTREE=y -CONFIG_OF_KOBJ=y -CONFIG_OF_DYNAMIC=y -CONFIG_OF_ADDRESS=y -CONFIG_OF_IRQ=y -CONFIG_OF_RESERVED_MEM=y -CONFIG_OF_RESOLVE=y -CONFIG_OF_OVERLAY=y -CONFIG_OF_DMA_DEFAULT_COHERENT=y -# CONFIG_PARPORT is not set -CONFIG_BLK_DEV=y -# CONFIG_BLK_DEV_NULL_BLK is not set -CONFIG_CDROM=y -# CONFIG_BLK_DEV_PCIESSD_MTIP32XX is not set -CONFIG_BLK_DEV_LOOP=y -CONFIG_BLK_DEV_LOOP_MIN_COUNT=8 -# CONFIG_BLK_DEV_DRBD is not set -# CONFIG_BLK_DEV_NBD is not set -# CONFIG_BLK_DEV_RAM is not set -# CONFIG_CDROM_PKTCDVD is not set -# CONFIG_ATA_OVER_ETH is not set -CONFIG_VIRTIO_BLK=y -# CONFIG_BLK_DEV_RBD is not set -# CONFIG_BLK_DEV_UBLK is not set - -# -# NVME Support -# -CONFIG_NVME_CORE=m -CONFIG_BLK_DEV_NVME=m -# CONFIG_NVME_MULTIPATH is not set -# CONFIG_NVME_VERBOSE_ERRORS is not set -# CONFIG_NVME_HWMON is not set -# CONFIG_NVME_FC is not set -# CONFIG_NVME_TCP is not set -# CONFIG_NVME_AUTH is not set -# CONFIG_NVME_TARGET is not set -# end of NVME Support - -# -# Misc devices -# -# CONFIG_AD525X_DPOT is not set -# CONFIG_DUMMY_IRQ is not set -# CONFIG_PHANTOM is not set -# CONFIG_TIFM_CORE is not set -# CONFIG_ICS932S401 is not set -# CONFIG_ENCLOSURE_SERVICES is not set -# CONFIG_HP_ILO is not set -# CONFIG_APDS9802ALS is not set -# CONFIG_ISL29003 is not set -# CONFIG_ISL29020 is not set -# CONFIG_SENSORS_TSL2550 is not set -# CONFIG_SENSORS_BH1770 is not set -# CONFIG_SENSORS_APDS990X is not set -# CONFIG_HMC6352 is not set -# CONFIG_DS1682 is not set -# CONFIG_LATTICE_ECP3_CONFIG is not set -# CONFIG_SRAM is not set -# CONFIG_DW_XDATA_PCIE is not set -# CONFIG_PCI_ENDPOINT_TEST is not set -# CONFIG_XILINX_SDFEC is not set -# CONFIG_OPEN_DICE is not set -# CONFIG_VCPU_STALL_DETECTOR is not set -# CONFIG_C2PORT is not set - -# -# EEPROM support -# -CONFIG_EEPROM_AT24=y -# CONFIG_EEPROM_AT25 is not set -# CONFIG_EEPROM_LEGACY is not set -# CONFIG_EEPROM_MAX6875 is not set -# CONFIG_EEPROM_93CX6 is not set -# CONFIG_EEPROM_93XX46 is not set -# CONFIG_EEPROM_IDT_89HPESX is not set -# CONFIG_EEPROM_EE1004 is not set -# end of EEPROM support - -# CONFIG_CB710_CORE is not set - -# -# Texas Instruments shared transport line discipline -# -# CONFIG_TI_ST is not set -# end of Texas Instruments shared transport line discipline - -# CONFIG_SENSORS_LIS3_SPI is not set -# CONFIG_SENSORS_LIS3_I2C is not set -# CONFIG_ALTERA_STAPL is not set -# CONFIG_GENWQE is not set -# CONFIG_ECHO is not set -# CONFIG_BCM_VK is not set -# CONFIG_MISC_ALCOR_PCI is not set -# CONFIG_MISC_RTSX_PCI is not set -# CONFIG_MISC_RTSX_USB is not set -# CONFIG_HABANA_AI is not set -# CONFIG_PVPANIC is not set -# CONFIG_GP_PCI1XXXX is not set -# end of Misc devices - -# -# SCSI device support -# -CONFIG_SCSI_MOD=y -# CONFIG_RAID_ATTRS is not set -CONFIG_SCSI_COMMON=y -CONFIG_SCSI=y -CONFIG_SCSI_DMA=y -CONFIG_SCSI_PROC_FS=y - -# -# SCSI support type (disk, tape, CD-ROM) -# -CONFIG_BLK_DEV_SD=y -# CONFIG_CHR_DEV_ST is not set -CONFIG_BLK_DEV_SR=y -# CONFIG_CHR_DEV_SG is not set -CONFIG_BLK_DEV_BSG=y -# CONFIG_CHR_DEV_SCH is not set -# CONFIG_SCSI_CONSTANTS is not set -# CONFIG_SCSI_LOGGING is not set -# CONFIG_SCSI_SCAN_ASYNC is not set - -# -# SCSI Transports -# -# CONFIG_SCSI_SPI_ATTRS is not set -# CONFIG_SCSI_FC_ATTRS is not set -# CONFIG_SCSI_ISCSI_ATTRS is not set -# CONFIG_SCSI_SAS_ATTRS is not set -# CONFIG_SCSI_SAS_LIBSAS is not set -# CONFIG_SCSI_SRP_ATTRS is not set -# end of SCSI Transports - -CONFIG_SCSI_LOWLEVEL=y -# CONFIG_ISCSI_TCP is not set -# CONFIG_ISCSI_BOOT_SYSFS is not set -# CONFIG_SCSI_CXGB3_ISCSI is not set -# CONFIG_SCSI_CXGB4_ISCSI is not set -# CONFIG_SCSI_BNX2_ISCSI is not set -# CONFIG_BE2ISCSI is not set -# CONFIG_BLK_DEV_3W_XXXX_RAID is not set -# CONFIG_SCSI_HPSA is not set -# CONFIG_SCSI_3W_9XXX is not set -# CONFIG_SCSI_3W_SAS is not set -# CONFIG_SCSI_ACARD is not set -# CONFIG_SCSI_AACRAID is not set -# CONFIG_SCSI_AIC7XXX is not set -# CONFIG_SCSI_AIC79XX is not set -# CONFIG_SCSI_AIC94XX is not set -# CONFIG_SCSI_MVSAS is not set -# CONFIG_SCSI_MVUMI is not set -# CONFIG_SCSI_ADVANSYS is not set -# CONFIG_SCSI_ARCMSR is not set -# CONFIG_SCSI_ESAS2R is not set -# CONFIG_MEGARAID_NEWGEN is not set -# CONFIG_MEGARAID_LEGACY is not set -# CONFIG_MEGARAID_SAS is not set -# CONFIG_SCSI_MPT3SAS is not set -# CONFIG_SCSI_MPT2SAS is not set -# CONFIG_SCSI_MPI3MR is not set -# CONFIG_SCSI_SMARTPQI is not set -# CONFIG_SCSI_HPTIOP is not set -# CONFIG_SCSI_BUSLOGIC is not set -# CONFIG_SCSI_MYRB is not set -# CONFIG_SCSI_MYRS is not set -# CONFIG_SCSI_SNIC is not set -# CONFIG_SCSI_DMX3191D is not set -# CONFIG_SCSI_FDOMAIN_PCI is not set -# CONFIG_SCSI_IPS is not set -# CONFIG_SCSI_INITIO is not set -# CONFIG_SCSI_INIA100 is not set -# CONFIG_SCSI_STEX is not set -# CONFIG_SCSI_SYM53C8XX_2 is not set -# CONFIG_SCSI_IPR is not set -# CONFIG_SCSI_QLOGIC_1280 is not set -# CONFIG_SCSI_QLA_ISCSI is not set -# CONFIG_SCSI_DC395x is not set -# CONFIG_SCSI_AM53C974 is not set -# CONFIG_SCSI_WD719X is not set -# CONFIG_SCSI_DEBUG is not set -# CONFIG_SCSI_PMCRAID is not set -# CONFIG_SCSI_PM8001 is not set -CONFIG_SCSI_VIRTIO=y -# CONFIG_SCSI_DH is not set -# end of SCSI device support - -CONFIG_ATA=y -CONFIG_SATA_HOST=y -CONFIG_ATA_VERBOSE_ERROR=y -CONFIG_ATA_FORCE=y -CONFIG_SATA_PMP=y - -# -# Controllers with non-SFF native interface -# -CONFIG_SATA_AHCI=y -CONFIG_SATA_MOBILE_LPM_POLICY=0 -CONFIG_SATA_AHCI_PLATFORM=y -# CONFIG_AHCI_DWC is not set -# CONFIG_AHCI_CEVA is not set -# CONFIG_AHCI_QORIQ is not set -# CONFIG_SATA_INIC162X is not set -# CONFIG_SATA_ACARD_AHCI is not set -# CONFIG_SATA_SIL24 is not set -CONFIG_ATA_SFF=y - -# -# SFF controllers with custom DMA interface -# -# CONFIG_PDC_ADMA is not set -# CONFIG_SATA_QSTOR is not set -# CONFIG_SATA_SX4 is not set -CONFIG_ATA_BMDMA=y - -# -# SATA SFF controllers with BMDMA -# -# CONFIG_ATA_PIIX is not set -# CONFIG_SATA_MV is not set -# CONFIG_SATA_NV is not set -# CONFIG_SATA_PROMISE is not set -# CONFIG_SATA_RCAR is not set -# CONFIG_SATA_SIL is not set -# CONFIG_SATA_SIS is not set -# CONFIG_SATA_SVW is not set -# CONFIG_SATA_ULI is not set -# CONFIG_SATA_VIA is not set -# CONFIG_SATA_VITESSE is not set - -# -# PATA SFF controllers with BMDMA -# -# CONFIG_PATA_ALI is not set -# CONFIG_PATA_AMD is not set -# CONFIG_PATA_ARTOP is not set -# CONFIG_PATA_ATIIXP is not set -# CONFIG_PATA_ATP867X is not set -# CONFIG_PATA_CMD64X is not set -# CONFIG_PATA_CYPRESS is not set -# CONFIG_PATA_EFAR is not set -# CONFIG_PATA_HPT366 is not set -# CONFIG_PATA_HPT37X is not set -# CONFIG_PATA_HPT3X2N is not set -# CONFIG_PATA_HPT3X3 is not set -# CONFIG_PATA_IT8213 is not set -# CONFIG_PATA_IT821X is not set -# CONFIG_PATA_JMICRON is not set -# CONFIG_PATA_MARVELL is not set -# CONFIG_PATA_NETCELL is not set -# CONFIG_PATA_NINJA32 is not set -# CONFIG_PATA_NS87415 is not set -# CONFIG_PATA_OLDPIIX is not set -# CONFIG_PATA_OPTIDMA is not set -# CONFIG_PATA_PDC2027X is not set -# CONFIG_PATA_PDC_OLD is not set -# CONFIG_PATA_RADISYS is not set -# CONFIG_PATA_RDC is not set -# CONFIG_PATA_SCH is not set -# CONFIG_PATA_SERVERWORKS is not set -# CONFIG_PATA_SIL680 is not set -# CONFIG_PATA_SIS is not set -# CONFIG_PATA_TOSHIBA is not set -# CONFIG_PATA_TRIFLEX is not set -# CONFIG_PATA_VIA is not set -# CONFIG_PATA_WINBOND is not set - -# -# PIO-only SFF controllers -# -# CONFIG_PATA_CMD640_PCI is not set -# CONFIG_PATA_MPIIX is not set -# CONFIG_PATA_NS87410 is not set -# CONFIG_PATA_OPTI is not set -# CONFIG_PATA_OF_PLATFORM is not set -# CONFIG_PATA_RZ1000 is not set - -# -# Generic fallback / legacy drivers -# -# CONFIG_ATA_GENERIC is not set -# CONFIG_PATA_LEGACY is not set -CONFIG_MD=y -# CONFIG_BLK_DEV_MD is not set -# CONFIG_BCACHE is not set -CONFIG_BLK_DEV_DM_BUILTIN=y -CONFIG_BLK_DEV_DM=y -# CONFIG_DM_DEBUG is not set -CONFIG_DM_BUFIO=m -# CONFIG_DM_DEBUG_BLOCK_MANAGER_LOCKING is not set -CONFIG_DM_BIO_PRISON=m -CONFIG_DM_PERSISTENT_DATA=m -# CONFIG_DM_UNSTRIPED is not set -# CONFIG_DM_CRYPT is not set -# CONFIG_DM_SNAPSHOT is not set -CONFIG_DM_THIN_PROVISIONING=m -# CONFIG_DM_CACHE is not set -# CONFIG_DM_WRITECACHE is not set -# CONFIG_DM_EBS is not set -# CONFIG_DM_ERA is not set -# CONFIG_DM_CLONE is not set -# CONFIG_DM_MIRROR is not set -# CONFIG_DM_RAID is not set -# CONFIG_DM_ZERO is not set -# CONFIG_DM_MULTIPATH is not set -# CONFIG_DM_DELAY is not set -# CONFIG_DM_DUST is not set -# CONFIG_DM_INIT is not set -# CONFIG_DM_UEVENT is not set -# CONFIG_DM_FLAKEY is not set -# CONFIG_DM_VERITY is not set -# CONFIG_DM_SWITCH is not set -# CONFIG_DM_LOG_WRITES is not set -# CONFIG_DM_INTEGRITY is not set -# CONFIG_DM_AUDIT is not set -# CONFIG_TARGET_CORE is not set -# CONFIG_FUSION is not set - -# -# IEEE 1394 (FireWire) support -# -# CONFIG_FIREWIRE is not set -# CONFIG_FIREWIRE_NOSY is not set -# end of IEEE 1394 (FireWire) support - -CONFIG_NETDEVICES=y -CONFIG_NET_CORE=y -# CONFIG_BONDING is not set -CONFIG_DUMMY=m -# CONFIG_WIREGUARD is not set -# CONFIG_EQUALIZER is not set -# CONFIG_NET_FC is not set -# CONFIG_NET_TEAM is not set -CONFIG_MACVLAN=m -# CONFIG_MACVTAP is not set -CONFIG_IPVLAN_L3S=y -CONFIG_IPVLAN=m -# CONFIG_IPVTAP is not set -CONFIG_VXLAN=m -# CONFIG_GENEVE is not set -# CONFIG_BAREUDP is not set -# CONFIG_GTP is not set -# CONFIG_AMT is not set -# CONFIG_MACSEC is not set -# CONFIG_NETCONSOLE is not set -# CONFIG_TUN is not set -# CONFIG_TUN_VNET_CROSS_LE is not set -CONFIG_VETH=m -CONFIG_VIRTIO_NET=y -# CONFIG_NLMON is not set -# CONFIG_ARCNET is not set -CONFIG_ETHERNET=y -CONFIG_NET_VENDOR_3COM=y -# CONFIG_VORTEX is not set -# CONFIG_TYPHOON is not set -CONFIG_NET_VENDOR_ADAPTEC=y -# CONFIG_ADAPTEC_STARFIRE is not set -CONFIG_NET_VENDOR_AGERE=y -# CONFIG_ET131X is not set -CONFIG_NET_VENDOR_ALACRITECH=y -# CONFIG_SLICOSS is not set -CONFIG_NET_VENDOR_ALTEON=y -# CONFIG_ACENIC is not set -# CONFIG_ALTERA_TSE is not set -CONFIG_NET_VENDOR_AMAZON=y -# CONFIG_ENA_ETHERNET is not set -CONFIG_NET_VENDOR_AMD=y -# CONFIG_AMD8111_ETH is not set -# CONFIG_PCNET32 is not set -CONFIG_NET_VENDOR_AQUANTIA=y -# CONFIG_AQTION is not set -CONFIG_NET_VENDOR_ARC=y -CONFIG_NET_VENDOR_ASIX=y -# CONFIG_SPI_AX88796C is not set -CONFIG_NET_VENDOR_ATHEROS=y -# CONFIG_ATL2 is not set -# CONFIG_ATL1 is not set -# CONFIG_ATL1E is not set -# CONFIG_ATL1C is not set -# CONFIG_ALX is not set -CONFIG_NET_VENDOR_BROADCOM=y -# CONFIG_B44 is not set -# CONFIG_BCMGENET is not set -# CONFIG_BNX2 is not set -# CONFIG_CNIC is not set -# CONFIG_TIGON3 is not set -# CONFIG_BNX2X is not set -# CONFIG_SYSTEMPORT is not set -# CONFIG_BNXT is not set -CONFIG_NET_VENDOR_CADENCE=y -CONFIG_MACB=y -# CONFIG_MACB_PCI is not set -CONFIG_NET_VENDOR_CAVIUM=y -# CONFIG_THUNDER_NIC_PF is not set -# CONFIG_THUNDER_NIC_VF is not set -# CONFIG_THUNDER_NIC_BGX is not set -# CONFIG_THUNDER_NIC_RGX is not set -# CONFIG_LIQUIDIO is not set -# CONFIG_LIQUIDIO_VF is not set -CONFIG_NET_VENDOR_CHELSIO=y -# CONFIG_CHELSIO_T1 is not set -# CONFIG_CHELSIO_T3 is not set -# CONFIG_CHELSIO_T4 is not set -# CONFIG_CHELSIO_T4VF is not set -CONFIG_NET_VENDOR_CISCO=y -# CONFIG_ENIC is not set -CONFIG_NET_VENDOR_CORTINA=y -# CONFIG_GEMINI_ETHERNET is not set -CONFIG_NET_VENDOR_DAVICOM=y -# CONFIG_DM9051 is not set -# CONFIG_DNET is not set -CONFIG_NET_VENDOR_DEC=y -# CONFIG_NET_TULIP is not set -CONFIG_NET_VENDOR_DLINK=y -# CONFIG_DL2K is not set -# CONFIG_SUNDANCE is not set -CONFIG_NET_VENDOR_EMULEX=y -# CONFIG_BE2NET is not set -CONFIG_NET_VENDOR_ENGLEDER=y -# CONFIG_TSNEP is not set -CONFIG_NET_VENDOR_EZCHIP=y -# CONFIG_EZCHIP_NPS_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_FUNGIBLE=y -# CONFIG_FUN_ETH is not set -CONFIG_NET_VENDOR_GOOGLE=y -CONFIG_NET_VENDOR_HUAWEI=y -CONFIG_NET_VENDOR_I825XX=y -CONFIG_NET_VENDOR_INTEL=y -# CONFIG_E100 is not set -# CONFIG_E1000 is not set -CONFIG_E1000E=y -# CONFIG_IGB is not set -# CONFIG_IGBVF is not set -# CONFIG_IXGB is not set -# CONFIG_IXGBE is not set -# CONFIG_IXGBEVF is not set -# CONFIG_I40E is not set -# CONFIG_I40EVF is not set -# CONFIG_ICE is not set -# CONFIG_FM10K is not set -# CONFIG_IGC is not set -CONFIG_NET_VENDOR_WANGXUN=y -# CONFIG_NGBE is not set -# CONFIG_TXGBE is not set -# CONFIG_JME is not set -CONFIG_NET_VENDOR_ADI=y -CONFIG_NET_VENDOR_LITEX=y -# CONFIG_LITEX_LITEETH is not set -CONFIG_NET_VENDOR_MARVELL=y -# CONFIG_MVMDIO is not set -# CONFIG_SKGE is not set -# CONFIG_SKY2 is not set -# CONFIG_OCTEON_EP is not set -CONFIG_NET_VENDOR_MELLANOX=y -# CONFIG_MLX4_EN is not set -# CONFIG_MLX5_CORE is not set -# CONFIG_MLXSW_CORE is not set -# CONFIG_MLXFW is not set -CONFIG_NET_VENDOR_MICREL=y -# CONFIG_KS8851 is not set -# CONFIG_KS8851_MLL is not set -# CONFIG_KSZ884X_PCI is not set -CONFIG_NET_VENDOR_MICROCHIP=y -# CONFIG_ENC28J60 is not set -# CONFIG_ENCX24J600 is not set -# CONFIG_LAN743X is not set -# CONFIG_VCAP is not set -CONFIG_NET_VENDOR_MICROSEMI=y -CONFIG_NET_VENDOR_MICROSOFT=y -CONFIG_NET_VENDOR_MYRI=y -# CONFIG_MYRI10GE is not set -# CONFIG_FEALNX is not set -CONFIG_NET_VENDOR_NI=y -# CONFIG_NI_XGE_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_NATSEMI=y -# CONFIG_NATSEMI is not set -# CONFIG_NS83820 is not set -CONFIG_NET_VENDOR_NETERION=y -# CONFIG_S2IO is not set -CONFIG_NET_VENDOR_NETRONOME=y -# CONFIG_NFP is not set -CONFIG_NET_VENDOR_8390=y -# CONFIG_NE2K_PCI is not set -CONFIG_NET_VENDOR_NVIDIA=y -# CONFIG_FORCEDETH is not set -CONFIG_NET_VENDOR_OKI=y -# CONFIG_ETHOC is not set -CONFIG_NET_VENDOR_PACKET_ENGINES=y -# CONFIG_HAMACHI is not set -# CONFIG_YELLOWFIN is not set -CONFIG_NET_VENDOR_PENSANDO=y -# CONFIG_IONIC is not set -CONFIG_NET_VENDOR_QLOGIC=y -# CONFIG_QLA3XXX is not set -# CONFIG_QLCNIC is not set -# CONFIG_NETXEN_NIC is not set -# CONFIG_QED is not set -CONFIG_NET_VENDOR_BROCADE=y -# CONFIG_BNA is not set -CONFIG_NET_VENDOR_QUALCOMM=y -# CONFIG_QCA7000_SPI is not set -# CONFIG_QCOM_EMAC is not set -# CONFIG_RMNET is not set -CONFIG_NET_VENDOR_RDC=y -# CONFIG_R6040 is not set -CONFIG_NET_VENDOR_REALTEK=y -# CONFIG_8139CP is not set -# CONFIG_8139TOO is not set -CONFIG_R8169=y -CONFIG_NET_VENDOR_RENESAS=y -# CONFIG_SH_ETH is not set -# CONFIG_RAVB is not set -# CONFIG_RENESAS_ETHER_SWITCH is not set -CONFIG_NET_VENDOR_ROCKER=y -CONFIG_NET_VENDOR_SAMSUNG=y -# CONFIG_SXGBE_ETH is not set -CONFIG_NET_VENDOR_SEEQ=y -CONFIG_NET_VENDOR_SILAN=y -# CONFIG_SC92031 is not set -CONFIG_NET_VENDOR_SIS=y -# CONFIG_SIS900 is not set -# CONFIG_SIS190 is not set -CONFIG_NET_VENDOR_SOLARFLARE=y -# CONFIG_SFC is not set -# CONFIG_SFC_FALCON is not set -CONFIG_NET_VENDOR_SMSC=y -# CONFIG_EPIC100 is not set -# CONFIG_SMSC911X is not set -# CONFIG_SMSC9420 is not set -CONFIG_NET_VENDOR_SOCIONEXT=y -CONFIG_NET_VENDOR_STMICRO=y -# CONFIG_STMMAC_ETH is not set -CONFIG_NET_VENDOR_SUN=y -# CONFIG_HAPPYMEAL is not set -# CONFIG_SUNGEM is not set -# CONFIG_CASSINI is not set -# CONFIG_NIU is not set -CONFIG_NET_VENDOR_SYNOPSYS=y -# CONFIG_DWC_XLGMAC is not set -CONFIG_NET_VENDOR_TEHUTI=y -# CONFIG_TEHUTI is not set -CONFIG_NET_VENDOR_TI=y -# CONFIG_TI_CPSW_PHY_SEL is not set -# CONFIG_TLAN is not set -CONFIG_NET_VENDOR_VERTEXCOM=y -# CONFIG_MSE102X is not set -CONFIG_NET_VENDOR_VIA=y -# CONFIG_VIA_RHINE is not set -# CONFIG_VIA_VELOCITY is not set -CONFIG_NET_VENDOR_WIZNET=y -# CONFIG_WIZNET_W5100 is not set -# CONFIG_WIZNET_W5300 is not set -CONFIG_NET_VENDOR_XILINX=y -# CONFIG_XILINX_EMACLITE is not set -# CONFIG_XILINX_AXI_EMAC is not set -# CONFIG_XILINX_LL_TEMAC is not set -# CONFIG_FDDI is not set -# CONFIG_HIPPI is not set -CONFIG_PHYLINK=y -CONFIG_PHYLIB=y -CONFIG_SWPHY=y -CONFIG_FIXED_PHY=y -# CONFIG_SFP is not set - -# -# MII PHY device drivers -# -# CONFIG_AMD_PHY is not set -# CONFIG_ADIN_PHY is not set -# CONFIG_ADIN1100_PHY is not set -# CONFIG_AQUANTIA_PHY is not set -# CONFIG_AX88796B_PHY is not set -# CONFIG_BROADCOM_PHY is not set -# CONFIG_BCM54140_PHY is not set -# CONFIG_BCM7XXX_PHY is not set -# CONFIG_BCM84881_PHY is not set -# CONFIG_BCM87XX_PHY is not set -# CONFIG_CICADA_PHY is not set -# CONFIG_CORTINA_PHY is not set -# CONFIG_DAVICOM_PHY is not set -# CONFIG_ICPLUS_PHY is not set -# CONFIG_LXT_PHY is not set -# CONFIG_INTEL_XWAY_PHY is not set -# CONFIG_LSI_ET1011C_PHY is not set -# CONFIG_MARVELL_PHY is not set -# CONFIG_MARVELL_10G_PHY is not set -# CONFIG_MARVELL_88X2222_PHY is not set -# CONFIG_MAXLINEAR_GPHY is not set -# CONFIG_MEDIATEK_GE_PHY is not set -# CONFIG_MICREL_PHY is not set -# CONFIG_MICROCHIP_PHY is not set -# CONFIG_MICROCHIP_T1_PHY is not set -CONFIG_MICROSEMI_PHY=y -# CONFIG_MOTORCOMM_PHY is not set -# CONFIG_NATIONAL_PHY is not set -# CONFIG_NXP_C45_TJA11XX_PHY is not set -# CONFIG_NXP_TJA11XX_PHY is not set -# CONFIG_QSEMI_PHY is not set -CONFIG_REALTEK_PHY=y -# CONFIG_RENESAS_PHY is not set -# CONFIG_ROCKCHIP_PHY is not set -# CONFIG_SMSC_PHY is not set -# CONFIG_STE10XP is not set -# CONFIG_TERANETICS_PHY is not set -# CONFIG_DP83822_PHY is not set -# CONFIG_DP83TC811_PHY is not set -# CONFIG_DP83848_PHY is not set -# CONFIG_DP83867_PHY is not set -# CONFIG_DP83869_PHY is not set -# CONFIG_DP83TD510_PHY is not set -# CONFIG_VITESSE_PHY is not set -# CONFIG_XILINX_GMII2RGMII is not set -# CONFIG_MICREL_KS8995MA is not set -# CONFIG_PSE_CONTROLLER is not set -CONFIG_MDIO_DEVICE=y -CONFIG_MDIO_BUS=y -CONFIG_FWNODE_MDIO=y -CONFIG_OF_MDIO=y -CONFIG_MDIO_DEVRES=y -# CONFIG_MDIO_BITBANG is not set -# CONFIG_MDIO_BCM_UNIMAC is not set -# CONFIG_MDIO_HISI_FEMAC is not set -# CONFIG_MDIO_MVUSB is not set -# CONFIG_MDIO_MSCC_MIIM is not set -# CONFIG_MDIO_OCTEON is not set -# CONFIG_MDIO_IPQ4019 is not set -# CONFIG_MDIO_IPQ8064 is not set -# CONFIG_MDIO_THUNDER is not set - -# -# MDIO Multiplexers -# -# CONFIG_MDIO_BUS_MUX_GPIO is not set -# CONFIG_MDIO_BUS_MUX_MULTIPLEXER is not set -# CONFIG_MDIO_BUS_MUX_MMIOREG is not set - -# -# PCS device drivers -# -# end of PCS device drivers - -# CONFIG_PPP is not set -# CONFIG_SLIP is not set -CONFIG_USB_NET_DRIVERS=y -# CONFIG_USB_CATC is not set -# CONFIG_USB_KAWETH is not set -# CONFIG_USB_PEGASUS is not set -# CONFIG_USB_RTL8150 is not set -# CONFIG_USB_RTL8152 is not set -# CONFIG_USB_LAN78XX is not set -# CONFIG_USB_USBNET is not set -# CONFIG_USB_IPHETH is not set -CONFIG_WLAN=y -CONFIG_WLAN_VENDOR_ADMTEK=y -CONFIG_WLAN_VENDOR_ATH=y -# CONFIG_ATH_DEBUG is not set -# CONFIG_ATH5K_PCI is not set -CONFIG_WLAN_VENDOR_ATMEL=y -CONFIG_WLAN_VENDOR_BROADCOM=y -CONFIG_WLAN_VENDOR_CISCO=y -CONFIG_WLAN_VENDOR_INTEL=y -CONFIG_WLAN_VENDOR_INTERSIL=y -# CONFIG_HOSTAP is not set -CONFIG_WLAN_VENDOR_MARVELL=y -CONFIG_WLAN_VENDOR_MEDIATEK=y -CONFIG_WLAN_VENDOR_MICROCHIP=y -CONFIG_WLAN_VENDOR_PURELIFI=y -CONFIG_WLAN_VENDOR_RALINK=y -CONFIG_WLAN_VENDOR_REALTEK=y -CONFIG_WLAN_VENDOR_RSI=y -CONFIG_WLAN_VENDOR_SILABS=y -CONFIG_WLAN_VENDOR_ST=y -CONFIG_WLAN_VENDOR_TI=y -CONFIG_WLAN_VENDOR_ZYDAS=y -CONFIG_WLAN_VENDOR_QUANTENNA=y -# CONFIG_WAN is not set - -# -# Wireless WAN -# -# CONFIG_WWAN is not set -# end of Wireless WAN - -# CONFIG_VMXNET3 is not set -# CONFIG_NETDEVSIM is not set -CONFIG_NET_FAILOVER=y -# CONFIG_ISDN is not set - -# -# Input device support -# -CONFIG_INPUT=y -# CONFIG_INPUT_FF_MEMLESS is not set -# CONFIG_INPUT_SPARSEKMAP is not set -# CONFIG_INPUT_MATRIXKMAP is not set -CONFIG_INPUT_VIVALDIFMAP=y - -# -# Userland interfaces -# -CONFIG_INPUT_MOUSEDEV=y -# CONFIG_INPUT_MOUSEDEV_PSAUX is not set -CONFIG_INPUT_MOUSEDEV_SCREEN_X=1024 -CONFIG_INPUT_MOUSEDEV_SCREEN_Y=768 -# CONFIG_INPUT_JOYDEV is not set -# CONFIG_INPUT_EVDEV is not set -# CONFIG_INPUT_EVBUG is not set - -# -# Input Device Drivers -# -CONFIG_INPUT_KEYBOARD=y -# CONFIG_KEYBOARD_ADC is not set -# CONFIG_KEYBOARD_ADP5588 is not set -# CONFIG_KEYBOARD_ADP5589 is not set -CONFIG_KEYBOARD_ATKBD=y -# CONFIG_KEYBOARD_QT1050 is not set -# CONFIG_KEYBOARD_QT1070 is not set -# CONFIG_KEYBOARD_QT2160 is not set -# CONFIG_KEYBOARD_DLINK_DIR685 is not set -# CONFIG_KEYBOARD_LKKBD is not set -# CONFIG_KEYBOARD_GPIO is not set -# CONFIG_KEYBOARD_GPIO_POLLED is not set -# CONFIG_KEYBOARD_TCA6416 is not set -# CONFIG_KEYBOARD_TCA8418 is not set -# CONFIG_KEYBOARD_MATRIX is not set -# CONFIG_KEYBOARD_LM8333 is not set -# CONFIG_KEYBOARD_MAX7359 is not set -# CONFIG_KEYBOARD_MCS is not set -# CONFIG_KEYBOARD_MPR121 is not set -# CONFIG_KEYBOARD_NEWTON is not set -# CONFIG_KEYBOARD_OPENCORES is not set -# CONFIG_KEYBOARD_SAMSUNG is not set -# CONFIG_KEYBOARD_GOLDFISH_EVENTS is not set -# CONFIG_KEYBOARD_STOWAWAY is not set -# CONFIG_KEYBOARD_SUNKBD is not set -# CONFIG_KEYBOARD_OMAP4 is not set -# CONFIG_KEYBOARD_XTKBD is not set -# CONFIG_KEYBOARD_CAP11XX is not set -# CONFIG_KEYBOARD_BCM is not set -# CONFIG_KEYBOARD_CYPRESS_SF is not set -CONFIG_INPUT_MOUSE=y -CONFIG_MOUSE_PS2=y -CONFIG_MOUSE_PS2_ALPS=y -CONFIG_MOUSE_PS2_BYD=y -CONFIG_MOUSE_PS2_LOGIPS2PP=y -CONFIG_MOUSE_PS2_SYNAPTICS=y -CONFIG_MOUSE_PS2_SYNAPTICS_SMBUS=y -CONFIG_MOUSE_PS2_CYPRESS=y -CONFIG_MOUSE_PS2_TRACKPOINT=y -# CONFIG_MOUSE_PS2_ELANTECH is not set -# CONFIG_MOUSE_PS2_SENTELIC is not set -# CONFIG_MOUSE_PS2_TOUCHKIT is not set -CONFIG_MOUSE_PS2_FOCALTECH=y -CONFIG_MOUSE_PS2_SMBUS=y -# CONFIG_MOUSE_SERIAL is not set -# CONFIG_MOUSE_APPLETOUCH is not set -# CONFIG_MOUSE_BCM5974 is not set -# CONFIG_MOUSE_CYAPA is not set -# CONFIG_MOUSE_ELAN_I2C is not set -# CONFIG_MOUSE_VSXXXAA is not set -# CONFIG_MOUSE_GPIO is not set -# CONFIG_MOUSE_SYNAPTICS_I2C is not set -# CONFIG_MOUSE_SYNAPTICS_USB is not set -# CONFIG_INPUT_JOYSTICK is not set -# CONFIG_INPUT_TABLET is not set -# CONFIG_INPUT_TOUCHSCREEN is not set -# CONFIG_INPUT_MISC is not set -# CONFIG_RMI4_CORE is not set - -# -# Hardware I/O ports -# -CONFIG_SERIO=y -CONFIG_SERIO_SERPORT=y -# CONFIG_SERIO_PCIPS2 is not set -CONFIG_SERIO_LIBPS2=y -# CONFIG_SERIO_RAW is not set -# CONFIG_SERIO_ALTERA_PS2 is not set -# CONFIG_SERIO_PS2MULT is not set -# CONFIG_SERIO_ARC_PS2 is not set -# CONFIG_SERIO_APBPS2 is not set -# CONFIG_SERIO_GPIO_PS2 is not set -# CONFIG_USERIO is not set -# CONFIG_GAMEPORT is not set -# end of Hardware I/O ports -# end of Input device support - -# -# Character devices -# -CONFIG_TTY=y -CONFIG_VT=y -CONFIG_CONSOLE_TRANSLATIONS=y -CONFIG_VT_CONSOLE=y -CONFIG_HW_CONSOLE=y -CONFIG_VT_HW_CONSOLE_BINDING=y -CONFIG_UNIX98_PTYS=y -CONFIG_LEGACY_PTYS=y -CONFIG_LEGACY_PTY_COUNT=256 -CONFIG_LEGACY_TIOCSTI=y -CONFIG_LDISC_AUTOLOAD=y - -# -# Serial drivers -# -CONFIG_SERIAL_EARLYCON=y -CONFIG_SERIAL_8250=y -CONFIG_SERIAL_8250_DEPRECATED_OPTIONS=y -CONFIG_SERIAL_8250_16550A_VARIANTS=y -# CONFIG_SERIAL_8250_FINTEK is not set -CONFIG_SERIAL_8250_CONSOLE=y -CONFIG_SERIAL_8250_PCI=y -CONFIG_SERIAL_8250_EXAR=y -CONFIG_SERIAL_8250_NR_UARTS=4 -CONFIG_SERIAL_8250_RUNTIME_UARTS=4 -# CONFIG_SERIAL_8250_EXTENDED is not set -CONFIG_SERIAL_8250_DWLIB=y -CONFIG_SERIAL_8250_DW=y -# CONFIG_SERIAL_8250_EM is not set -# CONFIG_SERIAL_8250_RT288X is not set -CONFIG_SERIAL_8250_PERICOM=y -CONFIG_SERIAL_OF_PLATFORM=y - -# -# Non-8250 serial port support -# -# CONFIG_SERIAL_MAX3100 is not set -# CONFIG_SERIAL_MAX310X is not set -# CONFIG_SERIAL_UARTLITE is not set -CONFIG_SERIAL_SH_SCI=y -CONFIG_SERIAL_SH_SCI_NR_UARTS=18 -CONFIG_SERIAL_SH_SCI_CONSOLE=y -CONFIG_SERIAL_SH_SCI_EARLYCON=y -CONFIG_SERIAL_CORE=y -CONFIG_SERIAL_CORE_CONSOLE=y -# CONFIG_SERIAL_JSM is not set -CONFIG_SERIAL_SIFIVE=y -CONFIG_SERIAL_SIFIVE_CONSOLE=y -# CONFIG_SERIAL_SCCNXP is not set -# CONFIG_SERIAL_SC16IS7XX is not set -# CONFIG_SERIAL_ALTERA_JTAGUART is not set -# CONFIG_SERIAL_ALTERA_UART is not set -# CONFIG_SERIAL_XILINX_PS_UART is not set -# CONFIG_SERIAL_ARC is not set -# CONFIG_SERIAL_RP2 is not set -# CONFIG_SERIAL_FSL_LPUART is not set -# CONFIG_SERIAL_FSL_LINFLEXUART is not set -# CONFIG_SERIAL_CONEXANT_DIGICOLOR is not set -# CONFIG_SERIAL_SPRD is not set -# end of Serial drivers - -CONFIG_SERIAL_MCTRL_GPIO=y -# CONFIG_SERIAL_NONSTANDARD is not set -# CONFIG_GOLDFISH_TTY is not set -# CONFIG_N_GSM is not set -# CONFIG_NOZOMI is not set -# CONFIG_NULL_TTY is not set -CONFIG_HVC_DRIVER=y -# CONFIG_RPMSG_TTY is not set -# CONFIG_SERIAL_DEV_BUS is not set -# CONFIG_TTY_PRINTK is not set -CONFIG_VIRTIO_CONSOLE=y -# CONFIG_IPMI_HANDLER is not set -CONFIG_HW_RANDOM=y -# CONFIG_HW_RANDOM_TIMERIOMEM is not set -# CONFIG_HW_RANDOM_BA431 is not set -CONFIG_HW_RANDOM_VIRTIO=y -CONFIG_HW_RANDOM_POLARFIRE_SOC=y -# CONFIG_HW_RANDOM_CCTRNG is not set -# CONFIG_HW_RANDOM_XIPHERA is not set -# CONFIG_APPLICOM is not set -CONFIG_DEVMEM=y -CONFIG_DEVPORT=y -# CONFIG_TCG_TPM is not set -# CONFIG_XILLYBUS is not set -# CONFIG_XILLYUSB is not set -# end of Character devices - -# -# I2C support -# -CONFIG_I2C=y -CONFIG_I2C_BOARDINFO=y -CONFIG_I2C_COMPAT=y -# CONFIG_I2C_CHARDEV is not set -CONFIG_I2C_MUX=m - -# -# Multiplexer I2C Chip support -# -# CONFIG_I2C_ARB_GPIO_CHALLENGE is not set -# CONFIG_I2C_MUX_GPIO is not set -# CONFIG_I2C_MUX_GPMUX is not set -# CONFIG_I2C_MUX_LTC4306 is not set -# CONFIG_I2C_MUX_PCA9541 is not set -# CONFIG_I2C_MUX_PCA954x is not set -# CONFIG_I2C_MUX_PINCTRL is not set -# CONFIG_I2C_MUX_REG is not set -# CONFIG_I2C_DEMUX_PINCTRL is not set -# CONFIG_I2C_MUX_MLXCPLD is not set -# end of Multiplexer I2C Chip support - -CONFIG_I2C_HELPER_AUTO=y - -# -# I2C Hardware Bus support -# - -# -# PC SMBus host controller drivers -# -# CONFIG_I2C_ALI1535 is not set -# CONFIG_I2C_ALI1563 is not set -# CONFIG_I2C_ALI15X3 is not set -# CONFIG_I2C_AMD756 is not set -# CONFIG_I2C_AMD8111 is not set -# CONFIG_I2C_I801 is not set -# CONFIG_I2C_ISCH is not set -# CONFIG_I2C_PIIX4 is not set -# CONFIG_I2C_NFORCE2 is not set -# CONFIG_I2C_NVIDIA_GPU is not set -# CONFIG_I2C_SIS5595 is not set -# CONFIG_I2C_SIS630 is not set -# CONFIG_I2C_SIS96X is not set -# CONFIG_I2C_VIA is not set -# CONFIG_I2C_VIAPRO is not set - -# -# I2C system bus drivers (mostly embedded / system-on-chip) -# -# CONFIG_I2C_CBUS_GPIO is not set -# CONFIG_I2C_DESIGNWARE_PLATFORM is not set -# CONFIG_I2C_DESIGNWARE_PCI is not set -# CONFIG_I2C_EMEV2 is not set -# CONFIG_I2C_GPIO is not set -CONFIG_I2C_MICROCHIP_CORE=y -# CONFIG_I2C_OCORES is not set -# CONFIG_I2C_PCA_PLATFORM is not set -# CONFIG_I2C_RIIC is not set -# CONFIG_I2C_RK3X is not set -# CONFIG_I2C_RZV2M is not set -# CONFIG_I2C_SH_MOBILE is not set -# CONFIG_I2C_SIMTEC is not set -# CONFIG_I2C_XILINX is not set -# CONFIG_I2C_RCAR is not set - -# -# External I2C/SMBus adapter drivers -# -# CONFIG_I2C_DIOLAN_U2C is not set -# CONFIG_I2C_CP2615 is not set -# CONFIG_I2C_PCI1XXXX is not set -# CONFIG_I2C_ROBOTFUZZ_OSIF is not set -# CONFIG_I2C_TAOS_EVM is not set -# CONFIG_I2C_TINY_USB is not set - -# -# Other I2C/SMBus bus drivers -# -# CONFIG_I2C_VIRTIO is not set -# end of I2C Hardware Bus support - -# CONFIG_I2C_STUB is not set -# CONFIG_I2C_SLAVE is not set -# CONFIG_I2C_DEBUG_CORE is not set -# CONFIG_I2C_DEBUG_ALGO is not set -# CONFIG_I2C_DEBUG_BUS is not set -# end of I2C support - -# CONFIG_I3C is not set -CONFIG_SPI=y -# CONFIG_SPI_DEBUG is not set -CONFIG_SPI_MASTER=y -# CONFIG_SPI_MEM is not set - -# -# SPI Master Controller Drivers -# -# CONFIG_SPI_ALTERA is not set -# CONFIG_SPI_AXI_SPI_ENGINE is not set -# CONFIG_SPI_BITBANG is not set -# CONFIG_SPI_CADENCE is not set -# CONFIG_SPI_DESIGNWARE is not set -# CONFIG_SPI_NXP_FLEXSPI is not set -# CONFIG_SPI_GPIO is not set -# CONFIG_SPI_FSL_SPI is not set -CONFIG_SPI_MICROCHIP_CORE=y -CONFIG_SPI_MICROCHIP_CORE_QSPI=y -# CONFIG_SPI_OC_TINY is not set -# CONFIG_SPI_PCI1XXXX is not set -# CONFIG_SPI_PXA2XX is not set -# CONFIG_SPI_ROCKCHIP is not set -# CONFIG_SPI_RSPI is not set -# CONFIG_SPI_SC18IS602 is not set -# CONFIG_SPI_SH_MSIOF is not set -# CONFIG_SPI_SH_HSPI is not set -CONFIG_SPI_SIFIVE=y -# CONFIG_SPI_MXIC is not set -# CONFIG_SPI_XCOMM is not set -# CONFIG_SPI_XILINX is not set -# CONFIG_SPI_ZYNQMP_GQSPI is not set -# CONFIG_SPI_AMD is not set - -# -# SPI Multiplexer support -# -# CONFIG_SPI_MUX is not set - -# -# SPI Protocol Masters -# -CONFIG_SPI_SPIDEV=m -# CONFIG_SPI_LOOPBACK_TEST is not set -# CONFIG_SPI_TLE62X0 is not set -# CONFIG_SPI_SLAVE is not set -CONFIG_SPI_DYNAMIC=y -# CONFIG_SPMI is not set -# CONFIG_HSI is not set -# CONFIG_PPS is not set - -# -# PTP clock support -# -# CONFIG_PTP_1588_CLOCK is not set -CONFIG_PTP_1588_CLOCK_OPTIONAL=y - -# -# Enable PHYLIB and NETWORK_PHY_TIMESTAMPING to see the additional clocks. -# -# end of PTP clock support - -CONFIG_PINCTRL=y -CONFIG_GENERIC_PINCTRL_GROUPS=y -CONFIG_PINMUX=y -CONFIG_GENERIC_PINMUX_FUNCTIONS=y -CONFIG_PINCONF=y -CONFIG_GENERIC_PINCONF=y -# CONFIG_DEBUG_PINCTRL is not set -# CONFIG_PINCTRL_CY8C95X0 is not set -# CONFIG_PINCTRL_MCP23S08 is not set -# CONFIG_PINCTRL_MICROCHIP_SGPIO is not set -# CONFIG_PINCTRL_OCELOT is not set -# CONFIG_PINCTRL_SINGLE is not set -# CONFIG_PINCTRL_STMFX is not set -# CONFIG_PINCTRL_SX150X is not set - -# -# Renesas pinctrl drivers -# -CONFIG_PINCTRL_RENESAS=y -CONFIG_PINCTRL_RZG2L=y -# end of Renesas pinctrl drivers - -CONFIG_PINCTRL_STARFIVE_JH7100=y -CONFIG_GPIOLIB=y -CONFIG_GPIOLIB_FASTPATH_LIMIT=512 -CONFIG_OF_GPIO=y -CONFIG_GPIOLIB_IRQCHIP=y -# CONFIG_DEBUG_GPIO is not set -CONFIG_GPIO_SYSFS=y -CONFIG_GPIO_CDEV=y -CONFIG_GPIO_CDEV_V1=y -CONFIG_GPIO_GENERIC=y - -# -# Memory mapped GPIO drivers -# -# CONFIG_GPIO_74XX_MMIO is not set -# CONFIG_GPIO_ALTERA is not set -# CONFIG_GPIO_CADENCE is not set -# CONFIG_GPIO_DWAPB is not set -# CONFIG_GPIO_EXAR is not set -# CONFIG_GPIO_FTGPIO010 is not set -# CONFIG_GPIO_GENERIC_PLATFORM is not set -# CONFIG_GPIO_GRGPIO is not set -# CONFIG_GPIO_HLWD is not set -# CONFIG_GPIO_LOGICVC is not set -# CONFIG_GPIO_MB86S7X is not set -# CONFIG_GPIO_RCAR is not set -CONFIG_GPIO_SIFIVE=y -# CONFIG_GPIO_SYSCON is not set -# CONFIG_GPIO_XILINX is not set -# CONFIG_GPIO_AMD_FCH is not set -# end of Memory mapped GPIO drivers - -# -# I2C GPIO expanders -# -# CONFIG_GPIO_ADNP is not set -# CONFIG_GPIO_GW_PLD is not set -# CONFIG_GPIO_MAX7300 is not set -# CONFIG_GPIO_MAX732X is not set -# CONFIG_GPIO_PCA953X is not set -# CONFIG_GPIO_PCA9570 is not set -# CONFIG_GPIO_PCF857X is not set -# CONFIG_GPIO_TPIC2810 is not set -# end of I2C GPIO expanders - -# -# MFD GPIO expanders -# -# end of MFD GPIO expanders - -# -# PCI GPIO expanders -# -# CONFIG_GPIO_BT8XX is not set -# CONFIG_GPIO_PCI_IDIO_16 is not set -# CONFIG_GPIO_PCIE_IDIO_24 is not set -# CONFIG_GPIO_RDC321X is not set -# end of PCI GPIO expanders - -# -# SPI GPIO expanders -# -# CONFIG_GPIO_74X164 is not set -# CONFIG_GPIO_MAX3191X is not set -# CONFIG_GPIO_MAX7301 is not set -# CONFIG_GPIO_MC33880 is not set -# CONFIG_GPIO_PISOSR is not set -# CONFIG_GPIO_XRA1403 is not set -# end of SPI GPIO expanders - -# -# USB GPIO expanders -# -# end of USB GPIO expanders - -# -# Virtual GPIO drivers -# -# CONFIG_GPIO_AGGREGATOR is not set -# CONFIG_GPIO_LATCH is not set -# CONFIG_GPIO_MOCKUP is not set -# CONFIG_GPIO_VIRTIO is not set -# CONFIG_GPIO_SIM is not set -# end of Virtual GPIO drivers - -# CONFIG_W1 is not set -CONFIG_POWER_RESET=y -# CONFIG_POWER_RESET_GPIO is not set -# CONFIG_POWER_RESET_GPIO_RESTART is not set -# CONFIG_POWER_RESET_LTC2952 is not set -# CONFIG_POWER_RESET_RESTART is not set -CONFIG_POWER_RESET_SYSCON=y -CONFIG_POWER_RESET_SYSCON_POWEROFF=y -# CONFIG_SYSCON_REBOOT_MODE is not set -# CONFIG_NVMEM_REBOOT_MODE is not set -CONFIG_POWER_SUPPLY=y -# CONFIG_POWER_SUPPLY_DEBUG is not set -CONFIG_POWER_SUPPLY_HWMON=y -# CONFIG_PDA_POWER is not set -# CONFIG_GENERIC_ADC_BATTERY is not set -# CONFIG_IP5XXX_POWER is not set -# CONFIG_TEST_POWER is not set -# CONFIG_CHARGER_ADP5061 is not set -# CONFIG_BATTERY_CW2015 is not set -# CONFIG_BATTERY_DS2780 is not set -# CONFIG_BATTERY_DS2781 is not set -# CONFIG_BATTERY_DS2782 is not set -# CONFIG_BATTERY_SAMSUNG_SDI is not set -# CONFIG_BATTERY_SBS is not set -# CONFIG_CHARGER_SBS is not set -# CONFIG_MANAGER_SBS is not set -# CONFIG_BATTERY_BQ27XXX is not set -# CONFIG_BATTERY_MAX17040 is not set -# CONFIG_BATTERY_MAX17042 is not set -# CONFIG_CHARGER_ISP1704 is not set -# CONFIG_CHARGER_MAX8903 is not set -# CONFIG_CHARGER_LP8727 is not set -# CONFIG_CHARGER_GPIO is not set -# CONFIG_CHARGER_LT3651 is not set -# CONFIG_CHARGER_LTC4162L is not set -# CONFIG_CHARGER_DETECTOR_MAX14656 is not set -# CONFIG_CHARGER_MAX77976 is not set -# CONFIG_CHARGER_BQ2415X is not set -# CONFIG_CHARGER_BQ24190 is not set -# CONFIG_CHARGER_BQ24257 is not set -# CONFIG_CHARGER_BQ24735 is not set -# CONFIG_CHARGER_BQ2515X is not set -# CONFIG_CHARGER_BQ25890 is not set -# CONFIG_CHARGER_BQ25980 is not set -# CONFIG_CHARGER_BQ256XX is not set -# CONFIG_BATTERY_GAUGE_LTC2941 is not set -# CONFIG_BATTERY_GOLDFISH is not set -# CONFIG_BATTERY_RT5033 is not set -# CONFIG_CHARGER_RT9455 is not set -# CONFIG_CHARGER_BD99954 is not set -# CONFIG_BATTERY_UG3105 is not set -CONFIG_HWMON=y -# CONFIG_HWMON_DEBUG_CHIP is not set - -# -# Native drivers -# -# CONFIG_SENSORS_AD7314 is not set -# CONFIG_SENSORS_AD7414 is not set -# CONFIG_SENSORS_AD7418 is not set -# CONFIG_SENSORS_ADM1021 is not set -# CONFIG_SENSORS_ADM1025 is not set -# CONFIG_SENSORS_ADM1026 is not set -# CONFIG_SENSORS_ADM1029 is not set -# CONFIG_SENSORS_ADM1031 is not set -# CONFIG_SENSORS_ADM1177 is not set -# CONFIG_SENSORS_ADM9240 is not set -# CONFIG_SENSORS_ADT7310 is not set -# CONFIG_SENSORS_ADT7410 is not set -# CONFIG_SENSORS_ADT7411 is not set -# CONFIG_SENSORS_ADT7462 is not set -# CONFIG_SENSORS_ADT7470 is not set -# CONFIG_SENSORS_ADT7475 is not set -# CONFIG_SENSORS_AHT10 is not set -# CONFIG_SENSORS_AQUACOMPUTER_D5NEXT is not set -# CONFIG_SENSORS_AS370 is not set -# CONFIG_SENSORS_ASC7621 is not set -# CONFIG_SENSORS_AXI_FAN_CONTROL is not set -# CONFIG_SENSORS_ATXP1 is not set -# CONFIG_SENSORS_CORSAIR_CPRO is not set -# CONFIG_SENSORS_CORSAIR_PSU is not set -# CONFIG_SENSORS_DRIVETEMP is not set -# CONFIG_SENSORS_DS620 is not set -# CONFIG_SENSORS_DS1621 is not set -# CONFIG_SENSORS_I5K_AMB is not set -# CONFIG_SENSORS_F71805F is not set -# CONFIG_SENSORS_F71882FG is not set -# CONFIG_SENSORS_F75375S is not set -# CONFIG_SENSORS_GL518SM is not set -# CONFIG_SENSORS_GL520SM is not set -# CONFIG_SENSORS_G760A is not set -# CONFIG_SENSORS_G762 is not set -# CONFIG_SENSORS_GPIO_FAN is not set -# CONFIG_SENSORS_HIH6130 is not set -# CONFIG_SENSORS_IIO_HWMON is not set -# CONFIG_SENSORS_IT87 is not set -# CONFIG_SENSORS_JC42 is not set -# CONFIG_SENSORS_POWR1220 is not set -# CONFIG_SENSORS_LINEAGE is not set -# CONFIG_SENSORS_LTC2945 is not set -# CONFIG_SENSORS_LTC2947_I2C is not set -# CONFIG_SENSORS_LTC2947_SPI is not set -# CONFIG_SENSORS_LTC2990 is not set -# CONFIG_SENSORS_LTC2992 is not set -# CONFIG_SENSORS_LTC4151 is not set -# CONFIG_SENSORS_LTC4215 is not set -# CONFIG_SENSORS_LTC4222 is not set -# CONFIG_SENSORS_LTC4245 is not set -# CONFIG_SENSORS_LTC4260 is not set -# CONFIG_SENSORS_LTC4261 is not set -# CONFIG_SENSORS_MAX1111 is not set -# CONFIG_SENSORS_MAX127 is not set -# CONFIG_SENSORS_MAX16065 is not set -# CONFIG_SENSORS_MAX1619 is not set -# CONFIG_SENSORS_MAX1668 is not set -# CONFIG_SENSORS_MAX197 is not set -# CONFIG_SENSORS_MAX31722 is not set -# CONFIG_SENSORS_MAX31730 is not set -# CONFIG_SENSORS_MAX31760 is not set -# CONFIG_SENSORS_MAX6620 is not set -# CONFIG_SENSORS_MAX6621 is not set -# CONFIG_SENSORS_MAX6639 is not set -# CONFIG_SENSORS_MAX6642 is not set -# CONFIG_SENSORS_MAX6650 is not set -# CONFIG_SENSORS_MAX6697 is not set -# CONFIG_SENSORS_MAX31790 is not set -# CONFIG_SENSORS_MCP3021 is not set -# CONFIG_SENSORS_TC654 is not set -# CONFIG_SENSORS_TPS23861 is not set -# CONFIG_SENSORS_MR75203 is not set -# CONFIG_SENSORS_ADCXX is not set -# CONFIG_SENSORS_LM63 is not set -# CONFIG_SENSORS_LM70 is not set -# CONFIG_SENSORS_LM73 is not set -# CONFIG_SENSORS_LM75 is not set -# CONFIG_SENSORS_LM77 is not set -# CONFIG_SENSORS_LM78 is not set -# CONFIG_SENSORS_LM80 is not set -# CONFIG_SENSORS_LM83 is not set -# CONFIG_SENSORS_LM85 is not set -# CONFIG_SENSORS_LM87 is not set -# CONFIG_SENSORS_LM90 is not set -# CONFIG_SENSORS_LM92 is not set -# CONFIG_SENSORS_LM93 is not set -# CONFIG_SENSORS_LM95234 is not set -# CONFIG_SENSORS_LM95241 is not set -# CONFIG_SENSORS_LM95245 is not set -# CONFIG_SENSORS_PC87360 is not set -# CONFIG_SENSORS_PC87427 is not set -# CONFIG_SENSORS_NTC_THERMISTOR is not set -# CONFIG_SENSORS_NCT6683 is not set -# CONFIG_SENSORS_NCT6775_I2C is not set -# CONFIG_SENSORS_NCT7802 is not set -# CONFIG_SENSORS_NPCM7XX is not set -# CONFIG_SENSORS_NZXT_KRAKEN2 is not set -# CONFIG_SENSORS_NZXT_SMART2 is not set -# CONFIG_SENSORS_OCC_P8_I2C is not set -# CONFIG_SENSORS_PCF8591 is not set -# CONFIG_PMBUS is not set -# CONFIG_SENSORS_SBTSI is not set -# CONFIG_SENSORS_SBRMI is not set -# CONFIG_SENSORS_SHT15 is not set -# CONFIG_SENSORS_SHT21 is not set -# CONFIG_SENSORS_SHT3x is not set -# CONFIG_SENSORS_SHT4x is not set -# CONFIG_SENSORS_SHTC1 is not set -# CONFIG_SENSORS_SIS5595 is not set -# CONFIG_SENSORS_DME1737 is not set -# CONFIG_SENSORS_EMC1403 is not set -# CONFIG_SENSORS_EMC2103 is not set -# CONFIG_SENSORS_EMC2305 is not set -# CONFIG_SENSORS_EMC6W201 is not set -# CONFIG_SENSORS_SMSC47M1 is not set -# CONFIG_SENSORS_SMSC47M192 is not set -# CONFIG_SENSORS_SMSC47B397 is not set -# CONFIG_SENSORS_STTS751 is not set -# CONFIG_SENSORS_SMM665 is not set -# CONFIG_SENSORS_ADC128D818 is not set -# CONFIG_SENSORS_ADS7828 is not set -# CONFIG_SENSORS_ADS7871 is not set -# CONFIG_SENSORS_AMC6821 is not set -# CONFIG_SENSORS_INA209 is not set -# CONFIG_SENSORS_INA2XX is not set -# CONFIG_SENSORS_INA238 is not set -# CONFIG_SENSORS_INA3221 is not set -# CONFIG_SENSORS_TC74 is not set -# CONFIG_SENSORS_THMC50 is not set -# CONFIG_SENSORS_TMP102 is not set -# CONFIG_SENSORS_TMP103 is not set -# CONFIG_SENSORS_TMP108 is not set -# CONFIG_SENSORS_TMP401 is not set -# CONFIG_SENSORS_TMP421 is not set -# CONFIG_SENSORS_TMP464 is not set -# CONFIG_SENSORS_TMP513 is not set -# CONFIG_SENSORS_VIA686A is not set -# CONFIG_SENSORS_VT1211 is not set -# CONFIG_SENSORS_VT8231 is not set -# CONFIG_SENSORS_W83773G is not set -# CONFIG_SENSORS_W83781D is not set -# CONFIG_SENSORS_W83791D is not set -# CONFIG_SENSORS_W83792D is not set -# CONFIG_SENSORS_W83793 is not set -# CONFIG_SENSORS_W83795 is not set -# CONFIG_SENSORS_W83L785TS is not set -# CONFIG_SENSORS_W83L786NG is not set -# CONFIG_SENSORS_W83627HF is not set -# CONFIG_SENSORS_W83627EHF is not set -# CONFIG_THERMAL is not set -# CONFIG_WATCHDOG is not set -CONFIG_SSB_POSSIBLE=y -# CONFIG_SSB is not set -CONFIG_BCMA_POSSIBLE=y -# CONFIG_BCMA is not set - -# -# Multifunction device drivers -# -# CONFIG_MFD_ACT8945A is not set -# CONFIG_MFD_AS3711 is not set -# CONFIG_MFD_SMPRO is not set -# CONFIG_MFD_AS3722 is not set -# CONFIG_PMIC_ADP5520 is not set -# CONFIG_MFD_AAT2870_CORE is not set -# CONFIG_MFD_ATMEL_FLEXCOM is not set -# CONFIG_MFD_ATMEL_HLCDC is not set -# CONFIG_MFD_BCM590XX is not set -# CONFIG_MFD_BD9571MWV is not set -# CONFIG_MFD_AXP20X_I2C is not set -# CONFIG_MFD_MADERA is not set -# CONFIG_PMIC_DA903X is not set -# CONFIG_MFD_DA9052_SPI is not set -# CONFIG_MFD_DA9052_I2C is not set -# CONFIG_MFD_DA9055 is not set -# CONFIG_MFD_DA9062 is not set -# CONFIG_MFD_DA9063 is not set -# CONFIG_MFD_DA9150 is not set -# CONFIG_MFD_DLN2 is not set -# CONFIG_MFD_GATEWORKS_GSC is not set -# CONFIG_MFD_MC13XXX_SPI is not set -# CONFIG_MFD_MC13XXX_I2C is not set -# CONFIG_MFD_MP2629 is not set -# CONFIG_MFD_HI6421_PMIC is not set -# CONFIG_HTC_PASIC3 is not set -# CONFIG_LPC_ICH is not set -# CONFIG_LPC_SCH is not set -# CONFIG_MFD_IQS62X is not set -# CONFIG_MFD_JANZ_CMODIO is not set -# CONFIG_MFD_KEMPLD is not set -# CONFIG_MFD_88PM800 is not set -# CONFIG_MFD_88PM805 is not set -# CONFIG_MFD_88PM860X is not set -# CONFIG_MFD_MAX14577 is not set -# CONFIG_MFD_MAX77620 is not set -# CONFIG_MFD_MAX77650 is not set -# CONFIG_MFD_MAX77686 is not set -# CONFIG_MFD_MAX77693 is not set -# CONFIG_MFD_MAX77714 is not set -# CONFIG_MFD_MAX77843 is not set -# CONFIG_MFD_MAX8907 is not set -# CONFIG_MFD_MAX8925 is not set -# CONFIG_MFD_MAX8997 is not set -# CONFIG_MFD_MAX8998 is not set -# CONFIG_MFD_MT6360 is not set -# CONFIG_MFD_MT6370 is not set -# CONFIG_MFD_MT6397 is not set -# CONFIG_MFD_MENF21BMC is not set -# CONFIG_MFD_OCELOT is not set -# CONFIG_EZX_PCAP is not set -# CONFIG_MFD_CPCAP is not set -# CONFIG_MFD_VIPERBOARD is not set -# CONFIG_MFD_NTXEC is not set -# CONFIG_MFD_RETU is not set -# CONFIG_MFD_PCF50633 is not set -# CONFIG_MFD_SY7636A is not set -# CONFIG_MFD_RDC321X is not set -# CONFIG_MFD_RT4831 is not set -# CONFIG_MFD_RT5033 is not set -# CONFIG_MFD_RT5120 is not set -# CONFIG_MFD_RC5T583 is not set -# CONFIG_MFD_RK808 is not set -# CONFIG_MFD_RN5T618 is not set -# CONFIG_MFD_SEC_CORE is not set -# CONFIG_MFD_SI476X_CORE is not set -# CONFIG_MFD_SM501 is not set -# CONFIG_MFD_SKY81452 is not set -# CONFIG_MFD_STMPE is not set -CONFIG_MFD_SYSCON=y -# CONFIG_MFD_TI_AM335X_TSCADC is not set -# CONFIG_MFD_LP3943 is not set -# CONFIG_MFD_LP8788 is not set -# CONFIG_MFD_TI_LMU is not set -# CONFIG_MFD_PALMAS is not set -# CONFIG_TPS6105X is not set -# CONFIG_TPS65010 is not set -# CONFIG_TPS6507X is not set -# CONFIG_MFD_TPS65086 is not set -# CONFIG_MFD_TPS65090 is not set -# CONFIG_MFD_TPS65217 is not set -# CONFIG_MFD_TI_LP873X is not set -# CONFIG_MFD_TI_LP87565 is not set -# CONFIG_MFD_TPS65218 is not set -# CONFIG_MFD_TPS65219 is not set -# CONFIG_MFD_TPS6586X is not set -# CONFIG_MFD_TPS65910 is not set -# CONFIG_MFD_TPS65912_I2C is not set -# CONFIG_MFD_TPS65912_SPI is not set -# CONFIG_TWL4030_CORE is not set -# CONFIG_TWL6040_CORE is not set -# CONFIG_MFD_WL1273_CORE is not set -# CONFIG_MFD_LM3533 is not set -# CONFIG_MFD_TC3589X is not set -# CONFIG_MFD_TQMX86 is not set -# CONFIG_MFD_VX855 is not set -# CONFIG_MFD_LOCHNAGAR is not set -# CONFIG_MFD_ARIZONA_I2C is not set -# CONFIG_MFD_ARIZONA_SPI is not set -# CONFIG_MFD_WM8400 is not set -# CONFIG_MFD_WM831X_I2C is not set -# CONFIG_MFD_WM831X_SPI is not set -# CONFIG_MFD_WM8350_I2C is not set -# CONFIG_MFD_WM8994 is not set -# CONFIG_MFD_ROHM_BD718XX is not set -# CONFIG_MFD_ROHM_BD71828 is not set -# CONFIG_MFD_ROHM_BD957XMUF is not set -# CONFIG_MFD_STPMIC1 is not set -# CONFIG_MFD_STMFX is not set -# CONFIG_MFD_ATC260X_I2C is not set -# CONFIG_MFD_QCOM_PM8008 is not set -# CONFIG_MFD_INTEL_M10_BMC is not set -# CONFIG_MFD_RSMU_I2C is not set -# CONFIG_MFD_RSMU_SPI is not set -# end of Multifunction device drivers - -# CONFIG_REGULATOR is not set -# CONFIG_RC_CORE is not set - -# -# CEC support -# -# CONFIG_MEDIA_CEC_SUPPORT is not set -# end of CEC support - -CONFIG_MEDIA_SUPPORT=m -CONFIG_MEDIA_SUPPORT_FILTER=y -CONFIG_MEDIA_SUBDRV_AUTOSELECT=y - -# -# Media device types -# -CONFIG_MEDIA_CAMERA_SUPPORT=y -# CONFIG_MEDIA_ANALOG_TV_SUPPORT is not set -# CONFIG_MEDIA_DIGITAL_TV_SUPPORT is not set -# CONFIG_MEDIA_RADIO_SUPPORT is not set -# CONFIG_MEDIA_SDR_SUPPORT is not set -# CONFIG_MEDIA_PLATFORM_SUPPORT is not set -# CONFIG_MEDIA_TEST_SUPPORT is not set -# end of Media device types - -CONFIG_VIDEO_DEV=m -CONFIG_MEDIA_CONTROLLER=y - -# -# Video4Linux options -# -CONFIG_VIDEO_V4L2_I2C=y -CONFIG_VIDEO_V4L2_SUBDEV_API=y -# CONFIG_VIDEO_ADV_DEBUG is not set -# CONFIG_VIDEO_FIXED_MINOR_RANGES is not set -CONFIG_V4L2_FWNODE=m -CONFIG_V4L2_ASYNC=m -# end of Video4Linux options - -# -# Media controller options -# -# end of Media controller options - -# -# Media drivers -# - -# -# Drivers filtered as selected at 'Filter media drivers' -# - -# -# Media drivers -# -# CONFIG_MEDIA_USB_SUPPORT is not set -# CONFIG_MEDIA_PCI_SUPPORT is not set -CONFIG_VIDEOBUF2_CORE=m -CONFIG_VIDEOBUF2_V4L2=m -CONFIG_VIDEOBUF2_MEMOPS=m -CONFIG_VIDEOBUF2_VMALLOC=m -CONFIG_VIDEOBUF2_DMA_SG=m -# end of Media drivers - -# -# Media ancillary drivers -# - -# -# Camera sensor devices -# -# CONFIG_VIDEO_AR0521 is not set -# CONFIG_VIDEO_HI556 is not set -# CONFIG_VIDEO_HI846 is not set -# CONFIG_VIDEO_HI847 is not set -# CONFIG_VIDEO_IMX208 is not set -# CONFIG_VIDEO_IMX214 is not set -CONFIG_VIDEO_IMX219=m -# CONFIG_VIDEO_IMX258 is not set -# CONFIG_VIDEO_IMX274 is not set -# CONFIG_VIDEO_IMX290 is not set -# CONFIG_VIDEO_IMX319 is not set -# CONFIG_VIDEO_IMX334 is not set -# CONFIG_VIDEO_IMX335 is not set -# CONFIG_VIDEO_IMX355 is not set -# CONFIG_VIDEO_IMX412 is not set -# CONFIG_VIDEO_MT9M001 is not set -# CONFIG_VIDEO_MT9M032 is not set -# CONFIG_VIDEO_MT9M111 is not set -# CONFIG_VIDEO_MT9P031 is not set -# CONFIG_VIDEO_MT9T001 is not set -# CONFIG_VIDEO_MT9T112 is not set -# CONFIG_VIDEO_MT9V011 is not set -# CONFIG_VIDEO_MT9V032 is not set -# CONFIG_VIDEO_MT9V111 is not set -# CONFIG_VIDEO_NOON010PC30 is not set -# CONFIG_VIDEO_OG01A1B is not set -# CONFIG_VIDEO_OV02A10 is not set -# CONFIG_VIDEO_OV08D10 is not set -# CONFIG_VIDEO_OV08X40 is not set -# CONFIG_VIDEO_OV13858 is not set -# CONFIG_VIDEO_OV13B10 is not set -# CONFIG_VIDEO_OV2640 is not set -# CONFIG_VIDEO_OV2659 is not set -# CONFIG_VIDEO_OV2680 is not set -# CONFIG_VIDEO_OV2685 is not set -# CONFIG_VIDEO_OV4689 is not set -# CONFIG_VIDEO_OV5640 is not set -# CONFIG_VIDEO_OV5645 is not set -# CONFIG_VIDEO_OV5647 is not set -# CONFIG_VIDEO_OV5648 is not set -# CONFIG_VIDEO_OV5670 is not set -# CONFIG_VIDEO_OV5675 is not set -# CONFIG_VIDEO_OV5693 is not set -# CONFIG_VIDEO_OV5695 is not set -# CONFIG_VIDEO_OV6650 is not set -# CONFIG_VIDEO_OV7251 is not set -# CONFIG_VIDEO_OV7640 is not set -# CONFIG_VIDEO_OV7670 is not set -# CONFIG_VIDEO_OV772X is not set -# CONFIG_VIDEO_OV7740 is not set -# CONFIG_VIDEO_OV8856 is not set -# CONFIG_VIDEO_OV8865 is not set -# CONFIG_VIDEO_OV9282 is not set -# CONFIG_VIDEO_OV9640 is not set -# CONFIG_VIDEO_OV9650 is not set -# CONFIG_VIDEO_RDACM20 is not set -# CONFIG_VIDEO_RDACM21 is not set -# CONFIG_VIDEO_RJ54N1 is not set -# CONFIG_VIDEO_S5C73M3 is not set -# CONFIG_VIDEO_S5K5BAF is not set -# CONFIG_VIDEO_S5K6A3 is not set -# CONFIG_VIDEO_S5K6AA is not set -# CONFIG_VIDEO_SR030PC30 is not set -# CONFIG_VIDEO_ST_VGXY61 is not set -# CONFIG_VIDEO_VS6624 is not set -# CONFIG_VIDEO_CCS is not set -# CONFIG_VIDEO_ET8EK8 is not set -# CONFIG_VIDEO_M5MOLS is not set -# end of Camera sensor devices - -# -# Lens drivers -# -# CONFIG_VIDEO_AD5820 is not set -# CONFIG_VIDEO_AK7375 is not set -# CONFIG_VIDEO_DW9714 is not set -# CONFIG_VIDEO_DW9768 is not set -# CONFIG_VIDEO_DW9807_VCM is not set -# end of Lens drivers - -# -# Flash devices -# -# CONFIG_VIDEO_ADP1653 is not set -# CONFIG_VIDEO_LM3560 is not set -# CONFIG_VIDEO_LM3646 is not set -# end of Flash devices - -# -# Audio decoders, processors and mixers -# -# CONFIG_VIDEO_CS3308 is not set -# CONFIG_VIDEO_CS5345 is not set -# CONFIG_VIDEO_CS53L32A is not set -# CONFIG_VIDEO_MSP3400 is not set -# CONFIG_VIDEO_SONY_BTF_MPX is not set -# CONFIG_VIDEO_TDA7432 is not set -# CONFIG_VIDEO_TDA9840 is not set -# CONFIG_VIDEO_TEA6415C is not set -# CONFIG_VIDEO_TEA6420 is not set -# CONFIG_VIDEO_TLV320AIC23B is not set -# CONFIG_VIDEO_TVAUDIO is not set -# CONFIG_VIDEO_UDA1342 is not set -# CONFIG_VIDEO_VP27SMPX is not set -# CONFIG_VIDEO_WM8739 is not set -# CONFIG_VIDEO_WM8775 is not set -# end of Audio decoders, processors and mixers - -# -# RDS decoders -# -# CONFIG_VIDEO_SAA6588 is not set -# end of RDS decoders - -# -# Video decoders -# -# CONFIG_VIDEO_ADV7180 is not set -# CONFIG_VIDEO_ADV7183 is not set -# CONFIG_VIDEO_ADV748X is not set -# CONFIG_VIDEO_ADV7604 is not set -# CONFIG_VIDEO_ADV7842 is not set -# CONFIG_VIDEO_BT819 is not set -# CONFIG_VIDEO_BT856 is not set -# CONFIG_VIDEO_BT866 is not set -# CONFIG_VIDEO_ISL7998X is not set -# CONFIG_VIDEO_KS0127 is not set -# CONFIG_VIDEO_MAX9286 is not set -# CONFIG_VIDEO_ML86V7667 is not set -# CONFIG_VIDEO_SAA7110 is not set -# CONFIG_VIDEO_SAA711X is not set -# CONFIG_VIDEO_TC358743 is not set -# CONFIG_VIDEO_TC358746 is not set -# CONFIG_VIDEO_TVP514X is not set -# CONFIG_VIDEO_TVP5150 is not set -# CONFIG_VIDEO_TVP7002 is not set -# CONFIG_VIDEO_TW2804 is not set -# CONFIG_VIDEO_TW9903 is not set -# CONFIG_VIDEO_TW9906 is not set -# CONFIG_VIDEO_TW9910 is not set -# CONFIG_VIDEO_VPX3220 is not set - -# -# Video and audio decoders -# -# CONFIG_VIDEO_SAA717X is not set -# CONFIG_VIDEO_CX25840 is not set -# end of Video decoders - -# -# Video encoders -# -# CONFIG_VIDEO_AD9389B is not set -# CONFIG_VIDEO_ADV7170 is not set -# CONFIG_VIDEO_ADV7175 is not set -# CONFIG_VIDEO_ADV7343 is not set -# CONFIG_VIDEO_ADV7393 is not set -# CONFIG_VIDEO_ADV7511 is not set -# CONFIG_VIDEO_AK881X is not set -# CONFIG_VIDEO_SAA7127 is not set -# CONFIG_VIDEO_SAA7185 is not set -# CONFIG_VIDEO_THS8200 is not set -# end of Video encoders - -# -# Video improvement chips -# -# CONFIG_VIDEO_UPD64031A is not set -# CONFIG_VIDEO_UPD64083 is not set -# end of Video improvement chips - -# -# Audio/Video compression chips -# -# CONFIG_VIDEO_SAA6752HS is not set -# end of Audio/Video compression chips - -# -# SDR tuner chips -# -# end of SDR tuner chips - -# -# Miscellaneous helper chips -# -# CONFIG_VIDEO_I2C is not set -# CONFIG_VIDEO_M52790 is not set -# CONFIG_VIDEO_ST_MIPID02 is not set -# CONFIG_VIDEO_THS7303 is not set -# end of Miscellaneous helper chips - -# -# Media SPI Adapters -# -# CONFIG_VIDEO_GS1662 is not set -# end of Media SPI Adapters -# end of Media ancillary drivers - -# -# Graphics support -# -CONFIG_APERTURE_HELPERS=y -# CONFIG_DRM is not set -# CONFIG_DRM_DEBUG_MODESET_LOCK is not set - -# -# ARM devices -# -# end of ARM devices - -# -# Frame buffer Devices -# -CONFIG_FB_CMDLINE=y -CONFIG_FB_NOTIFY=y -CONFIG_FB=y -# CONFIG_FIRMWARE_EDID is not set -# CONFIG_FB_FOREIGN_ENDIAN is not set -# CONFIG_FB_MODE_HELPERS is not set -# CONFIG_FB_TILEBLITTING is not set - -# -# Frame buffer hardware drivers -# -# CONFIG_FB_CIRRUS is not set -# CONFIG_FB_PM2 is not set -# CONFIG_FB_CYBER2000 is not set -# CONFIG_FB_ASILIANT is not set -# CONFIG_FB_IMSTT is not set -# CONFIG_FB_EFI is not set -# CONFIG_FB_OPENCORES is not set -# CONFIG_FB_S1D13XXX is not set -# CONFIG_FB_NVIDIA is not set -# CONFIG_FB_RIVA is not set -# CONFIG_FB_I740 is not set -# CONFIG_FB_MATROX is not set -# CONFIG_FB_RADEON is not set -# CONFIG_FB_ATY128 is not set -# CONFIG_FB_ATY is not set -# CONFIG_FB_S3 is not set -# CONFIG_FB_SAVAGE is not set -# CONFIG_FB_SIS is not set -# CONFIG_FB_NEOMAGIC is not set -# CONFIG_FB_KYRO is not set -# CONFIG_FB_3DFX is not set -# CONFIG_FB_VOODOO1 is not set -# CONFIG_FB_VT8623 is not set -# CONFIG_FB_TRIDENT is not set -# CONFIG_FB_ARK is not set -# CONFIG_FB_PM3 is not set -# CONFIG_FB_CARMINE is not set -# CONFIG_FB_SH_MOBILE_LCDC is not set -# CONFIG_FB_SMSCUFX is not set -# CONFIG_FB_UDL is not set -# CONFIG_FB_IBM_GXT4500 is not set -# CONFIG_FB_GOLDFISH is not set -# CONFIG_FB_VIRTUAL is not set -# CONFIG_FB_METRONOME is not set -# CONFIG_FB_MB862XX is not set -# CONFIG_FB_SIMPLE is not set -# CONFIG_FB_SSD1307 is not set -# CONFIG_FB_SM712 is not set -# end of Frame buffer Devices - -# -# Backlight & LCD device support -# -# CONFIG_LCD_CLASS_DEVICE is not set -CONFIG_BACKLIGHT_CLASS_DEVICE=m -# CONFIG_BACKLIGHT_KTD253 is not set -# CONFIG_BACKLIGHT_QCOM_WLED is not set -# CONFIG_BACKLIGHT_ADP8860 is not set -# CONFIG_BACKLIGHT_ADP8870 is not set -# CONFIG_BACKLIGHT_LM3639 is not set -# CONFIG_BACKLIGHT_GPIO is not set -# CONFIG_BACKLIGHT_LV5207LP is not set -# CONFIG_BACKLIGHT_BD6107 is not set -# CONFIG_BACKLIGHT_ARCXCNN is not set -# end of Backlight & LCD device support - -# -# Console display driver support -# -CONFIG_VGA_CONSOLE=y -CONFIG_DUMMY_CONSOLE=y -CONFIG_DUMMY_CONSOLE_COLUMNS=80 -CONFIG_DUMMY_CONSOLE_ROWS=25 -CONFIG_FRAMEBUFFER_CONSOLE=y -# CONFIG_FRAMEBUFFER_CONSOLE_LEGACY_ACCELERATION is not set -CONFIG_FRAMEBUFFER_CONSOLE_DETECT_PRIMARY=y -# CONFIG_FRAMEBUFFER_CONSOLE_ROTATION is not set -# CONFIG_FRAMEBUFFER_CONSOLE_DEFERRED_TAKEOVER is not set -# end of Console display driver support - -# CONFIG_LOGO is not set -# end of Graphics support - -# CONFIG_SOUND is not set - -# -# HID support -# -CONFIG_HID=y -# CONFIG_HID_BATTERY_STRENGTH is not set -# CONFIG_HIDRAW is not set -# CONFIG_UHID is not set -CONFIG_HID_GENERIC=y - -# -# Special HID drivers -# -# CONFIG_HID_A4TECH is not set -# CONFIG_HID_ACCUTOUCH is not set -# CONFIG_HID_ACRUX is not set -# CONFIG_HID_APPLEIR is not set -# CONFIG_HID_AUREAL is not set -# CONFIG_HID_BELKIN is not set -# CONFIG_HID_BETOP_FF is not set -# CONFIG_HID_CHERRY is not set -# CONFIG_HID_CHICONY is not set -# CONFIG_HID_COUGAR is not set -# CONFIG_HID_MACALLY is not set -# CONFIG_HID_CMEDIA is not set -# CONFIG_HID_CREATIVE_SB0540 is not set -# CONFIG_HID_CYPRESS is not set -# CONFIG_HID_DRAGONRISE is not set -# CONFIG_HID_EMS_FF is not set -# CONFIG_HID_ELECOM is not set -# CONFIG_HID_ELO is not set -# CONFIG_HID_EZKEY is not set -# CONFIG_HID_GEMBIRD is not set -# CONFIG_HID_GFRM is not set -# CONFIG_HID_GLORIOUS is not set -# CONFIG_HID_HOLTEK is not set -# CONFIG_HID_VIVALDI is not set -# CONFIG_HID_KEYTOUCH is not set -# CONFIG_HID_KYE is not set -# CONFIG_HID_UCLOGIC is not set -# CONFIG_HID_WALTOP is not set -# CONFIG_HID_VIEWSONIC is not set -# CONFIG_HID_VRC2 is not set -# CONFIG_HID_XIAOMI is not set -# CONFIG_HID_GYRATION is not set -# CONFIG_HID_ICADE is not set -# CONFIG_HID_ITE is not set -# CONFIG_HID_JABRA is not set -# CONFIG_HID_TWINHAN is not set -# CONFIG_HID_KENSINGTON is not set -# CONFIG_HID_LCPOWER is not set -# CONFIG_HID_LENOVO is not set -# CONFIG_HID_LETSKETCH is not set -# CONFIG_HID_MAGICMOUSE is not set -# CONFIG_HID_MALTRON is not set -# CONFIG_HID_MAYFLASH is not set -# CONFIG_HID_MEGAWORLD_FF is not set -# CONFIG_HID_REDRAGON is not set -# CONFIG_HID_MICROSOFT is not set -# CONFIG_HID_MONTEREY is not set -# CONFIG_HID_MULTITOUCH is not set -# CONFIG_HID_NTI is not set -# CONFIG_HID_NTRIG is not set -# CONFIG_HID_ORTEK is not set -# CONFIG_HID_PANTHERLORD is not set -# CONFIG_HID_PENMOUNT is not set -# CONFIG_HID_PETALYNX is not set -# CONFIG_HID_PICOLCD is not set -# CONFIG_HID_PLANTRONICS is not set -# CONFIG_HID_PXRC is not set -# CONFIG_HID_RAZER is not set -# CONFIG_HID_PRIMAX is not set -# CONFIG_HID_RETRODE is not set -# CONFIG_HID_ROCCAT is not set -# CONFIG_HID_SAITEK is not set -# CONFIG_HID_SAMSUNG is not set -# CONFIG_HID_SEMITEK is not set -# CONFIG_HID_SIGMAMICRO is not set -# CONFIG_HID_SPEEDLINK is not set -# CONFIG_HID_STEAM is not set -# CONFIG_HID_STEELSERIES is not set -# CONFIG_HID_SUNPLUS is not set -# CONFIG_HID_RMI is not set -# CONFIG_HID_GREENASIA is not set -# CONFIG_HID_SMARTJOYPLUS is not set -# CONFIG_HID_TIVO is not set -# CONFIG_HID_TOPSEED is not set -# CONFIG_HID_TOPRE is not set -# CONFIG_HID_THRUSTMASTER is not set -# CONFIG_HID_UDRAW_PS3 is not set -# CONFIG_HID_WACOM is not set -# CONFIG_HID_XINMO is not set -# CONFIG_HID_ZEROPLUS is not set -# CONFIG_HID_ZYDACRON is not set -# CONFIG_HID_SENSOR_HUB is not set -# CONFIG_HID_ALPS is not set -# CONFIG_HID_MCP2221 is not set -# end of Special HID drivers - -# -# USB HID support -# -CONFIG_USB_HID=y -# CONFIG_HID_PID is not set -# CONFIG_USB_HIDDEV is not set -# end of USB HID support - -# -# I2C HID support -# -# CONFIG_I2C_HID_OF is not set -# CONFIG_I2C_HID_OF_ELAN is not set -# CONFIG_I2C_HID_OF_GOODIX is not set -# end of I2C HID support -# end of HID support - -CONFIG_USB_OHCI_LITTLE_ENDIAN=y -CONFIG_USB_SUPPORT=y -CONFIG_USB_COMMON=y -# CONFIG_USB_ULPI_BUS is not set -# CONFIG_USB_CONN_GPIO is not set -CONFIG_USB_ARCH_HAS_HCD=y -CONFIG_USB=y -CONFIG_USB_PCI=y -# CONFIG_USB_ANNOUNCE_NEW_DEVICES is not set - -# -# Miscellaneous USB options -# -CONFIG_USB_DEFAULT_PERSIST=y -# CONFIG_USB_FEW_INIT_RETRIES is not set -# CONFIG_USB_DYNAMIC_MINORS is not set -# CONFIG_USB_OTG is not set -# CONFIG_USB_OTG_PRODUCTLIST is not set -# CONFIG_USB_OTG_DISABLE_EXTERNAL_HUB is not set -CONFIG_USB_AUTOSUSPEND_DELAY=2 -# CONFIG_USB_MON is not set - -# -# USB Host Controller Drivers -# -# CONFIG_USB_C67X00_HCD is not set -CONFIG_USB_XHCI_HCD=y -# CONFIG_USB_XHCI_DBGCAP is not set -CONFIG_USB_XHCI_PCI=y -# CONFIG_USB_XHCI_PCI_RENESAS is not set -CONFIG_USB_XHCI_PLATFORM=y -CONFIG_USB_XHCI_RCAR=y -CONFIG_USB_EHCI_HCD=y -# CONFIG_USB_EHCI_ROOT_HUB_TT is not set -CONFIG_USB_EHCI_TT_NEWSCHED=y -CONFIG_USB_EHCI_PCI=y -# CONFIG_USB_EHCI_FSL is not set -CONFIG_USB_EHCI_HCD_PLATFORM=y -# CONFIG_USB_OXU210HP_HCD is not set -# CONFIG_USB_ISP116X_HCD is not set -# CONFIG_USB_MAX3421_HCD is not set -CONFIG_USB_OHCI_HCD=y -CONFIG_USB_OHCI_HCD_PCI=y -CONFIG_USB_OHCI_HCD_PLATFORM=y -# CONFIG_USB_UHCI_HCD is not set -# CONFIG_USB_SL811_HCD is not set -# CONFIG_USB_R8A66597_HCD is not set -# CONFIG_USB_HCD_TEST_MODE is not set -# CONFIG_USB_RENESAS_USBHS is not set - -# -# USB Device Class drivers -# -# CONFIG_USB_ACM is not set -# CONFIG_USB_PRINTER is not set -# CONFIG_USB_WDM is not set -# CONFIG_USB_TMC is not set - -# -# NOTE: USB_STORAGE depends on SCSI but BLK_DEV_SD may -# - -# -# also be needed; see USB_STORAGE Help for more info -# -CONFIG_USB_STORAGE=y -# CONFIG_USB_STORAGE_DEBUG is not set -# CONFIG_USB_STORAGE_REALTEK is not set -# CONFIG_USB_STORAGE_DATAFAB is not set -# CONFIG_USB_STORAGE_FREECOM is not set -# CONFIG_USB_STORAGE_ISD200 is not set -# CONFIG_USB_STORAGE_USBAT is not set -# CONFIG_USB_STORAGE_SDDR09 is not set -# CONFIG_USB_STORAGE_SDDR55 is not set -# CONFIG_USB_STORAGE_JUMPSHOT is not set -# CONFIG_USB_STORAGE_ALAUDA is not set -# CONFIG_USB_STORAGE_ONETOUCH is not set -# CONFIG_USB_STORAGE_KARMA is not set -# CONFIG_USB_STORAGE_CYPRESS_ATACB is not set -# CONFIG_USB_STORAGE_ENE_UB6250 is not set -CONFIG_USB_UAS=y - -# -# USB Imaging devices -# -# CONFIG_USB_MDC800 is not set -# CONFIG_USB_MICROTEK is not set -# CONFIG_USBIP_CORE is not set - -# -# USB dual-mode controller drivers -# -# CONFIG_USB_CDNS_SUPPORT is not set -CONFIG_USB_MUSB_HDRC=y -# CONFIG_USB_MUSB_HOST is not set -# CONFIG_USB_MUSB_GADGET is not set -CONFIG_USB_MUSB_DUAL_ROLE=y - -# -# Platform Glue Layer -# -CONFIG_USB_MUSB_POLARFIRE_SOC=y - -# -# MUSB DMA mode -# -# CONFIG_MUSB_PIO_ONLY is not set -# CONFIG_USB_INVENTRA_DMA is not set -# CONFIG_USB_DWC3 is not set -# CONFIG_USB_DWC2 is not set -# CONFIG_USB_CHIPIDEA is not set -# CONFIG_USB_ISP1760 is not set - -# -# USB port drivers -# -# CONFIG_USB_SERIAL is not set - -# -# USB Miscellaneous drivers -# -# CONFIG_USB_EMI62 is not set -# CONFIG_USB_EMI26 is not set -# CONFIG_USB_ADUTUX is not set -# CONFIG_USB_SEVSEG is not set -# CONFIG_USB_LEGOTOWER is not set -# CONFIG_USB_LCD is not set -# CONFIG_USB_CYPRESS_CY7C63 is not set -# CONFIG_USB_CYTHERM is not set -# CONFIG_USB_IDMOUSE is not set -# CONFIG_USB_FTDI_ELAN is not set -# CONFIG_USB_APPLEDISPLAY is not set -# CONFIG_APPLE_MFI_FASTCHARGE is not set -# CONFIG_USB_SISUSBVGA is not set -# CONFIG_USB_LD is not set -# CONFIG_USB_TRANCEVIBRATOR is not set -# CONFIG_USB_IOWARRIOR is not set -# CONFIG_USB_TEST is not set -# CONFIG_USB_EHSET_TEST_FIXTURE is not set -# CONFIG_USB_ISIGHTFW is not set -# CONFIG_USB_YUREX is not set -# CONFIG_USB_EZUSB_FX2 is not set -# CONFIG_USB_HUB_USB251XB is not set -# CONFIG_USB_HSIC_USB3503 is not set -# CONFIG_USB_HSIC_USB4604 is not set -# CONFIG_USB_LINK_LAYER_TEST is not set -# CONFIG_USB_CHAOSKEY is not set -# CONFIG_USB_ONBOARD_HUB is not set - -# -# USB Physical Layer drivers -# -CONFIG_USB_PHY=y -CONFIG_NOP_USB_XCEIV=y -# CONFIG_USB_GPIO_VBUS is not set -# CONFIG_USB_ISP1301 is not set -# end of USB Physical Layer drivers - -CONFIG_USB_GADGET=y -# CONFIG_USB_GADGET_DEBUG is not set -# CONFIG_USB_GADGET_DEBUG_FILES is not set -# CONFIG_USB_GADGET_DEBUG_FS is not set -CONFIG_USB_GADGET_VBUS_DRAW=2 -CONFIG_USB_GADGET_STORAGE_NUM_BUFFERS=2 -# CONFIG_U_SERIAL_CONSOLE is not set - -# -# USB Peripheral Controller -# -# CONFIG_USB_GR_UDC is not set -# CONFIG_USB_R8A66597 is not set -# CONFIG_USB_RENESAS_USB3 is not set -# CONFIG_USB_PXA27X is not set -# CONFIG_USB_MV_UDC is not set -# CONFIG_USB_MV_U3D is not set -# CONFIG_USB_SNP_UDC_PLAT is not set -# CONFIG_USB_M66592 is not set -# CONFIG_USB_BDC_UDC is not set -# CONFIG_USB_AMD5536UDC is not set -# CONFIG_USB_NET2272 is not set -# CONFIG_USB_NET2280 is not set -# CONFIG_USB_GOKU is not set -# CONFIG_USB_EG20T is not set -# CONFIG_USB_GADGET_XILINX is not set -# CONFIG_USB_MAX3420_UDC is not set -# CONFIG_USB_DUMMY_HCD is not set -# end of USB Peripheral Controller - -CONFIG_USB_LIBCOMPOSITE=y -CONFIG_USB_F_ACM=y -CONFIG_USB_F_SS_LB=y -CONFIG_USB_U_SERIAL=y -CONFIG_USB_U_ETHER=y -CONFIG_USB_F_SERIAL=y -CONFIG_USB_F_OBEX=y -CONFIG_USB_F_NCM=y -CONFIG_USB_F_ECM=y -CONFIG_USB_F_EEM=y -CONFIG_USB_F_SUBSET=y -CONFIG_USB_F_RNDIS=y -CONFIG_USB_F_MASS_STORAGE=y -CONFIG_USB_F_FS=y -CONFIG_USB_F_UVC=m -CONFIG_USB_F_HID=y -CONFIG_USB_F_PRINTER=y -CONFIG_USB_CONFIGFS=y -CONFIG_USB_CONFIGFS_SERIAL=y -CONFIG_USB_CONFIGFS_ACM=y -CONFIG_USB_CONFIGFS_OBEX=y -CONFIG_USB_CONFIGFS_NCM=y -CONFIG_USB_CONFIGFS_ECM=y -CONFIG_USB_CONFIGFS_ECM_SUBSET=y -CONFIG_USB_CONFIGFS_RNDIS=y -CONFIG_USB_CONFIGFS_EEM=y -CONFIG_USB_CONFIGFS_MASS_STORAGE=y -CONFIG_USB_CONFIGFS_F_LB_SS=y -CONFIG_USB_CONFIGFS_F_FS=y -CONFIG_USB_CONFIGFS_F_HID=y -CONFIG_USB_CONFIGFS_F_UVC=y -CONFIG_USB_CONFIGFS_F_PRINTER=y - -# -# USB Gadget precomposed configurations -# -# CONFIG_USB_ZERO is not set -# CONFIG_USB_ETH is not set -# CONFIG_USB_G_NCM is not set -# CONFIG_USB_GADGETFS is not set -# CONFIG_USB_FUNCTIONFS is not set -# CONFIG_USB_MASS_STORAGE is not set -# CONFIG_USB_G_SERIAL is not set -# CONFIG_USB_G_PRINTER is not set -# CONFIG_USB_CDC_COMPOSITE is not set -# CONFIG_USB_G_ACM_MS is not set -# CONFIG_USB_G_MULTI is not set -# CONFIG_USB_G_HID is not set -# CONFIG_USB_G_DBGP is not set -# CONFIG_USB_G_WEBCAM is not set -# CONFIG_USB_RAW_GADGET is not set -# end of USB Gadget precomposed configurations - -# CONFIG_TYPEC is not set -# CONFIG_USB_ROLE_SWITCH is not set -CONFIG_MMC=y -CONFIG_PWRSEQ_EMMC=y -CONFIG_PWRSEQ_SIMPLE=y -CONFIG_MMC_BLOCK=y -CONFIG_MMC_BLOCK_MINORS=8 -# CONFIG_SDIO_UART is not set -# CONFIG_MMC_TEST is not set - -# -# MMC/SD/SDIO Host Controller Drivers -# -# CONFIG_MMC_DEBUG is not set -CONFIG_MMC_SDHCI=y -# CONFIG_MMC_SDHCI_PCI is not set -CONFIG_MMC_SDHCI_PLTFM=y -# CONFIG_MMC_SDHCI_OF_ARASAN is not set -# CONFIG_MMC_SDHCI_OF_AT91 is not set -# CONFIG_MMC_SDHCI_OF_DWCMSHC is not set -CONFIG_MMC_SDHCI_CADENCE=y -# CONFIG_MMC_SDHCI_F_SDH30 is not set -# CONFIG_MMC_SDHCI_MILBEAUT is not set -# CONFIG_MMC_TIFM_SD is not set -CONFIG_MMC_SPI=y -# CONFIG_MMC_SDHI is not set -# CONFIG_MMC_CB710 is not set -# CONFIG_MMC_VIA_SDMMC is not set -# CONFIG_MMC_DW is not set -# CONFIG_MMC_SH_MMCIF is not set -# CONFIG_MMC_VUB300 is not set -# CONFIG_MMC_USHC is not set -# CONFIG_MMC_USDHI6ROL0 is not set -# CONFIG_MMC_CQHCI is not set -# CONFIG_MMC_HSQ is not set -# CONFIG_MMC_TOSHIBA_PCI is not set -# CONFIG_MMC_MTK is not set -# CONFIG_MMC_SDHCI_XENON is not set -# CONFIG_MMC_SDHCI_OMAP is not set -# CONFIG_MMC_SDHCI_AM654 is not set -# CONFIG_SCSI_UFSHCD is not set -# CONFIG_MEMSTICK is not set -# CONFIG_NEW_LEDS is not set -# CONFIG_ACCESSIBILITY is not set -# CONFIG_INFINIBAND is not set -CONFIG_EDAC_SUPPORT=y -CONFIG_RTC_LIB=y -CONFIG_RTC_CLASS=y -CONFIG_RTC_HCTOSYS=y -CONFIG_RTC_HCTOSYS_DEVICE="rtc0" -CONFIG_RTC_SYSTOHC=y -CONFIG_RTC_SYSTOHC_DEVICE="rtc0" -# CONFIG_RTC_DEBUG is not set -CONFIG_RTC_NVMEM=y - -# -# RTC interfaces -# -CONFIG_RTC_INTF_SYSFS=y -CONFIG_RTC_INTF_PROC=y -CONFIG_RTC_INTF_DEV=y -# CONFIG_RTC_INTF_DEV_UIE_EMUL is not set -# CONFIG_RTC_DRV_TEST is not set - -# -# I2C RTC drivers -# -# CONFIG_RTC_DRV_ABB5ZES3 is not set -# CONFIG_RTC_DRV_ABEOZ9 is not set -# CONFIG_RTC_DRV_ABX80X is not set -# CONFIG_RTC_DRV_DS1307 is not set -# CONFIG_RTC_DRV_DS1374 is not set -# CONFIG_RTC_DRV_DS1672 is not set -# CONFIG_RTC_DRV_HYM8563 is not set -# CONFIG_RTC_DRV_MAX6900 is not set -# CONFIG_RTC_DRV_NCT3018Y is not set -# CONFIG_RTC_DRV_RS5C372 is not set -# CONFIG_RTC_DRV_ISL1208 is not set -# CONFIG_RTC_DRV_ISL12022 is not set -# CONFIG_RTC_DRV_ISL12026 is not set -# CONFIG_RTC_DRV_X1205 is not set -# CONFIG_RTC_DRV_PCF8523 is not set -# CONFIG_RTC_DRV_PCF85063 is not set -# CONFIG_RTC_DRV_PCF85363 is not set -# CONFIG_RTC_DRV_PCF8563 is not set -# CONFIG_RTC_DRV_PCF8583 is not set -# CONFIG_RTC_DRV_M41T80 is not set -# CONFIG_RTC_DRV_BQ32K is not set -# CONFIG_RTC_DRV_S35390A is not set -# CONFIG_RTC_DRV_FM3130 is not set -# CONFIG_RTC_DRV_RX8010 is not set -# CONFIG_RTC_DRV_RX8581 is not set -# CONFIG_RTC_DRV_RX8025 is not set -# CONFIG_RTC_DRV_EM3027 is not set -# CONFIG_RTC_DRV_RV3028 is not set -# CONFIG_RTC_DRV_RV3032 is not set -# CONFIG_RTC_DRV_RV8803 is not set -# CONFIG_RTC_DRV_SD3078 is not set - -# -# SPI RTC drivers -# -# CONFIG_RTC_DRV_M41T93 is not set -# CONFIG_RTC_DRV_M41T94 is not set -# CONFIG_RTC_DRV_DS1302 is not set -# CONFIG_RTC_DRV_DS1305 is not set -# CONFIG_RTC_DRV_DS1343 is not set -# CONFIG_RTC_DRV_DS1347 is not set -# CONFIG_RTC_DRV_DS1390 is not set -# CONFIG_RTC_DRV_MAX6916 is not set -# CONFIG_RTC_DRV_R9701 is not set -# CONFIG_RTC_DRV_RX4581 is not set -# CONFIG_RTC_DRV_RS5C348 is not set -# CONFIG_RTC_DRV_MAX6902 is not set -# CONFIG_RTC_DRV_PCF2123 is not set -# CONFIG_RTC_DRV_MCP795 is not set -CONFIG_RTC_I2C_AND_SPI=y - -# -# SPI and I2C RTC drivers -# -# CONFIG_RTC_DRV_DS3232 is not set -# CONFIG_RTC_DRV_PCF2127 is not set -# CONFIG_RTC_DRV_RV3029C2 is not set -# CONFIG_RTC_DRV_RX6110 is not set - -# -# Platform RTC drivers -# -# CONFIG_RTC_DRV_DS1286 is not set -# CONFIG_RTC_DRV_DS1511 is not set -# CONFIG_RTC_DRV_DS1553 is not set -# CONFIG_RTC_DRV_DS1685_FAMILY is not set -# CONFIG_RTC_DRV_DS1742 is not set -# CONFIG_RTC_DRV_DS2404 is not set -# CONFIG_RTC_DRV_EFI is not set -# CONFIG_RTC_DRV_STK17TA8 is not set -# CONFIG_RTC_DRV_M48T86 is not set -# CONFIG_RTC_DRV_M48T35 is not set -# CONFIG_RTC_DRV_M48T59 is not set -# CONFIG_RTC_DRV_MSM6242 is not set -# CONFIG_RTC_DRV_BQ4802 is not set -# CONFIG_RTC_DRV_RP5C01 is not set -# CONFIG_RTC_DRV_V3020 is not set -# CONFIG_RTC_DRV_ZYNQMP is not set - -# -# on-CPU RTC drivers -# -# CONFIG_RTC_DRV_SH is not set -# CONFIG_RTC_DRV_CADENCE is not set -# CONFIG_RTC_DRV_FTRTC010 is not set -# CONFIG_RTC_DRV_R7301 is not set - -# -# HID Sensor RTC drivers -# -CONFIG_RTC_DRV_GOLDFISH=y -# CONFIG_RTC_DRV_POLARFIRE_SOC is not set -# CONFIG_DMADEVICES is not set - -# -# DMABUF options -# -CONFIG_SYNC_FILE=y -# CONFIG_SW_SYNC is not set -# CONFIG_UDMABUF is not set -# CONFIG_DMABUF_MOVE_NOTIFY is not set -# CONFIG_DMABUF_DEBUG is not set -# CONFIG_DMABUF_SELFTESTS is not set -# CONFIG_DMABUF_HEAPS is not set -# CONFIG_DMABUF_SYSFS_STATS is not set -# end of DMABUF options - -# CONFIG_AUXDISPLAY is not set -# CONFIG_UIO is not set -# CONFIG_VFIO is not set -# CONFIG_VIRT_DRIVERS is not set -CONFIG_VIRTIO_ANCHOR=y -CONFIG_VIRTIO=y -CONFIG_VIRTIO_PCI_LIB=y -CONFIG_VIRTIO_PCI_LIB_LEGACY=y -CONFIG_VIRTIO_MENU=y -CONFIG_VIRTIO_PCI=y -CONFIG_VIRTIO_PCI_LEGACY=y -# CONFIG_VIRTIO_PMEM is not set -CONFIG_VIRTIO_BALLOON=y -CONFIG_VIRTIO_INPUT=y -CONFIG_VIRTIO_MMIO=y -# CONFIG_VIRTIO_MMIO_CMDLINE_DEVICES is not set -# CONFIG_VDPA is not set -CONFIG_VHOST_MENU=y -# CONFIG_VHOST_NET is not set -# CONFIG_VHOST_CROSS_ENDIAN_LEGACY is not set - -# -# Microsoft Hyper-V guest support -# -# end of Microsoft Hyper-V guest support - -# CONFIG_GREYBUS is not set -# CONFIG_COMEDI is not set -# CONFIG_STAGING is not set -CONFIG_GOLDFISH=y -# CONFIG_GOLDFISH_PIPE is not set -CONFIG_HAVE_CLK=y -CONFIG_HAVE_CLK_PREPARE=y -CONFIG_COMMON_CLK=y -# CONFIG_LMK04832 is not set -# CONFIG_COMMON_CLK_MAX9485 is not set -# CONFIG_COMMON_CLK_SI5341 is not set -# CONFIG_COMMON_CLK_SI5351 is not set -# CONFIG_COMMON_CLK_SI514 is not set -# CONFIG_COMMON_CLK_SI544 is not set -# CONFIG_COMMON_CLK_SI570 is not set -# CONFIG_COMMON_CLK_CDCE706 is not set -# CONFIG_COMMON_CLK_CDCE925 is not set -# CONFIG_COMMON_CLK_CS2000_CP is not set -# CONFIG_COMMON_CLK_AXI_CLKGEN is not set -# CONFIG_COMMON_CLK_RS9_PCIE is not set -# CONFIG_COMMON_CLK_VC5 is not set -# CONFIG_COMMON_CLK_VC7 is not set -# CONFIG_COMMON_CLK_FIXED_MMIO is not set -CONFIG_CLK_ANALOGBITS_WRPLL_CLN28HPC=y -CONFIG_MCHP_CLK_MPFS=y -CONFIG_CLK_RENESAS=y -CONFIG_CLK_R9A07G043=y -# CONFIG_CLK_RCAR_USB2_CLOCK_SEL is not set -CONFIG_CLK_RZG2L=y -CONFIG_CLK_SIFIVE=y -CONFIG_CLK_SIFIVE_PRCI=y -CONFIG_CLK_STARFIVE_JH7100=y -CONFIG_CLK_STARFIVE_JH7100_AUDIO=m -# CONFIG_XILINX_VCU is not set -# CONFIG_COMMON_CLK_XLNX_CLKWZRD is not set -# CONFIG_HWSPINLOCK is not set - -# -# Clock Source drivers -# -CONFIG_TIMER_OF=y -CONFIG_TIMER_PROBE=y -# CONFIG_RENESAS_OSTM is not set -CONFIG_RISCV_TIMER=y -# CONFIG_MICROCHIP_PIT64B is not set -# end of Clock Source drivers - -CONFIG_MAILBOX=y -# CONFIG_PLATFORM_MHU is not set -# CONFIG_ALTERA_MBOX is not set -# CONFIG_MAILBOX_TEST is not set -CONFIG_POLARFIRE_SOC_MAILBOX=y -CONFIG_IOMMU_SUPPORT=y - -# -# Generic IOMMU Pagetable Support -# -# end of Generic IOMMU Pagetable Support - -# CONFIG_IOMMU_DEBUGFS is not set -# CONFIG_IOMMUFD is not set -# CONFIG_IPMMU_VMSA is not set - -# -# Remoteproc drivers -# -CONFIG_REMOTEPROC=y -CONFIG_REMOTEPROC_CDEV=y -# CONFIG_RCAR_REMOTEPROC is not set -# end of Remoteproc drivers - -# -# Rpmsg drivers -# -CONFIG_RPMSG=y -CONFIG_RPMSG_CHAR=y -CONFIG_RPMSG_CTRL=y -CONFIG_RPMSG_NS=y -# CONFIG_RPMSG_QCOM_GLINK_RPM is not set -CONFIG_RPMSG_VIRTIO=y -# end of Rpmsg drivers - -# CONFIG_SOUNDWIRE is not set - -# -# SOC (System On Chip) specific Drivers -# - -# -# Amlogic SoC drivers -# -# end of Amlogic SoC drivers - -# -# Broadcom SoC drivers -# -# end of Broadcom SoC drivers - -# -# NXP/Freescale QorIQ SoC drivers -# -# end of NXP/Freescale QorIQ SoC drivers - -# -# fujitsu SoC drivers -# -# end of fujitsu SoC drivers - -# -# i.MX SoC drivers -# -# end of i.MX SoC drivers - -# -# Enable LiteX SoC Builder specific drivers -# -# CONFIG_LITEX_SOC_CONTROLLER is not set -# end of Enable LiteX SoC Builder specific drivers - -CONFIG_POLARFIRE_SOC_SYS_CTRL=y - -# -# Qualcomm SoC drivers -# -# end of Qualcomm SoC drivers - -CONFIG_SOC_RENESAS=y -CONFIG_ARCH_RZG2L=y -CONFIG_ARCH_R9A07G043=y -# CONFIG_SIFIVE_CCACHE is not set -# CONFIG_SOC_TI is not set - -# -# Xilinx SoC drivers -# -# end of Xilinx SoC drivers -# end of SOC (System On Chip) specific Drivers - -# CONFIG_PM_DEVFREQ is not set -CONFIG_EXTCON=y - -# -# Extcon Device Drivers -# -# CONFIG_EXTCON_ADC_JACK is not set -# CONFIG_EXTCON_FSA9480 is not set -# CONFIG_EXTCON_GPIO is not set -# CONFIG_EXTCON_MAX3355 is not set -# CONFIG_EXTCON_PTN5150 is not set -# CONFIG_EXTCON_RT8973A is not set -# CONFIG_EXTCON_SM5502 is not set -# CONFIG_EXTCON_USB_GPIO is not set -# CONFIG_MEMORY is not set -CONFIG_IIO=m -# CONFIG_IIO_BUFFER is not set -# CONFIG_IIO_CONFIGFS is not set -# CONFIG_IIO_TRIGGER is not set -# CONFIG_IIO_SW_DEVICE is not set -# CONFIG_IIO_SW_TRIGGER is not set -# CONFIG_IIO_TRIGGERED_EVENT is not set - -# -# Accelerometers -# -# CONFIG_ADIS16201 is not set -# CONFIG_ADIS16209 is not set -# CONFIG_ADXL313_I2C is not set -# CONFIG_ADXL313_SPI is not set -# CONFIG_ADXL345_I2C is not set -# CONFIG_ADXL345_SPI is not set -# CONFIG_ADXL355_I2C is not set -# CONFIG_ADXL355_SPI is not set -# CONFIG_ADXL367_SPI is not set -# CONFIG_ADXL367_I2C is not set -# CONFIG_ADXL372_SPI is not set -# CONFIG_ADXL372_I2C is not set -# CONFIG_BMA180 is not set -# CONFIG_BMA220 is not set -# CONFIG_BMA400 is not set -# CONFIG_BMC150_ACCEL is not set -# CONFIG_BMI088_ACCEL is not set -# CONFIG_DA280 is not set -# CONFIG_DA311 is not set -# CONFIG_DMARD06 is not set -# CONFIG_DMARD09 is not set -# CONFIG_DMARD10 is not set -# CONFIG_FXLS8962AF_I2C is not set -# CONFIG_FXLS8962AF_SPI is not set -# CONFIG_IIO_ST_ACCEL_3AXIS is not set -# CONFIG_IIO_KX022A_SPI is not set -# CONFIG_IIO_KX022A_I2C is not set -# CONFIG_KXSD9 is not set -# CONFIG_KXCJK1013 is not set -# CONFIG_MC3230 is not set -# CONFIG_MMA7455_I2C is not set -# CONFIG_MMA7455_SPI is not set -# CONFIG_MMA7660 is not set -# CONFIG_MMA8452 is not set -# CONFIG_MMA9551 is not set -# CONFIG_MMA9553 is not set -# CONFIG_MSA311 is not set -# CONFIG_MXC4005 is not set -# CONFIG_MXC6255 is not set -# CONFIG_SCA3000 is not set -# CONFIG_SCA3300 is not set -# CONFIG_STK8312 is not set -# CONFIG_STK8BA50 is not set -# end of Accelerometers - -# -# Analog to digital converters -# -# CONFIG_AD4130 is not set -# CONFIG_AD7091R5 is not set -# CONFIG_AD7124 is not set -# CONFIG_AD7192 is not set -# CONFIG_AD7266 is not set -# CONFIG_AD7280 is not set -# CONFIG_AD7291 is not set -# CONFIG_AD7292 is not set -# CONFIG_AD7298 is not set -# CONFIG_AD7476 is not set -# CONFIG_AD7606_IFACE_PARALLEL is not set -# CONFIG_AD7606_IFACE_SPI is not set -# CONFIG_AD7766 is not set -# CONFIG_AD7768_1 is not set -# CONFIG_AD7780 is not set -# CONFIG_AD7791 is not set -# CONFIG_AD7793 is not set -# CONFIG_AD7887 is not set -# CONFIG_AD7923 is not set -# CONFIG_AD7949 is not set -# CONFIG_AD799X is not set -# CONFIG_ADI_AXI_ADC is not set -# CONFIG_ENVELOPE_DETECTOR is not set -# CONFIG_HI8435 is not set -# CONFIG_HX711 is not set -# CONFIG_INA2XX_ADC is not set -# CONFIG_LTC2471 is not set -# CONFIG_LTC2485 is not set -# CONFIG_LTC2496 is not set -# CONFIG_LTC2497 is not set -# CONFIG_MAX1027 is not set -# CONFIG_MAX11100 is not set -# CONFIG_MAX1118 is not set -# CONFIG_MAX11205 is not set -# CONFIG_MAX11410 is not set -# CONFIG_MAX1241 is not set -# CONFIG_MAX1363 is not set -# CONFIG_MAX9611 is not set -# CONFIG_MCP320X is not set -# CONFIG_MCP3422 is not set -# CONFIG_MCP3911 is not set -# CONFIG_NAU7802 is not set -# CONFIG_RICHTEK_RTQ6056 is not set -# CONFIG_RZG2L_ADC is not set -# CONFIG_SD_ADC_MODULATOR is not set -# CONFIG_TI_ADC081C is not set -# CONFIG_TI_ADC0832 is not set -# CONFIG_TI_ADC084S021 is not set -# CONFIG_TI_ADC12138 is not set -# CONFIG_TI_ADC108S102 is not set -# CONFIG_TI_ADC128S052 is not set -# CONFIG_TI_ADC161S626 is not set -# CONFIG_TI_ADS1015 is not set -# CONFIG_TI_ADS7950 is not set -# CONFIG_TI_ADS8344 is not set -# CONFIG_TI_ADS8688 is not set -# CONFIG_TI_ADS124S08 is not set -# CONFIG_TI_ADS131E08 is not set -# CONFIG_TI_TLC4541 is not set -# CONFIG_TI_TSC2046 is not set -# CONFIG_VF610_ADC is not set -# CONFIG_XILINX_XADC is not set -# end of Analog to digital converters - -# -# Analog to digital and digital to analog converters -# -# CONFIG_AD74115 is not set -# CONFIG_AD74413R is not set -# end of Analog to digital and digital to analog converters - -# -# Analog Front Ends -# -# CONFIG_IIO_RESCALE is not set -# end of Analog Front Ends - -# -# Amplifiers -# -# CONFIG_AD8366 is not set -# CONFIG_ADA4250 is not set -# CONFIG_HMC425 is not set -# end of Amplifiers - -# -# Capacitance to digital converters -# -# CONFIG_AD7150 is not set -# CONFIG_AD7746 is not set -# end of Capacitance to digital converters - -# -# Chemical Sensors -# -# CONFIG_ATLAS_PH_SENSOR is not set -# CONFIG_ATLAS_EZO_SENSOR is not set -# CONFIG_BME680 is not set -# CONFIG_CCS811 is not set -# CONFIG_IAQCORE is not set -# CONFIG_SCD30_CORE is not set -# CONFIG_SCD4X is not set -# CONFIG_SENSIRION_SGP30 is not set -# CONFIG_SENSIRION_SGP40 is not set -# CONFIG_SPS30_I2C is not set -# CONFIG_SENSEAIR_SUNRISE_CO2 is not set -# CONFIG_VZ89X is not set -# end of Chemical Sensors - -# -# Hid Sensor IIO Common -# -# end of Hid Sensor IIO Common - -# -# IIO SCMI Sensors -# -# end of IIO SCMI Sensors - -# -# SSP Sensor Common -# -# CONFIG_IIO_SSP_SENSORHUB is not set -# end of SSP Sensor Common - -# -# Digital to analog converters -# -# CONFIG_AD3552R is not set -# CONFIG_AD5064 is not set -# CONFIG_AD5360 is not set -# CONFIG_AD5380 is not set -# CONFIG_AD5421 is not set -# CONFIG_AD5446 is not set -# CONFIG_AD5449 is not set -# CONFIG_AD5592R is not set -# CONFIG_AD5593R is not set -# CONFIG_AD5504 is not set -# CONFIG_AD5624R_SPI is not set -# CONFIG_LTC2688 is not set -# CONFIG_AD5686_SPI is not set -# CONFIG_AD5696_I2C is not set -# CONFIG_AD5755 is not set -# CONFIG_AD5758 is not set -# CONFIG_AD5761 is not set -# CONFIG_AD5764 is not set -# CONFIG_AD5766 is not set -# CONFIG_AD5770R is not set -# CONFIG_AD5791 is not set -# CONFIG_AD7293 is not set -# CONFIG_AD7303 is not set -# CONFIG_AD8801 is not set -# CONFIG_DPOT_DAC is not set -# CONFIG_DS4424 is not set -# CONFIG_LTC1660 is not set -# CONFIG_LTC2632 is not set -# CONFIG_M62332 is not set -# CONFIG_MAX517 is not set -# CONFIG_MAX5821 is not set -# CONFIG_MCP4725 is not set -# CONFIG_MCP4922 is not set -# CONFIG_TI_DAC082S085 is not set -# CONFIG_TI_DAC5571 is not set -# CONFIG_TI_DAC7311 is not set -# CONFIG_TI_DAC7612 is not set -# CONFIG_VF610_DAC is not set -# end of Digital to analog converters - -# -# IIO dummy driver -# -# end of IIO dummy driver - -# -# Filters -# -# CONFIG_ADMV8818 is not set -# end of Filters - -# -# Frequency Synthesizers DDS/PLL -# - -# -# Clock Generator/Distribution -# -# CONFIG_AD9523 is not set -# end of Clock Generator/Distribution - -# -# Phase-Locked Loop (PLL) frequency synthesizers -# -# CONFIG_ADF4350 is not set -# CONFIG_ADF4371 is not set -# CONFIG_ADF4377 is not set -# CONFIG_ADMV1013 is not set -# CONFIG_ADMV1014 is not set -# CONFIG_ADMV4420 is not set -# CONFIG_ADRF6780 is not set -# end of Phase-Locked Loop (PLL) frequency synthesizers -# end of Frequency Synthesizers DDS/PLL - -# -# Digital gyroscope sensors -# -# CONFIG_ADIS16080 is not set -# CONFIG_ADIS16130 is not set -# CONFIG_ADIS16136 is not set -# CONFIG_ADIS16260 is not set -# CONFIG_ADXRS290 is not set -# CONFIG_ADXRS450 is not set -# CONFIG_BMG160 is not set -# CONFIG_FXAS21002C is not set -# CONFIG_MPU3050_I2C is not set -# CONFIG_IIO_ST_GYRO_3AXIS is not set -# CONFIG_ITG3200 is not set -# end of Digital gyroscope sensors - -# -# Health Sensors -# - -# -# Heart Rate Monitors -# -# CONFIG_AFE4403 is not set -# CONFIG_AFE4404 is not set -# CONFIG_MAX30100 is not set -# CONFIG_MAX30102 is not set -# end of Heart Rate Monitors -# end of Health Sensors - -# -# Humidity sensors -# -# CONFIG_AM2315 is not set -# CONFIG_DHT11 is not set -# CONFIG_HDC100X is not set -# CONFIG_HDC2010 is not set -# CONFIG_HTS221 is not set -# CONFIG_HTU21 is not set -# CONFIG_SI7005 is not set -# CONFIG_SI7020 is not set -# end of Humidity sensors - -# -# Inertial measurement units -# -# CONFIG_ADIS16400 is not set -# CONFIG_ADIS16460 is not set -# CONFIG_ADIS16475 is not set -# CONFIG_ADIS16480 is not set -# CONFIG_BMI160_I2C is not set -# CONFIG_BMI160_SPI is not set -# CONFIG_BOSCH_BNO055_I2C is not set -# CONFIG_FXOS8700_I2C is not set -# CONFIG_FXOS8700_SPI is not set -# CONFIG_KMX61 is not set -# CONFIG_INV_ICM42600_I2C is not set -# CONFIG_INV_ICM42600_SPI is not set -# CONFIG_INV_MPU6050_I2C is not set -# CONFIG_INV_MPU6050_SPI is not set -# CONFIG_IIO_ST_LSM6DSX is not set -# CONFIG_IIO_ST_LSM9DS0 is not set -# end of Inertial measurement units - -# -# Light sensors -# -# CONFIG_ADJD_S311 is not set -# CONFIG_ADUX1020 is not set -# CONFIG_AL3010 is not set -# CONFIG_AL3320A is not set -# CONFIG_APDS9300 is not set -# CONFIG_APDS9960 is not set -# CONFIG_AS73211 is not set -# CONFIG_BH1750 is not set -# CONFIG_BH1780 is not set -# CONFIG_CM32181 is not set -# CONFIG_CM3232 is not set -# CONFIG_CM3323 is not set -# CONFIG_CM3605 is not set -# CONFIG_CM36651 is not set -# CONFIG_GP2AP002 is not set -# CONFIG_GP2AP020A00F is not set -# CONFIG_SENSORS_ISL29018 is not set -# CONFIG_SENSORS_ISL29028 is not set -# CONFIG_ISL29125 is not set -# CONFIG_JSA1212 is not set -# CONFIG_RPR0521 is not set -# CONFIG_LTR501 is not set -# CONFIG_LTRF216A is not set -# CONFIG_LV0104CS is not set -# CONFIG_MAX44000 is not set -# CONFIG_MAX44009 is not set -# CONFIG_NOA1305 is not set -# CONFIG_OPT3001 is not set -# CONFIG_PA12203001 is not set -# CONFIG_SI1133 is not set -# CONFIG_SI1145 is not set -# CONFIG_STK3310 is not set -# CONFIG_ST_UVIS25 is not set -# CONFIG_TCS3414 is not set -# CONFIG_TCS3472 is not set -# CONFIG_SENSORS_TSL2563 is not set -# CONFIG_TSL2583 is not set -# CONFIG_TSL2591 is not set -# CONFIG_TSL2772 is not set -# CONFIG_TSL4531 is not set -# CONFIG_US5182D is not set -# CONFIG_VCNL4000 is not set -# CONFIG_VCNL4035 is not set -# CONFIG_VEML6030 is not set -# CONFIG_VEML6070 is not set -# CONFIG_VL6180 is not set -# CONFIG_ZOPT2201 is not set -# end of Light sensors - -# -# Magnetometer sensors -# -# CONFIG_AK8974 is not set -# CONFIG_AK8975 is not set -# CONFIG_AK09911 is not set -# CONFIG_BMC150_MAGN_I2C is not set -# CONFIG_BMC150_MAGN_SPI is not set -# CONFIG_MAG3110 is not set -# CONFIG_MMC35240 is not set -# CONFIG_IIO_ST_MAGN_3AXIS is not set -# CONFIG_SENSORS_HMC5843_I2C is not set -# CONFIG_SENSORS_HMC5843_SPI is not set -# CONFIG_SENSORS_RM3100_I2C is not set -# CONFIG_SENSORS_RM3100_SPI is not set -# CONFIG_YAMAHA_YAS530 is not set -# end of Magnetometer sensors - -# -# Multiplexers -# -# CONFIG_IIO_MUX is not set -# end of Multiplexers - -# -# Inclinometer sensors -# -# end of Inclinometer sensors - -# -# Linear and angular position sensors -# -# end of Linear and angular position sensors - -# -# Digital potentiometers -# -# CONFIG_AD5110 is not set -# CONFIG_AD5272 is not set -# CONFIG_DS1803 is not set -# CONFIG_MAX5432 is not set -# CONFIG_MAX5481 is not set -# CONFIG_MAX5487 is not set -# CONFIG_MCP4018 is not set -# CONFIG_MCP4131 is not set -# CONFIG_MCP4531 is not set -# CONFIG_MCP41010 is not set -# CONFIG_TPL0102 is not set -# end of Digital potentiometers - -# -# Digital potentiostats -# -# CONFIG_LMP91000 is not set -# end of Digital potentiostats - -# -# Pressure sensors -# -# CONFIG_ABP060MG is not set -# CONFIG_BMP280 is not set -# CONFIG_DLHL60D is not set -# CONFIG_DPS310 is not set -# CONFIG_HP03 is not set -# CONFIG_ICP10100 is not set -# CONFIG_MPL115_I2C is not set -# CONFIG_MPL115_SPI is not set -# CONFIG_MPL3115 is not set -# CONFIG_MS5611 is not set -# CONFIG_MS5637 is not set -# CONFIG_IIO_ST_PRESS is not set -# CONFIG_T5403 is not set -# CONFIG_HP206C is not set -# CONFIG_ZPA2326 is not set -# end of Pressure sensors - -# -# Lightning sensors -# -# CONFIG_AS3935 is not set -# end of Lightning sensors - -# -# Proximity and distance sensors -# -# CONFIG_ISL29501 is not set -# CONFIG_LIDAR_LITE_V2 is not set -# CONFIG_MB1232 is not set -# CONFIG_PING is not set -# CONFIG_RFD77402 is not set -# CONFIG_SRF04 is not set -# CONFIG_SX9310 is not set -# CONFIG_SX9324 is not set -# CONFIG_SX9360 is not set -# CONFIG_SX9500 is not set -# CONFIG_SRF08 is not set -# CONFIG_VCNL3020 is not set -# CONFIG_VL53L0X_I2C is not set -# end of Proximity and distance sensors - -# -# Resolver to digital converters -# -# CONFIG_AD2S90 is not set -# CONFIG_AD2S1200 is not set -# end of Resolver to digital converters - -# -# Temperature sensors -# -# CONFIG_LTC2983 is not set -# CONFIG_MAXIM_THERMOCOUPLE is not set -# CONFIG_MLX90614 is not set -# CONFIG_MLX90632 is not set -# CONFIG_TMP006 is not set -# CONFIG_TMP007 is not set -# CONFIG_TMP117 is not set -# CONFIG_TSYS01 is not set -# CONFIG_TSYS02D is not set -# CONFIG_MAX30208 is not set -# CONFIG_MAX31856 is not set -# CONFIG_MAX31865 is not set -# end of Temperature sensors - -# CONFIG_NTB is not set -# CONFIG_PWM is not set - -# -# IRQ chip support -# -CONFIG_IRQCHIP=y -# CONFIG_AL_FIC is not set -CONFIG_RENESAS_RZG2L_IRQC=y -# CONFIG_XILINX_INTC is not set -CONFIG_RISCV_INTC=y -CONFIG_SIFIVE_PLIC=y -# end of IRQ chip support - -# CONFIG_IPACK_BUS is not set -CONFIG_RESET_CONTROLLER=y -CONFIG_RESET_POLARFIRE_SOC=y -# CONFIG_RESET_RZG2L_USBPHY_CTRL is not set -CONFIG_RESET_SIMPLE=y -CONFIG_RESET_STARFIVE_JH7100=y -# CONFIG_RESET_TI_SYSCON is not set -# CONFIG_RESET_TI_TPS380X is not set - -# -# PHY Subsystem -# -# CONFIG_GENERIC_PHY is not set -# CONFIG_PHY_CAN_TRANSCEIVER is not set - -# -# PHY drivers for Broadcom platforms -# -# CONFIG_BCM_KONA_USB2_PHY is not set -# end of PHY drivers for Broadcom platforms - -# CONFIG_PHY_CADENCE_TORRENT is not set -# CONFIG_PHY_CADENCE_DPHY is not set -# CONFIG_PHY_CADENCE_DPHY_RX is not set -# CONFIG_PHY_CADENCE_SIERRA is not set -# CONFIG_PHY_CADENCE_SALVO is not set -# CONFIG_PHY_PXA_28NM_HSIC is not set -# CONFIG_PHY_PXA_28NM_USB2 is not set -# CONFIG_PHY_LAN966X_SERDES is not set -# CONFIG_PHY_CPCAP_USB is not set -# CONFIG_PHY_MAPPHONE_MDM6600 is not set -# CONFIG_PHY_OCELOT_SERDES is not set -# CONFIG_PHY_R8A779F0_ETHERNET_SERDES is not set -# CONFIG_PHY_RCAR_GEN3_PCIE is not set -# CONFIG_PHY_RCAR_GEN3_USB2 is not set -# CONFIG_PHY_RCAR_GEN3_USB3 is not set -# end of PHY Subsystem - -# CONFIG_POWERCAP is not set -# CONFIG_MCB is not set - -# -# Performance monitor support -# -CONFIG_RISCV_PMU=y -CONFIG_RISCV_PMU_LEGACY=y -CONFIG_RISCV_PMU_SBI=y -# end of Performance monitor support - -# CONFIG_RAS is not set -# CONFIG_USB4 is not set - -# -# Android -# -# CONFIG_ANDROID_BINDER_IPC is not set -# end of Android - -CONFIG_LIBNVDIMM=y -CONFIG_BLK_DEV_PMEM=y -CONFIG_ND_CLAIM=y -CONFIG_ND_BTT=y -CONFIG_BTT=y -CONFIG_OF_PMEM=y -CONFIG_DAX=y -CONFIG_NVMEM=y -CONFIG_NVMEM_SYSFS=y -# CONFIG_NVMEM_RMEM is not set - -# -# HW tracing support -# -# CONFIG_STM is not set -# CONFIG_INTEL_TH is not set -# end of HW tracing support - -# CONFIG_FPGA is not set -# CONFIG_FSI is not set -# CONFIG_SIOX is not set -# CONFIG_SLIMBUS is not set -# CONFIG_INTERCONNECT is not set -# CONFIG_COUNTER is not set -# CONFIG_MOST is not set -# CONFIG_PECI is not set -# CONFIG_HTE is not set -# end of Device Drivers - -# -# File systems -# -# CONFIG_VALIDATE_FS_PARSER is not set -CONFIG_FS_IOMAP=y -# CONFIG_EXT2_FS is not set -# CONFIG_EXT3_FS is not set -CONFIG_EXT4_FS=y -CONFIG_EXT4_USE_FOR_EXT2=y -CONFIG_EXT4_FS_POSIX_ACL=y -CONFIG_EXT4_FS_SECURITY=y -# CONFIG_EXT4_DEBUG is not set -CONFIG_JBD2=y -# CONFIG_JBD2_DEBUG is not set -CONFIG_FS_MBCACHE=y -# CONFIG_REISERFS_FS is not set -# CONFIG_JFS_FS is not set -# CONFIG_XFS_FS is not set -# CONFIG_GFS2_FS is not set -# CONFIG_OCFS2_FS is not set -CONFIG_BTRFS_FS=m -CONFIG_BTRFS_FS_POSIX_ACL=y -# CONFIG_BTRFS_FS_CHECK_INTEGRITY is not set -# CONFIG_BTRFS_FS_RUN_SANITY_TESTS is not set -# CONFIG_BTRFS_DEBUG is not set -# CONFIG_BTRFS_ASSERT is not set -# CONFIG_BTRFS_FS_REF_VERIFY is not set -# CONFIG_NILFS2_FS is not set -# CONFIG_F2FS_FS is not set -CONFIG_FS_POSIX_ACL=y -CONFIG_EXPORTFS=y -# CONFIG_EXPORTFS_BLOCK_OPS is not set -CONFIG_FILE_LOCKING=y -# CONFIG_FS_ENCRYPTION is not set -# CONFIG_FS_VERITY is not set -CONFIG_FSNOTIFY=y -CONFIG_DNOTIFY=y -CONFIG_INOTIFY_USER=y -# CONFIG_FANOTIFY is not set -# CONFIG_QUOTA is not set -CONFIG_AUTOFS4_FS=y -CONFIG_AUTOFS_FS=y -# CONFIG_FUSE_FS is not set -CONFIG_OVERLAY_FS=m -# CONFIG_OVERLAY_FS_REDIRECT_DIR is not set -CONFIG_OVERLAY_FS_REDIRECT_ALWAYS_FOLLOW=y -# CONFIG_OVERLAY_FS_INDEX is not set -# CONFIG_OVERLAY_FS_XINO_AUTO is not set -# CONFIG_OVERLAY_FS_METACOPY is not set - -# -# Caches -# -CONFIG_NETFS_SUPPORT=y -# CONFIG_NETFS_STATS is not set -# CONFIG_FSCACHE is not set -# end of Caches - -# -# CD-ROM/DVD Filesystems -# -CONFIG_ISO9660_FS=y -CONFIG_JOLIET=y -CONFIG_ZISOFS=y -# CONFIG_UDF_FS is not set -# end of CD-ROM/DVD Filesystems - -# -# DOS/FAT/EXFAT/NT Filesystems -# -CONFIG_FAT_FS=y -CONFIG_MSDOS_FS=y -CONFIG_VFAT_FS=y -CONFIG_FAT_DEFAULT_CODEPAGE=437 -CONFIG_FAT_DEFAULT_IOCHARSET="iso8859-1" -# CONFIG_FAT_DEFAULT_UTF8 is not set -# CONFIG_EXFAT_FS is not set -# CONFIG_NTFS_FS is not set -# CONFIG_NTFS3_FS is not set -# end of DOS/FAT/EXFAT/NT Filesystems - -# -# Pseudo filesystems -# -CONFIG_PROC_FS=y -# CONFIG_PROC_KCORE is not set -CONFIG_PROC_SYSCTL=y -CONFIG_PROC_PAGE_MONITOR=y -CONFIG_PROC_CHILDREN=y -CONFIG_KERNFS=y -CONFIG_SYSFS=y -CONFIG_TMPFS=y -CONFIG_TMPFS_POSIX_ACL=y -CONFIG_TMPFS_XATTR=y -# CONFIG_TMPFS_INODE64 is not set -CONFIG_ARCH_SUPPORTS_HUGETLBFS=y -CONFIG_HUGETLBFS=y -CONFIG_HUGETLB_PAGE=y -CONFIG_MEMFD_CREATE=y -CONFIG_ARCH_HAS_GIGANTIC_PAGE=y -CONFIG_CONFIGFS_FS=y -CONFIG_EFIVAR_FS=m -# end of Pseudo filesystems - -CONFIG_MISC_FILESYSTEMS=y -# CONFIG_ORANGEFS_FS is not set -# CONFIG_ADFS_FS is not set -# CONFIG_AFFS_FS is not set -# CONFIG_ECRYPT_FS is not set -# CONFIG_HFS_FS is not set -# CONFIG_HFSPLUS_FS is not set -# CONFIG_BEFS_FS is not set -# CONFIG_BFS_FS is not set -# CONFIG_EFS_FS is not set -# CONFIG_CRAMFS is not set -# CONFIG_SQUASHFS is not set -# CONFIG_VXFS_FS is not set -# CONFIG_MINIX_FS is not set -# CONFIG_OMFS_FS is not set -# CONFIG_HPFS_FS is not set -# CONFIG_QNX4FS_FS is not set -# CONFIG_QNX6FS_FS is not set -# CONFIG_ROMFS_FS is not set -# CONFIG_PSTORE is not set -# CONFIG_SYSV_FS is not set -# CONFIG_UFS_FS is not set -# CONFIG_EROFS_FS is not set -CONFIG_NETWORK_FILESYSTEMS=y -CONFIG_NFS_FS=y -CONFIG_NFS_V2=y -CONFIG_NFS_V3=y -# CONFIG_NFS_V3_ACL is not set -CONFIG_NFS_V4=y -# CONFIG_NFS_SWAP is not set -CONFIG_NFS_V4_1=y -CONFIG_NFS_V4_2=y -CONFIG_PNFS_FILE_LAYOUT=y -CONFIG_PNFS_BLOCK=y -CONFIG_PNFS_FLEXFILE_LAYOUT=y -CONFIG_NFS_V4_1_IMPLEMENTATION_ID_DOMAIN="kernel.org" -# CONFIG_NFS_V4_1_MIGRATION is not set -CONFIG_NFS_V4_SECURITY_LABEL=y -CONFIG_ROOT_NFS=y -# CONFIG_NFS_USE_LEGACY_DNS is not set -CONFIG_NFS_USE_KERNEL_DNS=y -CONFIG_NFS_DISABLE_UDP_SUPPORT=y -# CONFIG_NFS_V4_2_READ_PLUS is not set -# CONFIG_NFSD is not set -CONFIG_GRACE_PERIOD=y -CONFIG_LOCKD=y -CONFIG_LOCKD_V4=y -CONFIG_NFS_COMMON=y -CONFIG_NFS_V4_2_SSC_HELPER=y -CONFIG_SUNRPC=y -CONFIG_SUNRPC_GSS=y -CONFIG_SUNRPC_BACKCHANNEL=y -# CONFIG_SUNRPC_DEBUG is not set -# CONFIG_CEPH_FS is not set -# CONFIG_CIFS is not set -# CONFIG_SMB_SERVER is not set -# CONFIG_CODA_FS is not set -# CONFIG_AFS_FS is not set -CONFIG_9P_FS=y -# CONFIG_9P_FS_POSIX_ACL is not set -# CONFIG_9P_FS_SECURITY is not set -CONFIG_NLS=y -CONFIG_NLS_DEFAULT="iso8859-1" -CONFIG_NLS_CODEPAGE_437=y -# CONFIG_NLS_CODEPAGE_737 is not set -# CONFIG_NLS_CODEPAGE_775 is not set -# CONFIG_NLS_CODEPAGE_850 is not set -# CONFIG_NLS_CODEPAGE_852 is not set -# CONFIG_NLS_CODEPAGE_855 is not set -# CONFIG_NLS_CODEPAGE_857 is not set -# CONFIG_NLS_CODEPAGE_860 is not set -# CONFIG_NLS_CODEPAGE_861 is not set -# CONFIG_NLS_CODEPAGE_862 is not set -# CONFIG_NLS_CODEPAGE_863 is not set -# CONFIG_NLS_CODEPAGE_864 is not set -# CONFIG_NLS_CODEPAGE_865 is not set -# CONFIG_NLS_CODEPAGE_866 is not set -# CONFIG_NLS_CODEPAGE_869 is not set -# CONFIG_NLS_CODEPAGE_936 is not set -# CONFIG_NLS_CODEPAGE_950 is not set -# CONFIG_NLS_CODEPAGE_932 is not set -# CONFIG_NLS_CODEPAGE_949 is not set -# CONFIG_NLS_CODEPAGE_874 is not set -# CONFIG_NLS_ISO8859_8 is not set -# CONFIG_NLS_CODEPAGE_1250 is not set -# CONFIG_NLS_CODEPAGE_1251 is not set -# CONFIG_NLS_ASCII is not set -CONFIG_NLS_ISO8859_1=y -# CONFIG_NLS_ISO8859_2 is not set -# CONFIG_NLS_ISO8859_3 is not set -# CONFIG_NLS_ISO8859_4 is not set -# CONFIG_NLS_ISO8859_5 is not set -# CONFIG_NLS_ISO8859_6 is not set -# CONFIG_NLS_ISO8859_7 is not set -# CONFIG_NLS_ISO8859_9 is not set -# CONFIG_NLS_ISO8859_13 is not set -# CONFIG_NLS_ISO8859_14 is not set -# CONFIG_NLS_ISO8859_15 is not set -# CONFIG_NLS_KOI8_R is not set -# CONFIG_NLS_KOI8_U is not set -# CONFIG_NLS_MAC_ROMAN is not set -# CONFIG_NLS_MAC_CELTIC is not set -# CONFIG_NLS_MAC_CENTEURO is not set -# CONFIG_NLS_MAC_CROATIAN is not set -# CONFIG_NLS_MAC_CYRILLIC is not set -# CONFIG_NLS_MAC_GAELIC is not set -# CONFIG_NLS_MAC_GREEK is not set -# CONFIG_NLS_MAC_ICELAND is not set -# CONFIG_NLS_MAC_INUIT is not set -# CONFIG_NLS_MAC_ROMANIAN is not set -# CONFIG_NLS_MAC_TURKISH is not set -# CONFIG_NLS_UTF8 is not set -# CONFIG_DLM is not set -# CONFIG_UNICODE is not set -CONFIG_IO_WQ=y -# end of File systems - -# -# Security options -# -CONFIG_KEYS=y -# CONFIG_KEYS_REQUEST_CACHE is not set -# CONFIG_PERSISTENT_KEYRINGS is not set -# CONFIG_TRUSTED_KEYS is not set -# CONFIG_ENCRYPTED_KEYS is not set -# CONFIG_KEY_DH_OPERATIONS is not set -# CONFIG_SECURITY_DMESG_RESTRICT is not set -CONFIG_SECURITY=y -CONFIG_SECURITYFS=y -CONFIG_SECURITY_NETWORK=y -# CONFIG_SECURITY_NETWORK_XFRM is not set -CONFIG_SECURITY_PATH=y -CONFIG_LSM_MMAP_MIN_ADDR=65536 -CONFIG_HAVE_HARDENED_USERCOPY_ALLOCATOR=y -# CONFIG_HARDENED_USERCOPY is not set -# CONFIG_FORTIFY_SOURCE is not set -# CONFIG_STATIC_USERMODEHELPER is not set -CONFIG_SECURITY_SELINUX=y -# CONFIG_SECURITY_SELINUX_BOOTPARAM is not set -# CONFIG_SECURITY_SELINUX_DISABLE is not set -CONFIG_SECURITY_SELINUX_DEVELOP=y -CONFIG_SECURITY_SELINUX_AVC_STATS=y -CONFIG_SECURITY_SELINUX_CHECKREQPROT_VALUE=0 -CONFIG_SECURITY_SELINUX_SIDTAB_HASH_BITS=9 -CONFIG_SECURITY_SELINUX_SID2STR_CACHE_SIZE=256 -# CONFIG_SECURITY_SMACK is not set -# CONFIG_SECURITY_TOMOYO is not set -CONFIG_SECURITY_APPARMOR=y -# CONFIG_SECURITY_APPARMOR_DEBUG is not set -CONFIG_SECURITY_APPARMOR_INTROSPECT_POLICY=y -CONFIG_SECURITY_APPARMOR_HASH=y -CONFIG_SECURITY_APPARMOR_HASH_DEFAULT=y -CONFIG_SECURITY_APPARMOR_EXPORT_BINARY=y -CONFIG_SECURITY_APPARMOR_PARANOID_LOAD=y -# CONFIG_SECURITY_LOADPIN is not set -# CONFIG_SECURITY_YAMA is not set -# CONFIG_SECURITY_SAFESETID is not set -# CONFIG_SECURITY_LOCKDOWN_LSM is not set -# CONFIG_SECURITY_LANDLOCK is not set -CONFIG_INTEGRITY=y -# CONFIG_INTEGRITY_SIGNATURE is not set -CONFIG_INTEGRITY_AUDIT=y -# CONFIG_IMA is not set -# CONFIG_EVM is not set -# CONFIG_DEFAULT_SECURITY_SELINUX is not set -# CONFIG_DEFAULT_SECURITY_APPARMOR is not set -CONFIG_DEFAULT_SECURITY_DAC=y -CONFIG_LSM="landlock,lockdown,yama,loadpin,safesetid,integrity,bpf" - -# -# Kernel hardening options -# - -# -# Memory initialization -# -CONFIG_INIT_STACK_NONE=y -# CONFIG_GCC_PLUGIN_STRUCTLEAK_USER is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF_ALL is not set -# CONFIG_INIT_ON_ALLOC_DEFAULT_ON is not set -# CONFIG_INIT_ON_FREE_DEFAULT_ON is not set -CONFIG_CC_HAS_ZERO_CALL_USED_REGS=y -# CONFIG_ZERO_CALL_USED_REGS is not set -# end of Memory initialization - -CONFIG_RANDSTRUCT_NONE=y -# CONFIG_RANDSTRUCT_FULL is not set -# CONFIG_RANDSTRUCT_PERFORMANCE is not set -# end of Kernel hardening options -# end of Security options - -CONFIG_XOR_BLOCKS=m -CONFIG_CRYPTO=y - -# -# Crypto core or helper -# -CONFIG_CRYPTO_ALGAPI=y -CONFIG_CRYPTO_ALGAPI2=y -CONFIG_CRYPTO_AEAD=y -CONFIG_CRYPTO_AEAD2=y -CONFIG_CRYPTO_SKCIPHER=y -CONFIG_CRYPTO_SKCIPHER2=y -CONFIG_CRYPTO_HASH=y -CONFIG_CRYPTO_HASH2=y -CONFIG_CRYPTO_RNG=m -CONFIG_CRYPTO_RNG2=y -CONFIG_CRYPTO_RNG_DEFAULT=m -CONFIG_CRYPTO_AKCIPHER2=y -CONFIG_CRYPTO_AKCIPHER=y -CONFIG_CRYPTO_KPP2=y -CONFIG_CRYPTO_ACOMP2=y -CONFIG_CRYPTO_MANAGER=y -CONFIG_CRYPTO_MANAGER2=y -# CONFIG_CRYPTO_USER is not set -CONFIG_CRYPTO_MANAGER_DISABLE_TESTS=y -CONFIG_CRYPTO_NULL=m -CONFIG_CRYPTO_NULL2=y -# CONFIG_CRYPTO_PCRYPT is not set -# CONFIG_CRYPTO_CRYPTD is not set -CONFIG_CRYPTO_AUTHENC=m -# CONFIG_CRYPTO_TEST is not set -CONFIG_CRYPTO_ENGINE=y -# end of Crypto core or helper - -# -# Public-key cryptography -# -CONFIG_CRYPTO_RSA=y -# CONFIG_CRYPTO_DH is not set -# CONFIG_CRYPTO_ECDH is not set -# CONFIG_CRYPTO_ECDSA is not set -# CONFIG_CRYPTO_ECRDSA is not set -# CONFIG_CRYPTO_SM2 is not set -# CONFIG_CRYPTO_CURVE25519 is not set -# end of Public-key cryptography - -# -# Block ciphers -# -CONFIG_CRYPTO_AES=m -# CONFIG_CRYPTO_AES_TI is not set -# CONFIG_CRYPTO_ANUBIS is not set -# CONFIG_CRYPTO_ARIA is not set -# CONFIG_CRYPTO_BLOWFISH is not set -# CONFIG_CRYPTO_CAMELLIA is not set -# CONFIG_CRYPTO_CAST5 is not set -# CONFIG_CRYPTO_CAST6 is not set -# CONFIG_CRYPTO_DES is not set -# CONFIG_CRYPTO_FCRYPT is not set -# CONFIG_CRYPTO_KHAZAD is not set -# CONFIG_CRYPTO_SEED is not set -# CONFIG_CRYPTO_SERPENT is not set -# CONFIG_CRYPTO_SM4_GENERIC is not set -# CONFIG_CRYPTO_TEA is not set -# CONFIG_CRYPTO_TWOFISH is not set -# end of Block ciphers - -# -# Length-preserving ciphers and modes -# -# CONFIG_CRYPTO_ADIANTUM is not set -# CONFIG_CRYPTO_ARC4 is not set -# CONFIG_CRYPTO_CHACHA20 is not set -CONFIG_CRYPTO_CBC=m -# CONFIG_CRYPTO_CFB is not set -CONFIG_CRYPTO_CTR=m -# CONFIG_CRYPTO_CTS is not set -# CONFIG_CRYPTO_ECB is not set -# CONFIG_CRYPTO_HCTR2 is not set -# CONFIG_CRYPTO_KEYWRAP is not set -# CONFIG_CRYPTO_LRW is not set -# CONFIG_CRYPTO_OFB is not set -# CONFIG_CRYPTO_PCBC is not set -# CONFIG_CRYPTO_XTS is not set -# end of Length-preserving ciphers and modes - -# -# AEAD (authenticated encryption with associated data) ciphers -# -# CONFIG_CRYPTO_AEGIS128 is not set -# CONFIG_CRYPTO_CHACHA20POLY1305 is not set -# CONFIG_CRYPTO_CCM is not set -CONFIG_CRYPTO_GCM=m -CONFIG_CRYPTO_SEQIV=m -CONFIG_CRYPTO_ECHAINIV=m -# CONFIG_CRYPTO_ESSIV is not set -# end of AEAD (authenticated encryption with associated data) ciphers - -# -# Hashes, digests, and MACs -# -CONFIG_CRYPTO_BLAKE2B=m -# CONFIG_CRYPTO_CMAC is not set -CONFIG_CRYPTO_GHASH=m -CONFIG_CRYPTO_HMAC=m -# CONFIG_CRYPTO_MD4 is not set -# CONFIG_CRYPTO_MD5 is not set -# CONFIG_CRYPTO_MICHAEL_MIC is not set -# CONFIG_CRYPTO_POLY1305 is not set -# CONFIG_CRYPTO_RMD160 is not set -CONFIG_CRYPTO_SHA1=y -CONFIG_CRYPTO_SHA256=m -CONFIG_CRYPTO_SHA512=m -# CONFIG_CRYPTO_SHA3 is not set -# CONFIG_CRYPTO_SM3_GENERIC is not set -# CONFIG_CRYPTO_STREEBOG is not set -# CONFIG_CRYPTO_VMAC is not set -# CONFIG_CRYPTO_WP512 is not set -# CONFIG_CRYPTO_XCBC is not set -CONFIG_CRYPTO_XXHASH=m -# end of Hashes, digests, and MACs - -# -# CRCs (cyclic redundancy checks) -# -CONFIG_CRYPTO_CRC32C=y -# CONFIG_CRYPTO_CRC32 is not set -# CONFIG_CRYPTO_CRCT10DIF is not set -# end of CRCs (cyclic redundancy checks) - -# -# Compression -# -# CONFIG_CRYPTO_DEFLATE is not set -# CONFIG_CRYPTO_LZO is not set -# CONFIG_CRYPTO_842 is not set -# CONFIG_CRYPTO_LZ4 is not set -# CONFIG_CRYPTO_LZ4HC is not set -# CONFIG_CRYPTO_ZSTD is not set -# end of Compression - -# -# Random number generation -# -# CONFIG_CRYPTO_ANSI_CPRNG is not set -CONFIG_CRYPTO_DRBG_MENU=m -CONFIG_CRYPTO_DRBG_HMAC=y -# CONFIG_CRYPTO_DRBG_HASH is not set -# CONFIG_CRYPTO_DRBG_CTR is not set -CONFIG_CRYPTO_DRBG=m -CONFIG_CRYPTO_JITTERENTROPY=m -# end of Random number generation - -# -# Userspace interface -# -CONFIG_CRYPTO_USER_API=y -CONFIG_CRYPTO_USER_API_HASH=y -# CONFIG_CRYPTO_USER_API_SKCIPHER is not set -# CONFIG_CRYPTO_USER_API_RNG is not set -# CONFIG_CRYPTO_USER_API_AEAD is not set -CONFIG_CRYPTO_USER_API_ENABLE_OBSOLETE=y -# end of Userspace interface - -CONFIG_CRYPTO_HW=y -# CONFIG_CRYPTO_DEV_ATMEL_ECC is not set -# CONFIG_CRYPTO_DEV_ATMEL_SHA204A is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCC is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXX is not set -# CONFIG_CRYPTO_DEV_QAT_C62X is not set -# CONFIG_CRYPTO_DEV_QAT_4XXX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCCVF is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXXVF is not set -# CONFIG_CRYPTO_DEV_QAT_C62XVF is not set -# CONFIG_CRYPTO_DEV_NITROX_CNN55XX is not set -CONFIG_CRYPTO_DEV_VIRTIO=y -# CONFIG_CRYPTO_DEV_SAFEXCEL is not set -# CONFIG_CRYPTO_DEV_CCREE is not set -# CONFIG_CRYPTO_DEV_AMLOGIC_GXL is not set -# CONFIG_ASYMMETRIC_KEY_TYPE is not set - -# -# Certificates for signature checking -# -# CONFIG_SYSTEM_BLACKLIST_KEYRING is not set -# end of Certificates for signature checking - -CONFIG_BINARY_PRINTF=y - -# -# Library routines -# -CONFIG_RAID6_PQ=m -CONFIG_RAID6_PQ_BENCHMARK=y -# CONFIG_PACKING is not set -CONFIG_BITREVERSE=y -CONFIG_GENERIC_STRNCPY_FROM_USER=y -CONFIG_GENERIC_STRNLEN_USER=y -CONFIG_GENERIC_NET_UTILS=y -# CONFIG_CORDIC is not set -# CONFIG_PRIME_NUMBERS is not set -CONFIG_RATIONAL=y -CONFIG_GENERIC_PCI_IOMAP=y - -# -# Crypto library routines -# -CONFIG_CRYPTO_LIB_UTILS=y -CONFIG_CRYPTO_LIB_AES=m -CONFIG_CRYPTO_LIB_GF128MUL=m -CONFIG_CRYPTO_LIB_BLAKE2S_GENERIC=y -# CONFIG_CRYPTO_LIB_CHACHA is not set -# CONFIG_CRYPTO_LIB_CURVE25519 is not set -CONFIG_CRYPTO_LIB_POLY1305_RSIZE=1 -# CONFIG_CRYPTO_LIB_POLY1305 is not set -# CONFIG_CRYPTO_LIB_CHACHA20POLY1305 is not set -CONFIG_CRYPTO_LIB_SHA1=y -CONFIG_CRYPTO_LIB_SHA256=m -# end of Crypto library routines - -# CONFIG_CRC_CCITT is not set -CONFIG_CRC16=y -# CONFIG_CRC_T10DIF is not set -# CONFIG_CRC64_ROCKSOFT is not set -CONFIG_CRC_ITU_T=y -CONFIG_CRC32=y -# CONFIG_CRC32_SELFTEST is not set -CONFIG_CRC32_SLICEBY8=y -# CONFIG_CRC32_SLICEBY4 is not set -# CONFIG_CRC32_SARWATE is not set -# CONFIG_CRC32_BIT is not set -# CONFIG_CRC64 is not set -# CONFIG_CRC4 is not set -CONFIG_CRC7=y -CONFIG_LIBCRC32C=m -# CONFIG_CRC8 is not set -CONFIG_XXHASH=y -CONFIG_AUDIT_GENERIC=y -# CONFIG_RANDOM32_SELFTEST is not set -CONFIG_ZLIB_INFLATE=y -CONFIG_ZLIB_DEFLATE=m -CONFIG_LZO_COMPRESS=m -CONFIG_LZO_DECOMPRESS=y -CONFIG_LZ4_DECOMPRESS=y -CONFIG_ZSTD_COMMON=y -CONFIG_ZSTD_COMPRESS=y -CONFIG_ZSTD_DECOMPRESS=y -CONFIG_XZ_DEC=y -CONFIG_XZ_DEC_X86=y -CONFIG_XZ_DEC_POWERPC=y -CONFIG_XZ_DEC_IA64=y -CONFIG_XZ_DEC_ARM=y -CONFIG_XZ_DEC_ARMTHUMB=y -CONFIG_XZ_DEC_SPARC=y -# CONFIG_XZ_DEC_MICROLZMA is not set -CONFIG_XZ_DEC_BCJ=y -# CONFIG_XZ_DEC_TEST is not set -CONFIG_DECOMPRESS_GZIP=y -CONFIG_DECOMPRESS_BZIP2=y -CONFIG_DECOMPRESS_LZMA=y -CONFIG_DECOMPRESS_XZ=y -CONFIG_DECOMPRESS_LZO=y -CONFIG_DECOMPRESS_LZ4=y -CONFIG_DECOMPRESS_ZSTD=y -CONFIG_GENERIC_ALLOCATOR=y -CONFIG_INTERVAL_TREE=y -CONFIG_ASSOCIATIVE_ARRAY=y -CONFIG_HAS_IOMEM=y -CONFIG_HAS_IOPORT_MAP=y -CONFIG_HAS_DMA=y -CONFIG_NEED_DMA_MAP_STATE=y -CONFIG_ARCH_DMA_ADDR_T_64BIT=y -CONFIG_DMA_DECLARE_COHERENT=y -CONFIG_ARCH_HAS_SETUP_DMA_OPS=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_DEVICE=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_CPU=y -CONFIG_ARCH_HAS_DMA_PREP_COHERENT=y -CONFIG_SWIOTLB=y -# CONFIG_DMA_RESTRICTED_POOL is not set -CONFIG_DMA_NONCOHERENT_MMAP=y -CONFIG_DMA_COHERENT_POOL=y -CONFIG_DMA_DIRECT_REMAP=y -# CONFIG_DMA_API_DEBUG is not set -# CONFIG_DMA_MAP_BENCHMARK is not set -CONFIG_SGL_ALLOC=y -# CONFIG_CPUMASK_OFFSTACK is not set -# CONFIG_FORCE_NR_CPUS is not set -CONFIG_CPU_RMAP=y -CONFIG_DQL=y -CONFIG_GLOB=y -# CONFIG_GLOB_SELFTEST is not set -CONFIG_NLATTR=y -CONFIG_CLZ_TAB=y -# CONFIG_IRQ_POLL is not set -CONFIG_MPILIB=y -CONFIG_LIBFDT=y -CONFIG_OID_REGISTRY=y -CONFIG_UCS2_STRING=y -CONFIG_HAVE_GENERIC_VDSO=y -CONFIG_GENERIC_GETTIMEOFDAY=y -CONFIG_GENERIC_VDSO_TIME_NS=y -CONFIG_FONT_SUPPORT=y -# CONFIG_FONTS is not set -CONFIG_FONT_8x8=y -CONFIG_FONT_8x16=y -CONFIG_SG_POOL=y -CONFIG_ARCH_HAS_PMEM_API=y -CONFIG_MEMREGION=y -CONFIG_ARCH_STACKWALK=y -CONFIG_STACKDEPOT=y -CONFIG_SBITMAP=y -# end of Library routines - -CONFIG_GENERIC_IOREMAP=y -CONFIG_GENERIC_LIB_DEVMEM_IS_ALLOWED=y - -# -# Kernel hacking -# - -# -# printk and dmesg options -# -CONFIG_PRINTK_TIME=y -# CONFIG_PRINTK_CALLER is not set -# CONFIG_STACKTRACE_BUILD_ID is not set -CONFIG_CONSOLE_LOGLEVEL_DEFAULT=7 -CONFIG_CONSOLE_LOGLEVEL_QUIET=4 -CONFIG_MESSAGE_LOGLEVEL_DEFAULT=4 -# CONFIG_BOOT_PRINTK_DELAY is not set -# CONFIG_DYNAMIC_DEBUG is not set -# CONFIG_DYNAMIC_DEBUG_CORE is not set -CONFIG_SYMBOLIC_ERRNAME=y -CONFIG_DEBUG_BUGVERBOSE=y -# end of printk and dmesg options - -CONFIG_DEBUG_KERNEL=y -CONFIG_DEBUG_MISC=y - -# -# Compile-time checks and compiler options -# -CONFIG_DEBUG_INFO_NONE=y -# CONFIG_DEBUG_INFO_DWARF_TOOLCHAIN_DEFAULT is not set -# CONFIG_DEBUG_INFO_DWARF4 is not set -# CONFIG_DEBUG_INFO_DWARF5 is not set -CONFIG_FRAME_WARN=2048 -# CONFIG_STRIP_ASM_SYMS is not set -# CONFIG_READABLE_ASM is not set -# CONFIG_HEADERS_INSTALL is not set -# CONFIG_DEBUG_SECTION_MISMATCH is not set -CONFIG_SECTION_MISMATCH_WARN_ONLY=y -CONFIG_ARCH_WANT_FRAME_POINTERS=y -CONFIG_FRAME_POINTER=y -# CONFIG_VMLINUX_MAP is not set -# CONFIG_DEBUG_FORCE_WEAK_PER_CPU is not set -# end of Compile-time checks and compiler options - -# -# Generic Kernel Debugging Instruments -# -# CONFIG_MAGIC_SYSRQ is not set -CONFIG_DEBUG_FS=y -CONFIG_DEBUG_FS_ALLOW_ALL=y -# CONFIG_DEBUG_FS_DISALLOW_MOUNT is not set -# CONFIG_DEBUG_FS_ALLOW_NONE is not set -CONFIG_HAVE_ARCH_KGDB=y -CONFIG_HAVE_ARCH_KGDB_QXFER_PKT=y -# CONFIG_KGDB is not set -CONFIG_ARCH_HAS_UBSAN_SANITIZE_ALL=y -# CONFIG_UBSAN is not set -CONFIG_HAVE_KCSAN_COMPILER=y -# end of Generic Kernel Debugging Instruments - -# -# Networking Debugging -# -# CONFIG_NET_DEV_REFCNT_TRACKER is not set -# CONFIG_NET_NS_REFCNT_TRACKER is not set -# CONFIG_DEBUG_NET is not set -# end of Networking Debugging - -# -# Memory Debugging -# -# CONFIG_PAGE_EXTENSION is not set -CONFIG_DEBUG_PAGEALLOC=y -# CONFIG_DEBUG_PAGEALLOC_ENABLE_DEFAULT is not set -CONFIG_SLUB_DEBUG=y -# CONFIG_SLUB_DEBUG_ON is not set -# CONFIG_PAGE_OWNER is not set -# CONFIG_PAGE_TABLE_CHECK is not set -# CONFIG_PAGE_POISONING is not set -# CONFIG_DEBUG_RODATA_TEST is not set -CONFIG_ARCH_HAS_DEBUG_WX=y -# CONFIG_DEBUG_WX is not set -CONFIG_GENERIC_PTDUMP=y -# CONFIG_PTDUMP_DEBUGFS is not set -# CONFIG_DEBUG_OBJECTS is not set -# CONFIG_SHRINKER_DEBUG is not set -CONFIG_HAVE_DEBUG_KMEMLEAK=y -# CONFIG_DEBUG_KMEMLEAK is not set -# CONFIG_DEBUG_STACK_USAGE is not set -CONFIG_SCHED_STACK_END_CHECK=y -CONFIG_ARCH_HAS_DEBUG_VM_PGTABLE=y -CONFIG_DEBUG_VM_IRQSOFF=y -CONFIG_DEBUG_VM=y -# CONFIG_DEBUG_VM_MAPLE_TREE is not set -# CONFIG_DEBUG_VM_RB is not set -CONFIG_DEBUG_VM_PGFLAGS=y -CONFIG_DEBUG_VM_PGTABLE=y -CONFIG_ARCH_HAS_DEBUG_VIRTUAL=y -# CONFIG_DEBUG_VIRTUAL is not set -CONFIG_DEBUG_MEMORY_INIT=y -CONFIG_DEBUG_PER_CPU_MAPS=y -CONFIG_HAVE_ARCH_KASAN=y -CONFIG_HAVE_ARCH_KASAN_VMALLOC=y -CONFIG_CC_HAS_KASAN_GENERIC=y -CONFIG_CC_HAS_WORKING_NOSANITIZE_ADDRESS=y -# CONFIG_KASAN is not set -CONFIG_HAVE_ARCH_KFENCE=y -# CONFIG_KFENCE is not set -# end of Memory Debugging - -# CONFIG_DEBUG_SHIRQ is not set - -# -# Debug Oops, Lockups and Hangs -# -# CONFIG_PANIC_ON_OOPS is not set -CONFIG_PANIC_ON_OOPS_VALUE=0 -CONFIG_PANIC_TIMEOUT=0 -CONFIG_LOCKUP_DETECTOR=y -CONFIG_SOFTLOCKUP_DETECTOR=y -# CONFIG_BOOTPARAM_SOFTLOCKUP_PANIC is not set -CONFIG_DETECT_HUNG_TASK=y -CONFIG_DEFAULT_HUNG_TASK_TIMEOUT=120 -# CONFIG_BOOTPARAM_HUNG_TASK_PANIC is not set -CONFIG_WQ_WATCHDOG=y -# CONFIG_TEST_LOCKUP is not set -# end of Debug Oops, Lockups and Hangs - -# -# Scheduler Debugging -# -CONFIG_SCHED_DEBUG=y -# CONFIG_SCHEDSTATS is not set -# end of Scheduler Debugging - -CONFIG_DEBUG_TIMEKEEPING=y - -# -# Lock Debugging (spinlocks, mutexes, etc...) -# -CONFIG_LOCK_DEBUGGING_SUPPORT=y -# CONFIG_PROVE_LOCKING is not set -# CONFIG_LOCK_STAT is not set -CONFIG_DEBUG_RT_MUTEXES=y -CONFIG_DEBUG_SPINLOCK=y -CONFIG_DEBUG_MUTEXES=y -# CONFIG_DEBUG_WW_MUTEX_SLOWPATH is not set -CONFIG_DEBUG_RWSEMS=y -# CONFIG_DEBUG_LOCK_ALLOC is not set -CONFIG_DEBUG_ATOMIC_SLEEP=y -# CONFIG_DEBUG_LOCKING_API_SELFTESTS is not set -# CONFIG_LOCK_TORTURE_TEST is not set -# CONFIG_WW_MUTEX_SELFTEST is not set -# CONFIG_SCF_TORTURE_TEST is not set -# CONFIG_CSD_LOCK_WAIT_DEBUG is not set -# end of Lock Debugging (spinlocks, mutexes, etc...) - -# CONFIG_DEBUG_IRQFLAGS is not set -CONFIG_STACKTRACE=y -# CONFIG_WARN_ALL_UNSEEDED_RANDOM is not set -# CONFIG_DEBUG_KOBJECT is not set - -# -# Debug kernel data structures -# -CONFIG_DEBUG_LIST=y -CONFIG_DEBUG_PLIST=y -CONFIG_DEBUG_SG=y -# CONFIG_DEBUG_NOTIFIERS is not set -# CONFIG_BUG_ON_DATA_CORRUPTION is not set -# CONFIG_DEBUG_MAPLE_TREE is not set -# end of Debug kernel data structures - -# CONFIG_DEBUG_CREDENTIALS is not set - -# -# RCU Debugging -# -# CONFIG_RCU_SCALE_TEST is not set -# CONFIG_RCU_TORTURE_TEST is not set -# CONFIG_RCU_REF_SCALE_TEST is not set -CONFIG_RCU_CPU_STALL_TIMEOUT=21 -CONFIG_RCU_EXP_CPU_STALL_TIMEOUT=0 -# CONFIG_RCU_TRACE is not set -CONFIG_RCU_EQS_DEBUG=y -# end of RCU Debugging - -# CONFIG_DEBUG_WQ_FORCE_RR_CPU is not set -# CONFIG_CPU_HOTPLUG_STATE_CONTROL is not set -# CONFIG_LATENCYTOP is not set -CONFIG_HAVE_RETHOOK=y -CONFIG_HAVE_FUNCTION_TRACER=y -CONFIG_HAVE_FUNCTION_GRAPH_TRACER=y -CONFIG_HAVE_DYNAMIC_FTRACE=y -CONFIG_HAVE_DYNAMIC_FTRACE_WITH_REGS=y -CONFIG_HAVE_FTRACE_MCOUNT_RECORD=y -CONFIG_HAVE_SYSCALL_TRACEPOINTS=y -CONFIG_TRACING_SUPPORT=y -# CONFIG_FTRACE is not set -# CONFIG_SAMPLES is not set -# CONFIG_STRICT_DEVMEM is not set - -# -# riscv Debugging -# -# end of riscv Debugging - -# -# Kernel Testing and Coverage -# -# CONFIG_KUNIT is not set -# CONFIG_NOTIFIER_ERROR_INJECTION is not set -# CONFIG_FAULT_INJECTION is not set -CONFIG_ARCH_HAS_KCOV=y -CONFIG_CC_HAS_SANCOV_TRACE_PC=y -# CONFIG_KCOV is not set -# CONFIG_RUNTIME_TESTING_MENU is not set -CONFIG_ARCH_USE_MEMTEST=y -CONFIG_MEMTEST=y -# end of Kernel Testing and Coverage - -# -# Rust hacking -# -# end of Rust hacking -# end of Kernel hacking diff --git a/patches/linux/linux-6.2.y/dts/mpfs-beaglev-fire-fabric.dtsi b/patches/linux/linux-6.2.y/dts/mpfs-beaglev-fire-fabric.dtsi deleted file mode 100644 index 1069134..0000000 --- a/patches/linux/linux-6.2.y/dts/mpfs-beaglev-fire-fabric.dtsi +++ /dev/null @@ -1,71 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/ { - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs-icicle-kit", - "microchip,mpfs"; - - core_pwm0: pwm@40000000 { - compatible = "microchip,corepwm-rtl-v4"; - reg = <0x0 0x40000000 0x0 0xF0>; - microchip,sync-update-mask = /bits/ 32 <0>; - #pwm-cells = <3>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - status = "disabled"; - }; - - i2c2: i2c@40000200 { - compatible = "microchip,corei2c-rtl-v7"; - reg = <0x0 0x40000200 0x0 0x100>; - #address-cells = <1>; - #size-cells = <0>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - interrupt-parent = <&plic>; - interrupts = <122>; - clock-frequency = <100000>; - status = "disabled"; - }; - - pcie: pcie@3000000000 { - compatible = "microchip,pcie-host-1.0"; - #address-cells = <0x3>; - #interrupt-cells = <0x1>; - #size-cells = <0x2>; - device_type = "pci"; - reg = <0x30 0x0 0x0 0x8000000>, <0x0 0x43000000 0x0 0x10000>; - reg-names = "cfg", "apb"; - bus-range = <0x0 0x7f>; - interrupt-parent = <&plic>; - interrupts = <119>; - interrupt-map = <0 0 0 1 &pcie_intc 0>, - <0 0 0 2 &pcie_intc 1>, - <0 0 0 3 &pcie_intc 2>, - <0 0 0 4 &pcie_intc 3>; - interrupt-map-mask = <0 0 0 7>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT1>, <&ccc_nw CLK_CCC_PLL0_OUT3>; - clock-names = "fic1", "fic3"; - ranges = <0x3000000 0x0 0x8000000 0x30 0x8000000 0x0 0x80000000>; - dma-ranges = <0x02000000 0x0 0x00000000 0x0 0x00000000 0x1 0x00000000>; - msi-parent = <&pcie>; - msi-controller; - status = "disabled"; - pcie_intc: interrupt-controller { - #address-cells = <0>; - #interrupt-cells = <1>; - interrupt-controller; - }; - }; - - refclk_ccc: cccrefclk { - compatible = "fixed-clock"; - #clock-cells = <0>; - }; -}; - -&ccc_nw { - clocks = <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, - <&refclk_ccc>, <&refclk_ccc>; - clock-names = "pll0_ref0", "pll0_ref1", "pll1_ref0", "pll1_ref1", - "dll0_ref", "dll1_ref"; - status = "okay"; -}; diff --git a/patches/linux/linux-6.2.y/dts/mpfs-beaglev-fire.dts b/patches/linux/linux-6.2.y/dts/mpfs-beaglev-fire.dts deleted file mode 100644 index c811d50..0000000 --- a/patches/linux/linux-6.2.y/dts/mpfs-beaglev-fire.dts +++ /dev/null @@ -1,323 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/dts-v1/; - -#include "mpfs.dtsi" -#include "mpfs-beaglev-fire-fabric.dtsi" -#include -#include - -/* Clock frequency (in Hz) of the rtcclk */ -#define RTCCLK_FREQ 1000000 - -/ { - #address-cells = <2>; - #size-cells = <2>; - model = "BeagleBoard BeagleV-Fire"; - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs"; - - aliases { - mmc0 = &mmc; - ethernet0 = &mac1; - serial0 = &mmuart0; - serial1 = &mmuart1; - serial2 = &mmuart2; - serial3 = &mmuart3; - serial4 = &mmuart4; - }; - - chosen { - stdout-path = "serial0:115200n8"; - }; - - cpus { - timebase-frequency = ; - }; - - ddrc_cache_lo: memory@80000000 { - device_type = "memory"; - reg = <0x0 0x80000000 0x0 0x40000000>; - status = "okay"; - }; - - ddrc_cache_hi: memory@1040000000 { - device_type = "memory"; - reg = <0x10 0x40000000 0x0 0x40000000>; - status = "okay"; - }; - - reserved-memory { - #address-cells = <2>; - #size-cells = <2>; - ranges; - - hss_payload: region@BFC00000 { - reg = <0x0 0xBFC00000 0x0 0x400000>; - no-map; - }; - }; - - imx219_vana: fixedregulator@0 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vana"; - regulator-min-microvolt = <2800000>; - regulator-max-microvolt = <2800000>; - }; - imx219_vdig: fixedregulator@1 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vdig"; - regulator-min-microvolt = <1800000>; - regulator-max-microvolt = <1800000>; - }; - imx219_vddl: fixedregulator@2 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vddl"; - regulator-min-microvolt = <1200000>; - regulator-max-microvolt = <1200000>; - }; - - imx219_clk: camera-clk { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <24000000>; - }; -}; - -&gpio0 { - ngpios=<14>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", "", "", "SD_CARD_CS", "USER_BUTTON"; - status = "okay"; - - sd_card_cs { - gpio-hog; - gpios = <12 12>; - output_high; - line-name = "SD_CARD_CS"; - }; - - user_button { - gpio-hog; - gpios = <13 13>; - input; - line-name = "USER_BUTTON"; - }; -}; - -&gpio1 { - ngpios=<24>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", - "", "", "", "", "", "", "", "", "", "", - "ADC_IRQn", "", "", "USB_OCn"; - status = "okay"; - - adc_irqn { - gpio-hog; - gpios = <20 20>; - input; - line-name = "ADC_IRQn"; - }; - - user_button { - gpio-hog; - gpios = <23 23>; - input; - line-name = "USB_OCn"; - }; - -}; - -&gpio2 { - interrupts = <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>; - gpio-line-names = "P8_PIN3_USER_LED_0", "P8_PIN4_USER_LED_1", "P8_PIN5_USER_LED_2", - "P8_PIN6_USER_LED_3", "P8_PIN7_USER_LED_4", "P8_PIN8_USER_LED_5", - "P8_PIN9_USER_LED_6", "P8_PIN10_USER_LED_7", "P8_PIN11_USER_LED_8", - "P8_PIN12_USER_LED_9", "P8_PIN13_USER_LED_10", "P8_PIN14_USER_LED_11", - "P8_PIN15", "P8_PIN16", "P8_PIN17", "P8_PIN18", "P8_PIN19", - "P8_PIN20", "P8_PIN21", "P8_PIN22", "P8_PIN23", "P8_PIN24", - "P8_PIN25", "P8_PIN26", "P8_PIN27", "P8_PIN28", "P8_PIN29", - "P8_PIN30", - "M2_W_DISABLE1", "M2_W_DISABLE2", - "VIO_ENABLE", "SD_DET"; - status = "okay"; - - vio_enable { - gpio-hog; - gpios = <30 30>; - output_high; - line-name = "VIO_ENABLE"; - }; - - sd_det { - gpio-hog; - gpios = <31 31>; - input; - line-name = "SD_DET"; - }; -}; - -&i2c0 { - status = "okay"; -}; - -&i2c1 { - status = "okay"; - eeprom: eeprom@50 { - compatible = "at,24c32"; - reg = <0x50>; - }; - - imx219: sensor@10 { - compatible = "sony,imx219"; - reg = <0x10>; - clocks = <&imx219_clk>; - VANA-supply = <&imx219_vana>; /* 2.8v */ - VDIG-supply = <&imx219_vdig>; /* 1.8v */ - VDDL-supply = <&imx219_vddl>; /* 1.2v */ - - port { - imx219_0: endpoint { -// remote-endpoint = <&csi1_ep>; - data-lanes = <1 2>; - clock-noncontinuous; - link-frequencies = /bits/ 64 <456000000>; - }; - }; - }; -}; - -&mac0 { - phy-mode = "sgmii"; - phy-handle = <&phy0>; - status = "okay"; - - phy0: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mac1 { - phy-mode = "sgmii"; - phy-handle = <&phy1>; - status = "okay"; - - phy1: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mbox { - status = "okay"; -}; - -//&mmc { -// status = "okay"; -// bus-width = <8>; -// disable-wp; -// cap-mmc-highspeed; -// mmc-ddr-1_8v; -// mmc-hs200-1_8v; -//}; - -&mmc { - //dma-noncoherent; - bus-width = <4>; - disable-wp; - cap-sd-highspeed; - cap-mmc-highspeed; - mmc-ddr-1_8v; - mmc-hs200-1_8v; - sd-uhs-sdr12; - sd-uhs-sdr25; - sd-uhs-sdr50; - sd-uhs-sdr104; - status = "okay"; -}; - - -&mmuart0 { - status = "okay"; -}; - -&mmuart1 { - status = "okay"; -}; - -//&mmuart2 { -// status = "okay"; -//}; - -//&mmuart3 //{ -// statu//s = "okay"; -//};// -// -//&mmuart4 { -// status = "okay"; -//}; - -//&pcie { -// status = "okay"; -//}; - -&qspi { - status = "okay"; - cs-gpios = <&gpio1 17 GPIO_ACTIVE_LOW>, <&gpio0 12 GPIO_ACTIVE_LOW>; - num-cs = <2>; - - - mcp3464: mcp3464@0 { - compatible = "microchip,mcp3464r"; - reg = <0>; /* CE0 */ - spi-cpol; - spi-cpha; - spi-max-frequency = <15000000>; - status = "okay"; - microchip,hw-device-address = <1>; - }; - - mmc-slot@1 { - compatible = "mmc-spi-slot"; - reg = <1>; - gpios = <&gpio2 31 1>; - voltage-ranges = <3300 3300>; - spi-max-frequency = <15000000>; - disable-wp; - }; -}; - -&refclk { - clock-frequency = <125000000>; -}; - -&refclk_ccc { - clock-frequency = <50000000>; -}; - -&rtc { - status = "okay"; -}; - -&spi0 { - status = "okay"; -}; - -&spi1 { - status = "okay"; -}; - -&syscontroller { - status = "okay"; -}; - -&usb { - //dma-noncoherent; - status = "okay"; - dr_mode = "otg"; -}; diff --git a/patches/linux/linux-6.3.y/Makefile b/patches/linux/linux-6.3.y/Makefile deleted file mode 100644 index 65af281..0000000 --- a/patches/linux/linux-6.3.y/Makefile +++ /dev/null @@ -1,8 +0,0 @@ -# SPDX-License-Identifier: GPL-2.0 -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-icicle-kit.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-m100pfsevp.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-polarberry.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-sev-kit.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-tysom-m.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-beaglev-fire.dtb -obj-$(CONFIG_BUILTIN_DTB) += $(addsuffix .o, $(dtb-y)) diff --git a/patches/linux/linux-6.3.y/defconfig b/patches/linux/linux-6.3.y/defconfig deleted file mode 100644 index 23b3d52..0000000 --- a/patches/linux/linux-6.3.y/defconfig +++ /dev/null @@ -1,5510 +0,0 @@ -# -# Automatically generated file; DO NOT EDIT. -# Linux/riscv 6.3.13 Kernel Configuration -# -CONFIG_CC_VERSION_TEXT="riscv64-linux-gcc (GCC) 11.4.0" -CONFIG_CC_IS_GCC=y -CONFIG_GCC_VERSION=110400 -CONFIG_CLANG_VERSION=0 -CONFIG_AS_IS_GNU=y -CONFIG_AS_VERSION=24000 -CONFIG_LD_IS_BFD=y -CONFIG_LD_VERSION=24000 -CONFIG_LLD_VERSION=0 -CONFIG_CC_HAS_ASM_GOTO_OUTPUT=y -CONFIG_CC_HAS_ASM_GOTO_TIED_OUTPUT=y -CONFIG_CC_HAS_ASM_INLINE=y -CONFIG_CC_HAS_NO_PROFILE_FN_ATTR=y -CONFIG_PAHOLE_VERSION=0 -CONFIG_IRQ_WORK=y -CONFIG_BUILDTIME_TABLE_SORT=y -CONFIG_THREAD_INFO_IN_TASK=y - -# -# General setup -# -CONFIG_INIT_ENV_ARG_LIMIT=32 -# CONFIG_COMPILE_TEST is not set -# CONFIG_WERROR is not set -CONFIG_LOCALVERSION="" -CONFIG_LOCALVERSION_AUTO=y -CONFIG_BUILD_SALT="" -CONFIG_DEFAULT_INIT="" -CONFIG_DEFAULT_HOSTNAME="(none)" -CONFIG_SYSVIPC=y -CONFIG_SYSVIPC_SYSCTL=y -CONFIG_SYSVIPC_COMPAT=y -CONFIG_POSIX_MQUEUE=y -CONFIG_POSIX_MQUEUE_SYSCTL=y -# CONFIG_WATCH_QUEUE is not set -CONFIG_CROSS_MEMORY_ATTACH=y -# CONFIG_USELIB is not set -CONFIG_AUDIT=y -CONFIG_HAVE_ARCH_AUDITSYSCALL=y -CONFIG_AUDITSYSCALL=y - -# -# IRQ subsystem -# -CONFIG_GENERIC_IRQ_SHOW=y -CONFIG_GENERIC_IRQ_SHOW_LEVEL=y -CONFIG_GENERIC_IRQ_EFFECTIVE_AFF_MASK=y -CONFIG_GENERIC_IRQ_MIGRATION=y -CONFIG_HARDIRQS_SW_RESEND=y -CONFIG_GENERIC_IRQ_CHIP=y -CONFIG_IRQ_DOMAIN=y -CONFIG_IRQ_DOMAIN_HIERARCHY=y -CONFIG_GENERIC_MSI_IRQ=y -CONFIG_IRQ_FORCED_THREADING=y -CONFIG_SPARSE_IRQ=y -# CONFIG_GENERIC_IRQ_DEBUGFS is not set -# end of IRQ subsystem - -CONFIG_GENERIC_IRQ_MULTI_HANDLER=y -CONFIG_GENERIC_TIME_VSYSCALL=y -CONFIG_GENERIC_CLOCKEVENTS=y -CONFIG_ARCH_HAS_TICK_BROADCAST=y -CONFIG_GENERIC_CLOCKEVENTS_BROADCAST=y -CONFIG_HAVE_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_CONTEXT_TRACKING=y -CONFIG_CONTEXT_TRACKING_IDLE=y - -# -# Timers subsystem -# -CONFIG_TICK_ONESHOT=y -CONFIG_NO_HZ_COMMON=y -# CONFIG_HZ_PERIODIC is not set -CONFIG_NO_HZ_IDLE=y -# CONFIG_NO_HZ_FULL is not set -# CONFIG_NO_HZ is not set -CONFIG_HIGH_RES_TIMERS=y -# end of Timers subsystem - -CONFIG_BPF=y -CONFIG_HAVE_EBPF_JIT=y - -# -# BPF subsystem -# -CONFIG_BPF_SYSCALL=y -# CONFIG_BPF_JIT is not set -CONFIG_BPF_UNPRIV_DEFAULT_OFF=y -# CONFIG_BPF_PRELOAD is not set -# end of BPF subsystem - -CONFIG_PREEMPT_NONE_BUILD=y -CONFIG_PREEMPT_NONE=y -# CONFIG_PREEMPT_VOLUNTARY is not set -# CONFIG_PREEMPT is not set -CONFIG_PREEMPT_COUNT=y - -# -# CPU/Task time and stats accounting -# -CONFIG_TICK_CPU_ACCOUNTING=y -# CONFIG_VIRT_CPU_ACCOUNTING_GEN is not set -# CONFIG_IRQ_TIME_ACCOUNTING is not set -# CONFIG_BSD_PROCESS_ACCT is not set -# CONFIG_TASKSTATS is not set -# CONFIG_PSI is not set -# end of CPU/Task time and stats accounting - -CONFIG_CPU_ISOLATION=y - -# -# RCU Subsystem -# -CONFIG_TREE_RCU=y -# CONFIG_RCU_EXPERT is not set -CONFIG_SRCU=y -CONFIG_TREE_SRCU=y -CONFIG_TASKS_RCU_GENERIC=y -CONFIG_TASKS_TRACE_RCU=y -CONFIG_RCU_STALL_COMMON=y -CONFIG_RCU_NEED_SEGCBLIST=y -# end of RCU Subsystem - -CONFIG_IKCONFIG=y -CONFIG_IKCONFIG_PROC=y -# CONFIG_IKHEADERS is not set -CONFIG_LOG_BUF_SHIFT=17 -CONFIG_LOG_CPU_MAX_BUF_SHIFT=12 -CONFIG_PRINTK_SAFE_LOG_BUF_SHIFT=13 -# CONFIG_PRINTK_INDEX is not set -CONFIG_GENERIC_SCHED_CLOCK=y - -# -# Scheduler features -# -# end of Scheduler features - -CONFIG_CC_HAS_INT128=y -CONFIG_CC_IMPLICIT_FALLTHROUGH="-Wimplicit-fallthrough=5" -CONFIG_GCC11_NO_ARRAY_BOUNDS=y -CONFIG_CC_NO_ARRAY_BOUNDS=y -CONFIG_ARCH_SUPPORTS_INT128=y -CONFIG_CGROUPS=y -CONFIG_PAGE_COUNTER=y -# CONFIG_CGROUP_FAVOR_DYNMODS is not set -CONFIG_MEMCG=y -CONFIG_MEMCG_KMEM=y -# CONFIG_BLK_CGROUP is not set -CONFIG_CGROUP_SCHED=y -CONFIG_FAIR_GROUP_SCHED=y -CONFIG_CFS_BANDWIDTH=y -CONFIG_RT_GROUP_SCHED=y -CONFIG_SCHED_MM_CID=y -CONFIG_CGROUP_PIDS=y -# CONFIG_CGROUP_RDMA is not set -CONFIG_CGROUP_FREEZER=y -CONFIG_CGROUP_HUGETLB=y -CONFIG_CPUSETS=y -CONFIG_PROC_PID_CPUSET=y -CONFIG_CGROUP_DEVICE=y -CONFIG_CGROUP_CPUACCT=y -CONFIG_CGROUP_PERF=y -CONFIG_CGROUP_BPF=y -# CONFIG_CGROUP_MISC is not set -# CONFIG_CGROUP_DEBUG is not set -CONFIG_SOCK_CGROUP_DATA=y -CONFIG_NAMESPACES=y -CONFIG_UTS_NS=y -CONFIG_TIME_NS=y -CONFIG_IPC_NS=y -CONFIG_USER_NS=y -CONFIG_PID_NS=y -CONFIG_NET_NS=y -CONFIG_CHECKPOINT_RESTORE=y -# CONFIG_SCHED_AUTOGROUP is not set -# CONFIG_SYSFS_DEPRECATED is not set -# CONFIG_RELAY is not set -CONFIG_BLK_DEV_INITRD=y -CONFIG_INITRAMFS_SOURCE="" -CONFIG_RD_GZIP=y -CONFIG_RD_BZIP2=y -CONFIG_RD_LZMA=y -CONFIG_RD_XZ=y -CONFIG_RD_LZO=y -CONFIG_RD_LZ4=y -CONFIG_RD_ZSTD=y -# CONFIG_BOOT_CONFIG is not set -CONFIG_INITRAMFS_PRESERVE_MTIME=y -CONFIG_CC_OPTIMIZE_FOR_PERFORMANCE=y -# CONFIG_CC_OPTIMIZE_FOR_SIZE is not set -CONFIG_LD_ORPHAN_WARN=y -CONFIG_LD_ORPHAN_WARN_LEVEL="warn" -CONFIG_SYSCTL=y -CONFIG_SYSCTL_EXCEPTION_TRACE=y -CONFIG_EXPERT=y -CONFIG_MULTIUSER=y -# CONFIG_SGETMASK_SYSCALL is not set -# CONFIG_SYSFS_SYSCALL is not set -CONFIG_FHANDLE=y -CONFIG_POSIX_TIMERS=y -CONFIG_PRINTK=y -CONFIG_BUG=y -CONFIG_ELF_CORE=y -CONFIG_BASE_FULL=y -CONFIG_FUTEX=y -CONFIG_FUTEX_PI=y -CONFIG_EPOLL=y -CONFIG_SIGNALFD=y -CONFIG_TIMERFD=y -CONFIG_EVENTFD=y -CONFIG_SHMEM=y -CONFIG_AIO=y -CONFIG_IO_URING=y -CONFIG_ADVISE_SYSCALLS=y -CONFIG_MEMBARRIER=y -CONFIG_KALLSYMS=y -# CONFIG_KALLSYMS_SELFTEST is not set -# CONFIG_KALLSYMS_ALL is not set -CONFIG_KALLSYMS_BASE_RELATIVE=y -CONFIG_KCMP=y -CONFIG_RSEQ=y -# CONFIG_DEBUG_RSEQ is not set -# CONFIG_EMBEDDED is not set -CONFIG_HAVE_PERF_EVENTS=y -# CONFIG_PC104 is not set - -# -# Kernel Performance Events And Counters -# -CONFIG_PERF_EVENTS=y -# CONFIG_DEBUG_PERF_USE_VMALLOC is not set -# end of Kernel Performance Events And Counters - -CONFIG_PROFILING=y -# end of General setup - -CONFIG_64BIT=y -CONFIG_RISCV=y -CONFIG_ARCH_MMAP_RND_BITS_MIN=18 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MIN=8 -CONFIG_ARCH_MMAP_RND_BITS_MAX=24 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MAX=17 -CONFIG_RISCV_SBI=y -CONFIG_MMU=y -CONFIG_PAGE_OFFSET=0xff60000000000000 -CONFIG_ARCH_FLATMEM_ENABLE=y -CONFIG_ARCH_SPARSEMEM_ENABLE=y -CONFIG_ARCH_SELECT_MEMORY_MODEL=y -CONFIG_ARCH_SUPPORTS_UPROBES=y -CONFIG_STACKTRACE_SUPPORT=y -CONFIG_GENERIC_BUG=y -CONFIG_GENERIC_BUG_RELATIVE_POINTERS=y -CONFIG_GENERIC_CALIBRATE_DELAY=y -CONFIG_GENERIC_CSUM=y -CONFIG_GENERIC_HWEIGHT=y -CONFIG_FIX_EARLYCON_MEM=y -CONFIG_PGTABLE_LEVELS=5 -CONFIG_LOCKDEP_SUPPORT=y -CONFIG_RISCV_DMA_NONCOHERENT=y -CONFIG_AS_HAS_INSN=y - -# -# SoC selection -# -CONFIG_ARCH_MICROCHIP_POLARFIRE=y -CONFIG_SOC_MICROCHIP_POLARFIRE=y -CONFIG_ARCH_RENESAS=y -CONFIG_ARCH_SIFIVE=y -CONFIG_SOC_SIFIVE=y -CONFIG_ARCH_STARFIVE=y -CONFIG_SOC_STARFIVE=y -CONFIG_ARCH_SUNXI=y -CONFIG_ARCH_VIRT=y -CONFIG_SOC_VIRT=y -# end of SoC selection - -# -# CPU errata selection -# -CONFIG_ERRATA_SIFIVE=y -CONFIG_ERRATA_SIFIVE_CIP_453=y -CONFIG_ERRATA_SIFIVE_CIP_1200=y -CONFIG_ERRATA_THEAD=y -CONFIG_ERRATA_THEAD_PBMT=y -CONFIG_ERRATA_THEAD_CMO=y -CONFIG_ERRATA_THEAD_PMU=y -# end of CPU errata selection - -# -# Platform type -# -# CONFIG_NONPORTABLE is not set -CONFIG_ARCH_RV64I=y -# CONFIG_CMODEL_MEDLOW is not set -CONFIG_CMODEL_MEDANY=y -CONFIG_MODULE_SECTIONS=y -CONFIG_SMP=y -CONFIG_NR_CPUS=64 -CONFIG_HOTPLUG_CPU=y -CONFIG_TUNE_GENERIC=y -# CONFIG_NUMA is not set -CONFIG_RISCV_ALTERNATIVE=y -CONFIG_RISCV_ALTERNATIVE_EARLY=y -CONFIG_RISCV_ISA_C=y -CONFIG_RISCV_ISA_SVPBMT=y -CONFIG_TOOLCHAIN_HAS_ZBB=y -CONFIG_RISCV_ISA_ZBB=y -CONFIG_RISCV_ISA_ZICBOM=y -CONFIG_TOOLCHAIN_HAS_ZIHINTPAUSE=y -CONFIG_TOOLCHAIN_NEEDS_EXPLICIT_ZICSR_ZIFENCEI=y -CONFIG_FPU=y -# end of Platform type - -# -# Kernel features -# -# CONFIG_HZ_100 is not set -CONFIG_HZ_250=y -# CONFIG_HZ_300 is not set -# CONFIG_HZ_1000 is not set -CONFIG_HZ=250 -CONFIG_SCHED_HRTICK=y -# CONFIG_RISCV_SBI_V01 is not set -# CONFIG_RISCV_BOOT_SPINWAIT is not set -# CONFIG_KEXEC is not set -# CONFIG_KEXEC_FILE is not set -# CONFIG_CRASH_DUMP is not set -CONFIG_COMPAT=y -# end of Kernel features - -# -# Boot options -# -CONFIG_CMDLINE="" -CONFIG_EFI_STUB=y -CONFIG_EFI=y -CONFIG_CC_HAVE_STACKPROTECTOR_TLS=y -CONFIG_STACKPROTECTOR_PER_TASK=y -# end of Boot options - -CONFIG_PORTABLE=y - -# -# Power management options -# -CONFIG_PM=y -# CONFIG_PM_DEBUG is not set -CONFIG_PM_CLK=y -CONFIG_PM_GENERIC_DOMAINS=y -# CONFIG_WQ_POWER_EFFICIENT_DEFAULT is not set -CONFIG_PM_GENERIC_DOMAINS_OF=y -CONFIG_CPU_PM=y -# end of Power management options - -# -# CPU Power Management -# - -# -# CPU Idle -# -CONFIG_CPU_IDLE=y -CONFIG_CPU_IDLE_MULTIPLE_DRIVERS=y -# CONFIG_CPU_IDLE_GOV_LADDER is not set -CONFIG_CPU_IDLE_GOV_MENU=y -# CONFIG_CPU_IDLE_GOV_TEO is not set -CONFIG_DT_IDLE_STATES=y -CONFIG_DT_IDLE_GENPD=y - -# -# RISC-V CPU Idle Drivers -# -CONFIG_RISCV_SBI_CPUIDLE=y -# end of RISC-V CPU Idle Drivers -# end of CPU Idle - -# -# CPU Frequency scaling -# -# CONFIG_CPU_FREQ is not set -# end of CPU Frequency scaling -# end of CPU Power Management - -CONFIG_HAVE_KVM_EVENTFD=y -CONFIG_KVM_MMIO=y -CONFIG_KVM_GENERIC_DIRTYLOG_READ_PROTECT=y -CONFIG_HAVE_KVM_VCPU_ASYNC_IOCTL=y -CONFIG_KVM_XFER_TO_GUEST_WORK=y -CONFIG_KVM_GENERIC_HARDWARE_ENABLING=y -CONFIG_VIRTUALIZATION=y -CONFIG_KVM=m - -# -# General architecture-dependent options -# -# CONFIG_KPROBES is not set -CONFIG_JUMP_LABEL=y -# CONFIG_STATIC_KEYS_SELFTEST is not set -CONFIG_HAVE_64BIT_ALIGNED_ACCESS=y -CONFIG_HAVE_KPROBES=y -CONFIG_HAVE_KRETPROBES=y -CONFIG_HAVE_KPROBES_ON_FTRACE=y -CONFIG_HAVE_FUNCTION_ERROR_INJECTION=y -CONFIG_TRACE_IRQFLAGS_SUPPORT=y -CONFIG_HAVE_ARCH_TRACEHOOK=y -CONFIG_HAVE_DMA_CONTIGUOUS=y -CONFIG_GENERIC_SMP_IDLE_THREAD=y -CONFIG_GENERIC_IDLE_POLL_SETUP=y -CONFIG_ARCH_HAS_FORTIFY_SOURCE=y -CONFIG_ARCH_HAS_SET_MEMORY=y -CONFIG_ARCH_HAS_SET_DIRECT_MAP=y -CONFIG_HAVE_ARCH_THREAD_STRUCT_WHITELIST=y -CONFIG_HAVE_ASM_MODVERSIONS=y -CONFIG_HAVE_REGS_AND_STACK_ACCESS_API=y -CONFIG_HAVE_RSEQ=y -CONFIG_HAVE_FUNCTION_ARG_ACCESS_API=y -CONFIG_HAVE_PERF_REGS=y -CONFIG_HAVE_PERF_USER_STACK_DUMP=y -CONFIG_HAVE_ARCH_JUMP_LABEL=y -CONFIG_HAVE_ARCH_JUMP_LABEL_RELATIVE=y -CONFIG_HAVE_ARCH_SECCOMP=y -CONFIG_HAVE_ARCH_SECCOMP_FILTER=y -CONFIG_SECCOMP=y -CONFIG_SECCOMP_FILTER=y -# CONFIG_SECCOMP_CACHE_DEBUG is not set -CONFIG_HAVE_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR_STRONG=y -CONFIG_LTO_NONE=y -CONFIG_HAVE_CONTEXT_TRACKING_USER=y -CONFIG_HAVE_VIRT_CPU_ACCOUNTING_GEN=y -CONFIG_HAVE_IRQ_TIME_ACCOUNTING=y -CONFIG_HAVE_MOVE_PUD=y -CONFIG_HAVE_MOVE_PMD=y -CONFIG_HAVE_ARCH_TRANSPARENT_HUGEPAGE=y -CONFIG_HAVE_ARCH_HUGE_VMAP=y -CONFIG_HAVE_ARCH_HUGE_VMALLOC=y -CONFIG_ARCH_WANT_HUGE_PMD_SHARE=y -CONFIG_HAVE_MOD_ARCH_SPECIFIC=y -CONFIG_MODULES_USE_ELF_RELA=y -CONFIG_ARCH_HAS_ELF_RANDOMIZE=y -CONFIG_HAVE_ARCH_MMAP_RND_BITS=y -CONFIG_ARCH_MMAP_RND_BITS=18 -CONFIG_HAVE_ARCH_MMAP_RND_COMPAT_BITS=y -CONFIG_ARCH_MMAP_RND_COMPAT_BITS=8 -CONFIG_PAGE_SIZE_LESS_THAN_64KB=y -CONFIG_PAGE_SIZE_LESS_THAN_256KB=y -CONFIG_ARCH_WANT_DEFAULT_TOPDOWN_MMAP_LAYOUT=y -CONFIG_CLONE_BACKWARDS=y -CONFIG_COMPAT_32BIT_TIME=y -CONFIG_HAVE_ARCH_VMAP_STACK=y -CONFIG_VMAP_STACK=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX_DEFAULT=y -CONFIG_ARCH_HAS_STRICT_KERNEL_RWX=y -CONFIG_STRICT_KERNEL_RWX=y -CONFIG_ARCH_HAS_STRICT_MODULE_RWX=y -CONFIG_STRICT_MODULE_RWX=y -CONFIG_ARCH_USE_MEMREMAP_PROT=y -# CONFIG_LOCK_EVENT_COUNTS is not set -CONFIG_ARCH_WANT_LD_ORPHAN_WARN=y -CONFIG_ARCH_SUPPORTS_DEBUG_PAGEALLOC=y -CONFIG_ARCH_SUPPORTS_PAGE_TABLE_CHECK=y - -# -# GCOV-based kernel profiling -# -# CONFIG_GCOV_KERNEL is not set -CONFIG_ARCH_HAS_GCOV_PROFILE_ALL=y -# end of GCOV-based kernel profiling - -CONFIG_HAVE_GCC_PLUGINS=y -CONFIG_GCC_PLUGINS=y -# CONFIG_GCC_PLUGIN_LATENT_ENTROPY is not set -CONFIG_FUNCTION_ALIGNMENT=0 -# end of General architecture-dependent options - -CONFIG_RT_MUTEXES=y -CONFIG_BASE_SMALL=0 -CONFIG_MODULES=y -# CONFIG_MODULE_FORCE_LOAD is not set -CONFIG_MODULE_UNLOAD=y -# CONFIG_MODULE_FORCE_UNLOAD is not set -# CONFIG_MODULE_UNLOAD_TAINT_TRACKING is not set -# CONFIG_MODVERSIONS is not set -# CONFIG_MODULE_SRCVERSION_ALL is not set -# CONFIG_MODULE_SIG is not set -CONFIG_MODULE_COMPRESS_NONE=y -# CONFIG_MODULE_COMPRESS_GZIP is not set -# CONFIG_MODULE_COMPRESS_XZ is not set -# CONFIG_MODULE_COMPRESS_ZSTD is not set -# CONFIG_MODULE_ALLOW_MISSING_NAMESPACE_IMPORTS is not set -CONFIG_MODPROBE_PATH="/sbin/modprobe" -# CONFIG_TRIM_UNUSED_KSYMS is not set -CONFIG_MODULES_TREE_LOOKUP=y -CONFIG_BLOCK=y -CONFIG_BLOCK_LEGACY_AUTOLOAD=y -CONFIG_BLK_DEV_BSG_COMMON=y -CONFIG_BLK_ICQ=y -# CONFIG_BLK_DEV_BSGLIB is not set -# CONFIG_BLK_DEV_INTEGRITY is not set -# CONFIG_BLK_DEV_ZONED is not set -# CONFIG_BLK_WBT is not set -CONFIG_BLK_DEBUG_FS=y -# CONFIG_BLK_SED_OPAL is not set -# CONFIG_BLK_INLINE_ENCRYPTION is not set - -# -# Partition Types -# -# CONFIG_PARTITION_ADVANCED is not set -CONFIG_MSDOS_PARTITION=y -CONFIG_EFI_PARTITION=y -# end of Partition Types - -CONFIG_BLK_MQ_PCI=y -CONFIG_BLK_MQ_VIRTIO=y -CONFIG_BLK_PM=y -CONFIG_BLOCK_HOLDER_DEPRECATED=y -CONFIG_BLK_MQ_STACKING=y - -# -# IO Schedulers -# -CONFIG_MQ_IOSCHED_DEADLINE=y -CONFIG_MQ_IOSCHED_KYBER=y -CONFIG_IOSCHED_BFQ=y -# end of IO Schedulers - -CONFIG_PREEMPT_NOTIFIERS=y -CONFIG_ASN1=y -CONFIG_UNINLINE_SPIN_UNLOCK=y -CONFIG_ARCH_SUPPORTS_ATOMIC_RMW=y -CONFIG_MUTEX_SPIN_ON_OWNER=y -CONFIG_RWSEM_SPIN_ON_OWNER=y -CONFIG_LOCK_SPIN_ON_OWNER=y -CONFIG_ARCH_USE_QUEUED_RWLOCKS=y -CONFIG_QUEUED_RWLOCKS=y -CONFIG_ARCH_HAS_MMIOWB=y -CONFIG_MMIOWB=y -CONFIG_ARCH_HAS_NON_OVERLAPPING_ADDRESS_SPACE=y -CONFIG_FREEZER=y - -# -# Executable file formats -# -CONFIG_BINFMT_ELF=y -CONFIG_COMPAT_BINFMT_ELF=y -CONFIG_ELFCORE=y -CONFIG_CORE_DUMP_DEFAULT_ELF_HEADERS=y -CONFIG_BINFMT_SCRIPT=y -CONFIG_ARCH_HAS_BINFMT_FLAT=y -# CONFIG_BINFMT_FLAT is not set -# CONFIG_BINFMT_MISC is not set -CONFIG_COREDUMP=y -# end of Executable file formats - -# -# Memory Management options -# -CONFIG_SWAP=y -# CONFIG_ZSWAP is not set - -# -# SLAB allocator options -# -# CONFIG_SLAB is not set -CONFIG_SLUB=y -# CONFIG_SLOB_DEPRECATED is not set -# CONFIG_SLUB_TINY is not set -CONFIG_SLAB_MERGE_DEFAULT=y -# CONFIG_SLAB_FREELIST_RANDOM is not set -# CONFIG_SLAB_FREELIST_HARDENED is not set -# CONFIG_SLUB_STATS is not set -CONFIG_SLUB_CPU_PARTIAL=y -# end of SLAB allocator options - -# CONFIG_SHUFFLE_PAGE_ALLOCATOR is not set -CONFIG_COMPAT_BRK=y -CONFIG_SELECT_MEMORY_MODEL=y -# CONFIG_FLATMEM_MANUAL is not set -CONFIG_SPARSEMEM_MANUAL=y -CONFIG_SPARSEMEM=y -CONFIG_SPARSEMEM_EXTREME=y -CONFIG_SPARSEMEM_VMEMMAP_ENABLE=y -CONFIG_SPARSEMEM_VMEMMAP=y -CONFIG_SPLIT_PTLOCK_CPUS=4 -CONFIG_ARCH_ENABLE_SPLIT_PMD_PTLOCK=y -CONFIG_MEMORY_BALLOON=y -CONFIG_BALLOON_COMPACTION=y -CONFIG_COMPACTION=y -CONFIG_COMPACT_UNEVICTABLE_DEFAULT=1 -CONFIG_PAGE_REPORTING=y -CONFIG_MIGRATION=y -CONFIG_ARCH_ENABLE_HUGEPAGE_MIGRATION=y -CONFIG_PHYS_ADDR_T_64BIT=y -CONFIG_MMU_NOTIFIER=y -# CONFIG_KSM is not set -CONFIG_DEFAULT_MMAP_MIN_ADDR=4096 -CONFIG_ARCH_WANT_GENERAL_HUGETLB=y -CONFIG_ARCH_WANTS_THP_SWAP=y -# CONFIG_TRANSPARENT_HUGEPAGE is not set -# CONFIG_CMA is not set -CONFIG_GENERIC_EARLY_IOREMAP=y -# CONFIG_DEFERRED_STRUCT_PAGE_INIT is not set -# CONFIG_IDLE_PAGE_TRACKING is not set -CONFIG_ARCH_HAS_CURRENT_STACK_POINTER=y -CONFIG_ZONE_DMA32=y -CONFIG_VM_EVENT_COUNTERS=y -# CONFIG_PERCPU_STATS is not set -# CONFIG_GUP_TEST is not set -CONFIG_ARCH_HAS_PTE_SPECIAL=y -CONFIG_SECRETMEM=y -# CONFIG_ANON_VMA_NAME is not set -# CONFIG_USERFAULTFD is not set -# CONFIG_LRU_GEN is not set -CONFIG_LOCK_MM_AND_FIND_VMA=y - -# -# Data Access Monitoring -# -# CONFIG_DAMON is not set -# end of Data Access Monitoring -# end of Memory Management options - -CONFIG_NET=y -CONFIG_NET_INGRESS=y -CONFIG_NET_EGRESS=y -CONFIG_SKB_EXTENSIONS=y - -# -# Networking options -# -CONFIG_PACKET=y -# CONFIG_PACKET_DIAG is not set -CONFIG_UNIX=y -CONFIG_UNIX_SCM=y -CONFIG_AF_UNIX_OOB=y -# CONFIG_UNIX_DIAG is not set -# CONFIG_TLS is not set -CONFIG_XFRM=y -CONFIG_XFRM_ALGO=m -CONFIG_XFRM_USER=m -# CONFIG_XFRM_INTERFACE is not set -# CONFIG_XFRM_SUB_POLICY is not set -# CONFIG_XFRM_MIGRATE is not set -# CONFIG_XFRM_STATISTICS is not set -CONFIG_XFRM_ESP=m -# CONFIG_NET_KEY is not set -# CONFIG_XDP_SOCKETS is not set -CONFIG_INET=y -CONFIG_IP_MULTICAST=y -CONFIG_IP_ADVANCED_ROUTER=y -# CONFIG_IP_FIB_TRIE_STATS is not set -# CONFIG_IP_MULTIPLE_TABLES is not set -# CONFIG_IP_ROUTE_MULTIPATH is not set -# CONFIG_IP_ROUTE_VERBOSE is not set -CONFIG_IP_PNP=y -CONFIG_IP_PNP_DHCP=y -CONFIG_IP_PNP_BOOTP=y -CONFIG_IP_PNP_RARP=y -# CONFIG_NET_IPIP is not set -# CONFIG_NET_IPGRE_DEMUX is not set -CONFIG_NET_IP_TUNNEL=y -# CONFIG_IP_MROUTE is not set -# CONFIG_SYN_COOKIES is not set -# CONFIG_NET_IPVTI is not set -CONFIG_NET_UDP_TUNNEL=m -# CONFIG_NET_FOU is not set -# CONFIG_NET_FOU_IP_TUNNELS is not set -# CONFIG_INET_AH is not set -CONFIG_INET_ESP=m -# CONFIG_INET_ESP_OFFLOAD is not set -# CONFIG_INET_ESPINTCP is not set -# CONFIG_INET_IPCOMP is not set -CONFIG_INET_TABLE_PERTURB_ORDER=16 -CONFIG_INET_TUNNEL=y -CONFIG_INET_DIAG=y -CONFIG_INET_TCP_DIAG=y -# CONFIG_INET_UDP_DIAG is not set -# CONFIG_INET_RAW_DIAG is not set -# CONFIG_INET_DIAG_DESTROY is not set -# CONFIG_TCP_CONG_ADVANCED is not set -CONFIG_TCP_CONG_CUBIC=y -CONFIG_DEFAULT_TCP_CONG="cubic" -# CONFIG_TCP_MD5SIG is not set -CONFIG_IPV6=y -# CONFIG_IPV6_ROUTER_PREF is not set -# CONFIG_IPV6_OPTIMISTIC_DAD is not set -# CONFIG_INET6_AH is not set -# CONFIG_INET6_ESP is not set -# CONFIG_INET6_IPCOMP is not set -# CONFIG_IPV6_MIP6 is not set -# CONFIG_IPV6_ILA is not set -# CONFIG_IPV6_VTI is not set -CONFIG_IPV6_SIT=y -# CONFIG_IPV6_SIT_6RD is not set -CONFIG_IPV6_NDISC_NODETYPE=y -# CONFIG_IPV6_TUNNEL is not set -# CONFIG_IPV6_MULTIPLE_TABLES is not set -# CONFIG_IPV6_MROUTE is not set -# CONFIG_IPV6_SEG6_LWTUNNEL is not set -# CONFIG_IPV6_SEG6_HMAC is not set -# CONFIG_IPV6_RPL_LWTUNNEL is not set -# CONFIG_IPV6_IOAM6_LWTUNNEL is not set -# CONFIG_NETLABEL is not set -# CONFIG_MPTCP is not set -CONFIG_NETWORK_SECMARK=y -# CONFIG_NETWORK_PHY_TIMESTAMPING is not set -CONFIG_NETFILTER=y -CONFIG_NETFILTER_ADVANCED=y -CONFIG_BRIDGE_NETFILTER=m - -# -# Core Netfilter Configuration -# -CONFIG_NETFILTER_INGRESS=y -CONFIG_NETFILTER_EGRESS=y -CONFIG_NETFILTER_FAMILY_BRIDGE=y -# CONFIG_NETFILTER_NETLINK_ACCT is not set -# CONFIG_NETFILTER_NETLINK_QUEUE is not set -# CONFIG_NETFILTER_NETLINK_LOG is not set -# CONFIG_NETFILTER_NETLINK_OSF is not set -CONFIG_NF_CONNTRACK=m -CONFIG_NF_LOG_SYSLOG=m -# CONFIG_NF_CONNTRACK_MARK is not set -# CONFIG_NF_CONNTRACK_SECMARK is not set -# CONFIG_NF_CONNTRACK_ZONES is not set -# CONFIG_NF_CONNTRACK_PROCFS is not set -# CONFIG_NF_CONNTRACK_EVENTS is not set -# CONFIG_NF_CONNTRACK_TIMEOUT is not set -# CONFIG_NF_CONNTRACK_TIMESTAMP is not set -# CONFIG_NF_CONNTRACK_LABELS is not set -CONFIG_NF_CT_PROTO_DCCP=y -CONFIG_NF_CT_PROTO_SCTP=y -CONFIG_NF_CT_PROTO_UDPLITE=y -# CONFIG_NF_CONNTRACK_AMANDA is not set -CONFIG_NF_CONNTRACK_FTP=m -# CONFIG_NF_CONNTRACK_H323 is not set -# CONFIG_NF_CONNTRACK_IRC is not set -# CONFIG_NF_CONNTRACK_NETBIOS_NS is not set -# CONFIG_NF_CONNTRACK_SNMP is not set -# CONFIG_NF_CONNTRACK_PPTP is not set -# CONFIG_NF_CONNTRACK_SANE is not set -# CONFIG_NF_CONNTRACK_SIP is not set -CONFIG_NF_CONNTRACK_TFTP=m -# CONFIG_NF_CT_NETLINK is not set -CONFIG_NF_NAT=m -CONFIG_NF_NAT_FTP=m -CONFIG_NF_NAT_TFTP=m -CONFIG_NF_NAT_REDIRECT=y -CONFIG_NF_NAT_MASQUERADE=y -# CONFIG_NF_TABLES is not set -CONFIG_NETFILTER_XTABLES=y -CONFIG_NETFILTER_XTABLES_COMPAT=y - -# -# Xtables combined modules -# -CONFIG_NETFILTER_XT_MARK=m -# CONFIG_NETFILTER_XT_CONNMARK is not set - -# -# Xtables targets -# -# CONFIG_NETFILTER_XT_TARGET_AUDIT is not set -# CONFIG_NETFILTER_XT_TARGET_CHECKSUM is not set -# CONFIG_NETFILTER_XT_TARGET_CLASSIFY is not set -# CONFIG_NETFILTER_XT_TARGET_CONNMARK is not set -# CONFIG_NETFILTER_XT_TARGET_DSCP is not set -# CONFIG_NETFILTER_XT_TARGET_HL is not set -# CONFIG_NETFILTER_XT_TARGET_HMARK is not set -# CONFIG_NETFILTER_XT_TARGET_IDLETIMER is not set -# CONFIG_NETFILTER_XT_TARGET_LOG is not set -# CONFIG_NETFILTER_XT_TARGET_MARK is not set -CONFIG_NETFILTER_XT_NAT=m -# CONFIG_NETFILTER_XT_TARGET_NETMAP is not set -# CONFIG_NETFILTER_XT_TARGET_NFLOG is not set -# CONFIG_NETFILTER_XT_TARGET_NFQUEUE is not set -# CONFIG_NETFILTER_XT_TARGET_RATEEST is not set -CONFIG_NETFILTER_XT_TARGET_REDIRECT=m -CONFIG_NETFILTER_XT_TARGET_MASQUERADE=m -# CONFIG_NETFILTER_XT_TARGET_TEE is not set -# CONFIG_NETFILTER_XT_TARGET_TPROXY is not set -# CONFIG_NETFILTER_XT_TARGET_SECMARK is not set -# CONFIG_NETFILTER_XT_TARGET_TCPMSS is not set -# CONFIG_NETFILTER_XT_TARGET_TCPOPTSTRIP is not set - -# -# Xtables matches -# -CONFIG_NETFILTER_XT_MATCH_ADDRTYPE=m -# CONFIG_NETFILTER_XT_MATCH_BPF is not set -# CONFIG_NETFILTER_XT_MATCH_CGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_CLUSTER is not set -# CONFIG_NETFILTER_XT_MATCH_COMMENT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNBYTES is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLABEL is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNMARK is not set -CONFIG_NETFILTER_XT_MATCH_CONNTRACK=m -# CONFIG_NETFILTER_XT_MATCH_CPU is not set -# CONFIG_NETFILTER_XT_MATCH_DCCP is not set -# CONFIG_NETFILTER_XT_MATCH_DEVGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_DSCP is not set -# CONFIG_NETFILTER_XT_MATCH_ECN is not set -# CONFIG_NETFILTER_XT_MATCH_ESP is not set -# CONFIG_NETFILTER_XT_MATCH_HASHLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_HELPER is not set -# CONFIG_NETFILTER_XT_MATCH_HL is not set -# CONFIG_NETFILTER_XT_MATCH_IPCOMP is not set -# CONFIG_NETFILTER_XT_MATCH_IPRANGE is not set -CONFIG_NETFILTER_XT_MATCH_IPVS=m -# CONFIG_NETFILTER_XT_MATCH_L2TP is not set -# CONFIG_NETFILTER_XT_MATCH_LENGTH is not set -# CONFIG_NETFILTER_XT_MATCH_LIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_MAC is not set -# CONFIG_NETFILTER_XT_MATCH_MARK is not set -# CONFIG_NETFILTER_XT_MATCH_MULTIPORT is not set -# CONFIG_NETFILTER_XT_MATCH_NFACCT is not set -# CONFIG_NETFILTER_XT_MATCH_OSF is not set -# CONFIG_NETFILTER_XT_MATCH_OWNER is not set -# CONFIG_NETFILTER_XT_MATCH_POLICY is not set -# CONFIG_NETFILTER_XT_MATCH_PHYSDEV is not set -# CONFIG_NETFILTER_XT_MATCH_PKTTYPE is not set -# CONFIG_NETFILTER_XT_MATCH_QUOTA is not set -# CONFIG_NETFILTER_XT_MATCH_RATEEST is not set -# CONFIG_NETFILTER_XT_MATCH_REALM is not set -# CONFIG_NETFILTER_XT_MATCH_RECENT is not set -# CONFIG_NETFILTER_XT_MATCH_SCTP is not set -# CONFIG_NETFILTER_XT_MATCH_SOCKET is not set -# CONFIG_NETFILTER_XT_MATCH_STATE is not set -# CONFIG_NETFILTER_XT_MATCH_STATISTIC is not set -# CONFIG_NETFILTER_XT_MATCH_STRING is not set -# CONFIG_NETFILTER_XT_MATCH_TCPMSS is not set -# CONFIG_NETFILTER_XT_MATCH_TIME is not set -# CONFIG_NETFILTER_XT_MATCH_U32 is not set -# end of Core Netfilter Configuration - -# CONFIG_IP_SET is not set -CONFIG_IP_VS=m -# CONFIG_IP_VS_IPV6 is not set -# CONFIG_IP_VS_DEBUG is not set -CONFIG_IP_VS_TAB_BITS=12 - -# -# IPVS transport protocol load balancing support -# -CONFIG_IP_VS_PROTO_TCP=y -CONFIG_IP_VS_PROTO_UDP=y -# CONFIG_IP_VS_PROTO_ESP is not set -# CONFIG_IP_VS_PROTO_AH is not set -# CONFIG_IP_VS_PROTO_SCTP is not set - -# -# IPVS scheduler -# -CONFIG_IP_VS_RR=m -# CONFIG_IP_VS_WRR is not set -# CONFIG_IP_VS_LC is not set -# CONFIG_IP_VS_WLC is not set -# CONFIG_IP_VS_FO is not set -# CONFIG_IP_VS_OVF is not set -# CONFIG_IP_VS_LBLC is not set -# CONFIG_IP_VS_LBLCR is not set -# CONFIG_IP_VS_DH is not set -# CONFIG_IP_VS_SH is not set -# CONFIG_IP_VS_MH is not set -# CONFIG_IP_VS_SED is not set -# CONFIG_IP_VS_NQ is not set -# CONFIG_IP_VS_TWOS is not set - -# -# IPVS SH scheduler -# -CONFIG_IP_VS_SH_TAB_BITS=8 - -# -# IPVS MH scheduler -# -CONFIG_IP_VS_MH_TAB_INDEX=12 - -# -# IPVS application helper -# -# CONFIG_IP_VS_FTP is not set -CONFIG_IP_VS_NFCT=y - -# -# IP: Netfilter Configuration -# -CONFIG_NF_DEFRAG_IPV4=m -# CONFIG_NF_SOCKET_IPV4 is not set -# CONFIG_NF_TPROXY_IPV4 is not set -# CONFIG_NF_DUP_IPV4 is not set -CONFIG_NF_LOG_ARP=m -CONFIG_NF_LOG_IPV4=m -CONFIG_NF_REJECT_IPV4=m -CONFIG_IP_NF_IPTABLES=y -# CONFIG_IP_NF_MATCH_AH is not set -# CONFIG_IP_NF_MATCH_ECN is not set -# CONFIG_IP_NF_MATCH_RPFILTER is not set -# CONFIG_IP_NF_MATCH_TTL is not set -CONFIG_IP_NF_FILTER=m -CONFIG_IP_NF_TARGET_REJECT=m -# CONFIG_IP_NF_TARGET_SYNPROXY is not set -CONFIG_IP_NF_NAT=m -CONFIG_IP_NF_TARGET_MASQUERADE=m -# CONFIG_IP_NF_TARGET_NETMAP is not set -CONFIG_IP_NF_TARGET_REDIRECT=m -CONFIG_IP_NF_MANGLE=m -# CONFIG_IP_NF_TARGET_ECN is not set -# CONFIG_IP_NF_TARGET_TTL is not set -# CONFIG_IP_NF_RAW is not set -# CONFIG_IP_NF_SECURITY is not set -# CONFIG_IP_NF_ARPTABLES is not set -# end of IP: Netfilter Configuration - -# -# IPv6: Netfilter Configuration -# -# CONFIG_NF_SOCKET_IPV6 is not set -# CONFIG_NF_TPROXY_IPV6 is not set -# CONFIG_NF_DUP_IPV6 is not set -CONFIG_NF_REJECT_IPV6=m -CONFIG_NF_LOG_IPV6=m -CONFIG_IP6_NF_IPTABLES=m -# CONFIG_IP6_NF_MATCH_AH is not set -# CONFIG_IP6_NF_MATCH_EUI64 is not set -# CONFIG_IP6_NF_MATCH_FRAG is not set -# CONFIG_IP6_NF_MATCH_OPTS is not set -# CONFIG_IP6_NF_MATCH_HL is not set -CONFIG_IP6_NF_MATCH_IPV6HEADER=m -# CONFIG_IP6_NF_MATCH_MH is not set -# CONFIG_IP6_NF_MATCH_RPFILTER is not set -# CONFIG_IP6_NF_MATCH_RT is not set -# CONFIG_IP6_NF_MATCH_SRH is not set -# CONFIG_IP6_NF_TARGET_HL is not set -CONFIG_IP6_NF_FILTER=m -CONFIG_IP6_NF_TARGET_REJECT=m -# CONFIG_IP6_NF_TARGET_SYNPROXY is not set -CONFIG_IP6_NF_MANGLE=m -# CONFIG_IP6_NF_RAW is not set -# CONFIG_IP6_NF_SECURITY is not set -# CONFIG_IP6_NF_NAT is not set -# end of IPv6: Netfilter Configuration - -CONFIG_NF_DEFRAG_IPV6=m -# CONFIG_NF_CONNTRACK_BRIDGE is not set -# CONFIG_BRIDGE_NF_EBTABLES is not set -# CONFIG_BPFILTER is not set -# CONFIG_IP_DCCP is not set -# CONFIG_IP_SCTP is not set -# CONFIG_RDS is not set -# CONFIG_TIPC is not set -# CONFIG_ATM is not set -# CONFIG_L2TP is not set -CONFIG_STP=m -CONFIG_BRIDGE=m -CONFIG_BRIDGE_IGMP_SNOOPING=y -CONFIG_BRIDGE_VLAN_FILTERING=y -# CONFIG_BRIDGE_MRP is not set -# CONFIG_BRIDGE_CFM is not set -# CONFIG_NET_DSA is not set -CONFIG_VLAN_8021Q=m -# CONFIG_VLAN_8021Q_GVRP is not set -# CONFIG_VLAN_8021Q_MVRP is not set -CONFIG_LLC=m -# CONFIG_LLC2 is not set -# CONFIG_ATALK is not set -# CONFIG_X25 is not set -# CONFIG_LAPB is not set -# CONFIG_PHONET is not set -# CONFIG_6LOWPAN is not set -# CONFIG_IEEE802154 is not set -CONFIG_NET_SCHED=y - -# -# Queueing/Scheduling -# -# CONFIG_NET_SCH_HTB is not set -# CONFIG_NET_SCH_HFSC is not set -# CONFIG_NET_SCH_PRIO is not set -# CONFIG_NET_SCH_MULTIQ is not set -# CONFIG_NET_SCH_RED is not set -# CONFIG_NET_SCH_SFB is not set -# CONFIG_NET_SCH_SFQ is not set -# CONFIG_NET_SCH_TEQL is not set -# CONFIG_NET_SCH_TBF is not set -# CONFIG_NET_SCH_CBS is not set -# CONFIG_NET_SCH_ETF is not set -# CONFIG_NET_SCH_TAPRIO is not set -# CONFIG_NET_SCH_GRED is not set -# CONFIG_NET_SCH_NETEM is not set -# CONFIG_NET_SCH_DRR is not set -# CONFIG_NET_SCH_MQPRIO is not set -# CONFIG_NET_SCH_SKBPRIO is not set -# CONFIG_NET_SCH_CHOKE is not set -# CONFIG_NET_SCH_QFQ is not set -# CONFIG_NET_SCH_CODEL is not set -# CONFIG_NET_SCH_FQ_CODEL is not set -# CONFIG_NET_SCH_CAKE is not set -# CONFIG_NET_SCH_FQ is not set -# CONFIG_NET_SCH_HHF is not set -# CONFIG_NET_SCH_PIE is not set -# CONFIG_NET_SCH_PLUG is not set -# CONFIG_NET_SCH_ETS is not set -# CONFIG_NET_SCH_DEFAULT is not set - -# -# Classification -# -CONFIG_NET_CLS=y -# CONFIG_NET_CLS_BASIC is not set -# CONFIG_NET_CLS_ROUTE4 is not set -# CONFIG_NET_CLS_FW is not set -# CONFIG_NET_CLS_U32 is not set -# CONFIG_NET_CLS_FLOW is not set -CONFIG_NET_CLS_CGROUP=m -# CONFIG_NET_CLS_BPF is not set -# CONFIG_NET_CLS_FLOWER is not set -# CONFIG_NET_CLS_MATCHALL is not set -# CONFIG_NET_EMATCH is not set -# CONFIG_NET_CLS_ACT is not set -CONFIG_NET_SCH_FIFO=y -# CONFIG_DCB is not set -CONFIG_DNS_RESOLVER=y -# CONFIG_BATMAN_ADV is not set -# CONFIG_OPENVSWITCH is not set -# CONFIG_VSOCKETS is not set -CONFIG_NETLINK_DIAG=y -# CONFIG_MPLS is not set -# CONFIG_NET_NSH is not set -# CONFIG_HSR is not set -# CONFIG_NET_SWITCHDEV is not set -CONFIG_NET_L3_MASTER_DEV=y -# CONFIG_QRTR is not set -# CONFIG_NET_NCSI is not set -CONFIG_PCPU_DEV_REFCNT=y -CONFIG_RPS=y -CONFIG_RFS_ACCEL=y -CONFIG_SOCK_RX_QUEUE_MAPPING=y -CONFIG_XPS=y -CONFIG_CGROUP_NET_PRIO=y -CONFIG_CGROUP_NET_CLASSID=y -CONFIG_NET_RX_BUSY_POLL=y -CONFIG_BQL=y -# CONFIG_BPF_STREAM_PARSER is not set -CONFIG_NET_FLOW_LIMIT=y - -# -# Network testing -# -# CONFIG_NET_PKTGEN is not set -# end of Network testing -# end of Networking options - -# CONFIG_HAMRADIO is not set -# CONFIG_CAN is not set -# CONFIG_BT is not set -# CONFIG_AF_RXRPC is not set -# CONFIG_AF_KCM is not set -# CONFIG_MCTP is not set -CONFIG_WIRELESS=y -# CONFIG_CFG80211 is not set - -# -# CFG80211 needs to be enabled for MAC80211 -# -CONFIG_MAC80211_STA_HASH_MAX_SIZE=0 -# CONFIG_RFKILL is not set -CONFIG_NET_9P=y -CONFIG_NET_9P_FD=y -CONFIG_NET_9P_VIRTIO=y -# CONFIG_NET_9P_DEBUG is not set -# CONFIG_CAIF is not set -# CONFIG_CEPH_LIB is not set -# CONFIG_NFC is not set -# CONFIG_PSAMPLE is not set -# CONFIG_NET_IFE is not set -# CONFIG_LWTUNNEL is not set -CONFIG_DST_CACHE=y -CONFIG_GRO_CELLS=y -CONFIG_NET_SELFTESTS=y -CONFIG_NET_SOCK_MSG=y -CONFIG_PAGE_POOL=y -# CONFIG_PAGE_POOL_STATS is not set -CONFIG_FAILOVER=y -CONFIG_ETHTOOL_NETLINK=y - -# -# Device Drivers -# -CONFIG_HAVE_PCI=y -CONFIG_PCI=y -CONFIG_PCI_DOMAINS=y -CONFIG_PCI_DOMAINS_GENERIC=y -CONFIG_PCIEPORTBUS=y -# CONFIG_PCIEAER is not set -CONFIG_PCIEASPM=y -CONFIG_PCIEASPM_DEFAULT=y -# CONFIG_PCIEASPM_POWERSAVE is not set -# CONFIG_PCIEASPM_POWER_SUPERSAVE is not set -# CONFIG_PCIEASPM_PERFORMANCE is not set -CONFIG_PCIE_PME=y -# CONFIG_PCIE_PTM is not set -CONFIG_PCI_MSI=y -CONFIG_PCI_QUIRKS=y -# CONFIG_PCI_DEBUG is not set -# CONFIG_PCI_STUB is not set -CONFIG_PCI_ECAM=y -# CONFIG_PCI_IOV is not set -# CONFIG_PCI_PRI is not set -# CONFIG_PCI_PASID is not set -# CONFIG_PCIE_BUS_TUNE_OFF is not set -CONFIG_PCIE_BUS_DEFAULT=y -# CONFIG_PCIE_BUS_SAFE is not set -# CONFIG_PCIE_BUS_PERFORMANCE is not set -# CONFIG_PCIE_BUS_PEER2PEER is not set -CONFIG_VGA_ARB=y -CONFIG_VGA_ARB_MAX_GPUS=16 -# CONFIG_HOTPLUG_PCI is not set - -# -# PCI controller drivers -# -# CONFIG_PCI_FTPCI100 is not set -# CONFIG_PCIE_RCAR_HOST is not set -CONFIG_PCI_HOST_COMMON=y -CONFIG_PCI_HOST_GENERIC=y -CONFIG_PCIE_XILINX=y -CONFIG_PCIE_MICROCHIP_HOST=y - -# -# DesignWare PCI Core Support -# -CONFIG_PCIE_DW=y -CONFIG_PCIE_DW_HOST=y -# CONFIG_PCIE_DW_PLAT_HOST is not set -# CONFIG_PCI_MESON is not set -CONFIG_PCIE_FU740=y -# end of DesignWare PCI Core Support - -# -# Mobiveil PCIe Core Support -# -# end of Mobiveil PCIe Core Support - -# -# Cadence PCIe controllers support -# -# CONFIG_PCIE_CADENCE_PLAT_HOST is not set -# CONFIG_PCI_J721E_HOST is not set -# end of Cadence PCIe controllers support -# end of PCI controller drivers - -# -# PCI Endpoint -# -# CONFIG_PCI_ENDPOINT is not set -# end of PCI Endpoint - -# -# PCI switch controller drivers -# -# CONFIG_PCI_SW_SWITCHTEC is not set -# end of PCI switch controller drivers - -# CONFIG_CXL_BUS is not set -# CONFIG_PCCARD is not set -# CONFIG_RAPIDIO is not set - -# -# Generic Driver Options -# -CONFIG_AUXILIARY_BUS=y -# CONFIG_UEVENT_HELPER is not set -CONFIG_DEVTMPFS=y -CONFIG_DEVTMPFS_MOUNT=y -# CONFIG_DEVTMPFS_SAFE is not set -CONFIG_STANDALONE=y -CONFIG_PREVENT_FIRMWARE_BUILD=y - -# -# Firmware loader -# -CONFIG_FW_LOADER=y -CONFIG_EXTRA_FIRMWARE="" -# CONFIG_FW_LOADER_USER_HELPER is not set -# CONFIG_FW_LOADER_COMPRESS is not set -# CONFIG_FW_UPLOAD is not set -# end of Firmware loader - -CONFIG_WANT_DEV_COREDUMP=y -CONFIG_ALLOW_DEV_COREDUMP=y -CONFIG_DEV_COREDUMP=y -# CONFIG_DEBUG_DRIVER is not set -# CONFIG_DEBUG_DEVRES is not set -# CONFIG_DEBUG_TEST_DRIVER_REMOVE is not set -# CONFIG_TEST_ASYNC_DRIVER_PROBE is not set -CONFIG_SOC_BUS=y -CONFIG_REGMAP=y -CONFIG_REGMAP_I2C=y -CONFIG_REGMAP_MMIO=y -CONFIG_DMA_SHARED_BUFFER=y -# CONFIG_DMA_FENCE_TRACE is not set -CONFIG_GENERIC_ARCH_TOPOLOGY=y -# end of Generic Driver Options - -# -# Bus devices -# -# CONFIG_MOXTET is not set -# CONFIG_SUN50I_DE2_BUS is not set -# CONFIG_SUNXI_RSB is not set -# CONFIG_MHI_BUS is not set -# CONFIG_MHI_BUS_EP is not set -# end of Bus devices - -# CONFIG_CONNECTOR is not set - -# -# Firmware Drivers -# - -# -# ARM System Control and Management Interface Protocol -# -# end of ARM System Control and Management Interface Protocol - -# CONFIG_FIRMWARE_MEMMAP is not set -# CONFIG_SYSFB_SIMPLEFB is not set -# CONFIG_GOOGLE_FIRMWARE is not set - -# -# EFI (Extensible Firmware Interface) Support -# -CONFIG_EFI_ESRT=y -CONFIG_EFI_PARAMS_FROM_FDT=y -CONFIG_EFI_RUNTIME_WRAPPERS=y -CONFIG_EFI_GENERIC_STUB=y -# CONFIG_EFI_ZBOOT is not set -# CONFIG_EFI_BOOTLOADER_CONTROL is not set -# CONFIG_EFI_CAPSULE_LOADER is not set -# CONFIG_EFI_TEST is not set -# CONFIG_RESET_ATTACK_MITIGATION is not set -# CONFIG_EFI_DISABLE_PCI_DMA is not set -CONFIG_EFI_EARLYCON=y -# CONFIG_EFI_DISABLE_RUNTIME is not set -# CONFIG_EFI_COCO_SECRET is not set -# end of EFI (Extensible Firmware Interface) Support - -# -# Tegra firmware driver -# -# end of Tegra firmware driver -# end of Firmware Drivers - -# CONFIG_GNSS is not set -# CONFIG_MTD is not set -CONFIG_DTC=y -CONFIG_OF=y -# CONFIG_OF_UNITTEST is not set -CONFIG_OF_FLATTREE=y -CONFIG_OF_EARLY_FLATTREE=y -CONFIG_OF_KOBJ=y -CONFIG_OF_DYNAMIC=y -CONFIG_OF_ADDRESS=y -CONFIG_OF_IRQ=y -CONFIG_OF_RESERVED_MEM=y -CONFIG_OF_RESOLVE=y -CONFIG_OF_OVERLAY=y -CONFIG_OF_DMA_DEFAULT_COHERENT=y -# CONFIG_PARPORT is not set -CONFIG_BLK_DEV=y -# CONFIG_BLK_DEV_NULL_BLK is not set -CONFIG_CDROM=y -# CONFIG_BLK_DEV_PCIESSD_MTIP32XX is not set -CONFIG_BLK_DEV_LOOP=y -CONFIG_BLK_DEV_LOOP_MIN_COUNT=8 -# CONFIG_BLK_DEV_DRBD is not set -# CONFIG_BLK_DEV_NBD is not set -# CONFIG_BLK_DEV_RAM is not set -# CONFIG_CDROM_PKTCDVD is not set -# CONFIG_ATA_OVER_ETH is not set -CONFIG_VIRTIO_BLK=y -# CONFIG_BLK_DEV_RBD is not set -# CONFIG_BLK_DEV_UBLK is not set - -# -# NVME Support -# -CONFIG_NVME_CORE=m -CONFIG_BLK_DEV_NVME=m -# CONFIG_NVME_MULTIPATH is not set -# CONFIG_NVME_VERBOSE_ERRORS is not set -# CONFIG_NVME_HWMON is not set -# CONFIG_NVME_FC is not set -# CONFIG_NVME_TCP is not set -# CONFIG_NVME_AUTH is not set -# CONFIG_NVME_TARGET is not set -# end of NVME Support - -# -# Misc devices -# -# CONFIG_AD525X_DPOT is not set -# CONFIG_DUMMY_IRQ is not set -# CONFIG_PHANTOM is not set -# CONFIG_TIFM_CORE is not set -# CONFIG_ICS932S401 is not set -# CONFIG_ENCLOSURE_SERVICES is not set -# CONFIG_HP_ILO is not set -# CONFIG_APDS9802ALS is not set -# CONFIG_ISL29003 is not set -# CONFIG_ISL29020 is not set -# CONFIG_SENSORS_TSL2550 is not set -# CONFIG_SENSORS_BH1770 is not set -# CONFIG_SENSORS_APDS990X is not set -# CONFIG_HMC6352 is not set -# CONFIG_DS1682 is not set -# CONFIG_LATTICE_ECP3_CONFIG is not set -# CONFIG_SRAM is not set -# CONFIG_DW_XDATA_PCIE is not set -# CONFIG_PCI_ENDPOINT_TEST is not set -# CONFIG_XILINX_SDFEC is not set -# CONFIG_OPEN_DICE is not set -# CONFIG_VCPU_STALL_DETECTOR is not set -# CONFIG_C2PORT is not set - -# -# EEPROM support -# -CONFIG_EEPROM_AT24=y -# CONFIG_EEPROM_AT25 is not set -# CONFIG_EEPROM_LEGACY is not set -# CONFIG_EEPROM_MAX6875 is not set -# CONFIG_EEPROM_93CX6 is not set -# CONFIG_EEPROM_93XX46 is not set -# CONFIG_EEPROM_IDT_89HPESX is not set -# CONFIG_EEPROM_EE1004 is not set -# end of EEPROM support - -# CONFIG_CB710_CORE is not set - -# -# Texas Instruments shared transport line discipline -# -# CONFIG_TI_ST is not set -# end of Texas Instruments shared transport line discipline - -# CONFIG_SENSORS_LIS3_SPI is not set -# CONFIG_SENSORS_LIS3_I2C is not set -# CONFIG_ALTERA_STAPL is not set -# CONFIG_GENWQE is not set -# CONFIG_ECHO is not set -# CONFIG_BCM_VK is not set -# CONFIG_MISC_ALCOR_PCI is not set -# CONFIG_MISC_RTSX_PCI is not set -# CONFIG_MISC_RTSX_USB is not set -# CONFIG_UACCE is not set -# CONFIG_PVPANIC is not set -# CONFIG_GP_PCI1XXXX is not set -# end of Misc devices - -# -# SCSI device support -# -CONFIG_SCSI_MOD=y -# CONFIG_RAID_ATTRS is not set -CONFIG_SCSI_COMMON=y -CONFIG_SCSI=y -CONFIG_SCSI_DMA=y -CONFIG_SCSI_PROC_FS=y - -# -# SCSI support type (disk, tape, CD-ROM) -# -CONFIG_BLK_DEV_SD=y -# CONFIG_CHR_DEV_ST is not set -CONFIG_BLK_DEV_SR=y -# CONFIG_CHR_DEV_SG is not set -CONFIG_BLK_DEV_BSG=y -# CONFIG_CHR_DEV_SCH is not set -# CONFIG_SCSI_CONSTANTS is not set -# CONFIG_SCSI_LOGGING is not set -# CONFIG_SCSI_SCAN_ASYNC is not set - -# -# SCSI Transports -# -# CONFIG_SCSI_SPI_ATTRS is not set -# CONFIG_SCSI_FC_ATTRS is not set -# CONFIG_SCSI_ISCSI_ATTRS is not set -# CONFIG_SCSI_SAS_ATTRS is not set -# CONFIG_SCSI_SAS_LIBSAS is not set -# CONFIG_SCSI_SRP_ATTRS is not set -# end of SCSI Transports - -CONFIG_SCSI_LOWLEVEL=y -# CONFIG_ISCSI_TCP is not set -# CONFIG_ISCSI_BOOT_SYSFS is not set -# CONFIG_SCSI_CXGB3_ISCSI is not set -# CONFIG_SCSI_CXGB4_ISCSI is not set -# CONFIG_SCSI_BNX2_ISCSI is not set -# CONFIG_BE2ISCSI is not set -# CONFIG_BLK_DEV_3W_XXXX_RAID is not set -# CONFIG_SCSI_HPSA is not set -# CONFIG_SCSI_3W_9XXX is not set -# CONFIG_SCSI_3W_SAS is not set -# CONFIG_SCSI_ACARD is not set -# CONFIG_SCSI_AACRAID is not set -# CONFIG_SCSI_AIC7XXX is not set -# CONFIG_SCSI_AIC79XX is not set -# CONFIG_SCSI_AIC94XX is not set -# CONFIG_SCSI_MVSAS is not set -# CONFIG_SCSI_MVUMI is not set -# CONFIG_SCSI_ADVANSYS is not set -# CONFIG_SCSI_ARCMSR is not set -# CONFIG_SCSI_ESAS2R is not set -# CONFIG_MEGARAID_NEWGEN is not set -# CONFIG_MEGARAID_LEGACY is not set -# CONFIG_MEGARAID_SAS is not set -# CONFIG_SCSI_MPT3SAS is not set -# CONFIG_SCSI_MPT2SAS is not set -# CONFIG_SCSI_MPI3MR is not set -# CONFIG_SCSI_SMARTPQI is not set -# CONFIG_SCSI_HPTIOP is not set -# CONFIG_SCSI_BUSLOGIC is not set -# CONFIG_SCSI_MYRB is not set -# CONFIG_SCSI_MYRS is not set -# CONFIG_SCSI_SNIC is not set -# CONFIG_SCSI_DMX3191D is not set -# CONFIG_SCSI_FDOMAIN_PCI is not set -# CONFIG_SCSI_IPS is not set -# CONFIG_SCSI_INITIO is not set -# CONFIG_SCSI_INIA100 is not set -# CONFIG_SCSI_STEX is not set -# CONFIG_SCSI_SYM53C8XX_2 is not set -# CONFIG_SCSI_IPR is not set -# CONFIG_SCSI_QLOGIC_1280 is not set -# CONFIG_SCSI_QLA_ISCSI is not set -# CONFIG_SCSI_DC395x is not set -# CONFIG_SCSI_AM53C974 is not set -# CONFIG_SCSI_WD719X is not set -# CONFIG_SCSI_DEBUG is not set -# CONFIG_SCSI_PMCRAID is not set -# CONFIG_SCSI_PM8001 is not set -CONFIG_SCSI_VIRTIO=y -# CONFIG_SCSI_DH is not set -# end of SCSI device support - -CONFIG_ATA=y -CONFIG_SATA_HOST=y -CONFIG_ATA_VERBOSE_ERROR=y -CONFIG_ATA_FORCE=y -CONFIG_SATA_PMP=y - -# -# Controllers with non-SFF native interface -# -CONFIG_SATA_AHCI=y -CONFIG_SATA_MOBILE_LPM_POLICY=0 -CONFIG_SATA_AHCI_PLATFORM=y -# CONFIG_AHCI_DWC is not set -# CONFIG_AHCI_CEVA is not set -# CONFIG_AHCI_SUNXI is not set -# CONFIG_AHCI_QORIQ is not set -# CONFIG_SATA_INIC162X is not set -# CONFIG_SATA_ACARD_AHCI is not set -# CONFIG_SATA_SIL24 is not set -CONFIG_ATA_SFF=y - -# -# SFF controllers with custom DMA interface -# -# CONFIG_PDC_ADMA is not set -# CONFIG_SATA_QSTOR is not set -# CONFIG_SATA_SX4 is not set -CONFIG_ATA_BMDMA=y - -# -# SATA SFF controllers with BMDMA -# -# CONFIG_ATA_PIIX is not set -# CONFIG_SATA_DWC is not set -# CONFIG_SATA_MV is not set -# CONFIG_SATA_NV is not set -# CONFIG_SATA_PROMISE is not set -# CONFIG_SATA_RCAR is not set -# CONFIG_SATA_SIL is not set -# CONFIG_SATA_SIS is not set -# CONFIG_SATA_SVW is not set -# CONFIG_SATA_ULI is not set -# CONFIG_SATA_VIA is not set -# CONFIG_SATA_VITESSE is not set - -# -# PATA SFF controllers with BMDMA -# -# CONFIG_PATA_ALI is not set -# CONFIG_PATA_AMD is not set -# CONFIG_PATA_ARTOP is not set -# CONFIG_PATA_ATIIXP is not set -# CONFIG_PATA_ATP867X is not set -# CONFIG_PATA_CMD64X is not set -# CONFIG_PATA_CYPRESS is not set -# CONFIG_PATA_EFAR is not set -# CONFIG_PATA_HPT366 is not set -# CONFIG_PATA_HPT37X is not set -# CONFIG_PATA_HPT3X2N is not set -# CONFIG_PATA_HPT3X3 is not set -# CONFIG_PATA_IT8213 is not set -# CONFIG_PATA_IT821X is not set -# CONFIG_PATA_JMICRON is not set -# CONFIG_PATA_MARVELL is not set -# CONFIG_PATA_NETCELL is not set -# CONFIG_PATA_NINJA32 is not set -# CONFIG_PATA_NS87415 is not set -# CONFIG_PATA_OLDPIIX is not set -# CONFIG_PATA_OPTIDMA is not set -# CONFIG_PATA_PDC2027X is not set -# CONFIG_PATA_PDC_OLD is not set -# CONFIG_PATA_RADISYS is not set -# CONFIG_PATA_RDC is not set -# CONFIG_PATA_SCH is not set -# CONFIG_PATA_SERVERWORKS is not set -# CONFIG_PATA_SIL680 is not set -# CONFIG_PATA_SIS is not set -# CONFIG_PATA_TOSHIBA is not set -# CONFIG_PATA_TRIFLEX is not set -# CONFIG_PATA_VIA is not set -# CONFIG_PATA_WINBOND is not set - -# -# PIO-only SFF controllers -# -# CONFIG_PATA_CMD640_PCI is not set -# CONFIG_PATA_MPIIX is not set -# CONFIG_PATA_NS87410 is not set -# CONFIG_PATA_OPTI is not set -# CONFIG_PATA_OF_PLATFORM is not set -# CONFIG_PATA_RZ1000 is not set - -# -# Generic fallback / legacy drivers -# -# CONFIG_ATA_GENERIC is not set -# CONFIG_PATA_LEGACY is not set -CONFIG_MD=y -# CONFIG_BLK_DEV_MD is not set -# CONFIG_BCACHE is not set -CONFIG_BLK_DEV_DM_BUILTIN=y -CONFIG_BLK_DEV_DM=y -# CONFIG_DM_DEBUG is not set -CONFIG_DM_BUFIO=m -# CONFIG_DM_DEBUG_BLOCK_MANAGER_LOCKING is not set -CONFIG_DM_BIO_PRISON=m -CONFIG_DM_PERSISTENT_DATA=m -# CONFIG_DM_UNSTRIPED is not set -# CONFIG_DM_CRYPT is not set -# CONFIG_DM_SNAPSHOT is not set -CONFIG_DM_THIN_PROVISIONING=m -# CONFIG_DM_CACHE is not set -# CONFIG_DM_WRITECACHE is not set -# CONFIG_DM_EBS is not set -# CONFIG_DM_ERA is not set -# CONFIG_DM_CLONE is not set -# CONFIG_DM_MIRROR is not set -# CONFIG_DM_RAID is not set -# CONFIG_DM_ZERO is not set -# CONFIG_DM_MULTIPATH is not set -# CONFIG_DM_DELAY is not set -# CONFIG_DM_DUST is not set -# CONFIG_DM_INIT is not set -# CONFIG_DM_UEVENT is not set -# CONFIG_DM_FLAKEY is not set -# CONFIG_DM_VERITY is not set -# CONFIG_DM_SWITCH is not set -# CONFIG_DM_LOG_WRITES is not set -# CONFIG_DM_INTEGRITY is not set -# CONFIG_DM_AUDIT is not set -# CONFIG_TARGET_CORE is not set -# CONFIG_FUSION is not set - -# -# IEEE 1394 (FireWire) support -# -# CONFIG_FIREWIRE is not set -# CONFIG_FIREWIRE_NOSY is not set -# end of IEEE 1394 (FireWire) support - -CONFIG_NETDEVICES=y -CONFIG_MII=m -CONFIG_NET_CORE=y -# CONFIG_BONDING is not set -CONFIG_DUMMY=m -# CONFIG_WIREGUARD is not set -# CONFIG_EQUALIZER is not set -# CONFIG_NET_FC is not set -# CONFIG_NET_TEAM is not set -CONFIG_MACVLAN=m -# CONFIG_MACVTAP is not set -CONFIG_IPVLAN_L3S=y -CONFIG_IPVLAN=m -# CONFIG_IPVTAP is not set -CONFIG_VXLAN=m -# CONFIG_GENEVE is not set -# CONFIG_BAREUDP is not set -# CONFIG_GTP is not set -# CONFIG_AMT is not set -# CONFIG_MACSEC is not set -# CONFIG_NETCONSOLE is not set -# CONFIG_TUN is not set -# CONFIG_TUN_VNET_CROSS_LE is not set -CONFIG_VETH=m -CONFIG_VIRTIO_NET=y -# CONFIG_NLMON is not set -# CONFIG_ARCNET is not set -CONFIG_ETHERNET=y -CONFIG_NET_VENDOR_3COM=y -# CONFIG_VORTEX is not set -# CONFIG_TYPHOON is not set -CONFIG_NET_VENDOR_ADAPTEC=y -# CONFIG_ADAPTEC_STARFIRE is not set -CONFIG_NET_VENDOR_AGERE=y -# CONFIG_ET131X is not set -CONFIG_NET_VENDOR_ALACRITECH=y -# CONFIG_SLICOSS is not set -CONFIG_NET_VENDOR_ALLWINNER=y -# CONFIG_SUN4I_EMAC is not set -CONFIG_NET_VENDOR_ALTEON=y -# CONFIG_ACENIC is not set -# CONFIG_ALTERA_TSE is not set -CONFIG_NET_VENDOR_AMAZON=y -# CONFIG_ENA_ETHERNET is not set -CONFIG_NET_VENDOR_AMD=y -# CONFIG_AMD8111_ETH is not set -# CONFIG_PCNET32 is not set -CONFIG_NET_VENDOR_AQUANTIA=y -# CONFIG_AQTION is not set -CONFIG_NET_VENDOR_ARC=y -CONFIG_NET_VENDOR_ASIX=y -# CONFIG_SPI_AX88796C is not set -CONFIG_NET_VENDOR_ATHEROS=y -# CONFIG_ATL2 is not set -# CONFIG_ATL1 is not set -# CONFIG_ATL1E is not set -# CONFIG_ATL1C is not set -# CONFIG_ALX is not set -CONFIG_NET_VENDOR_BROADCOM=y -# CONFIG_B44 is not set -# CONFIG_BCMGENET is not set -# CONFIG_BNX2 is not set -# CONFIG_CNIC is not set -# CONFIG_TIGON3 is not set -# CONFIG_BNX2X is not set -# CONFIG_SYSTEMPORT is not set -# CONFIG_BNXT is not set -CONFIG_NET_VENDOR_CADENCE=y -CONFIG_MACB=y -# CONFIG_MACB_PCI is not set -CONFIG_NET_VENDOR_CAVIUM=y -# CONFIG_THUNDER_NIC_PF is not set -# CONFIG_THUNDER_NIC_VF is not set -# CONFIG_THUNDER_NIC_BGX is not set -# CONFIG_THUNDER_NIC_RGX is not set -# CONFIG_LIQUIDIO is not set -# CONFIG_LIQUIDIO_VF is not set -CONFIG_NET_VENDOR_CHELSIO=y -# CONFIG_CHELSIO_T1 is not set -# CONFIG_CHELSIO_T3 is not set -# CONFIG_CHELSIO_T4 is not set -# CONFIG_CHELSIO_T4VF is not set -CONFIG_NET_VENDOR_CISCO=y -# CONFIG_ENIC is not set -CONFIG_NET_VENDOR_CORTINA=y -# CONFIG_GEMINI_ETHERNET is not set -CONFIG_NET_VENDOR_DAVICOM=y -# CONFIG_DM9051 is not set -# CONFIG_DNET is not set -CONFIG_NET_VENDOR_DEC=y -# CONFIG_NET_TULIP is not set -CONFIG_NET_VENDOR_DLINK=y -# CONFIG_DL2K is not set -# CONFIG_SUNDANCE is not set -CONFIG_NET_VENDOR_EMULEX=y -# CONFIG_BE2NET is not set -CONFIG_NET_VENDOR_ENGLEDER=y -# CONFIG_TSNEP is not set -CONFIG_NET_VENDOR_EZCHIP=y -# CONFIG_EZCHIP_NPS_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_FUNGIBLE=y -# CONFIG_FUN_ETH is not set -CONFIG_NET_VENDOR_GOOGLE=y -CONFIG_NET_VENDOR_HUAWEI=y -CONFIG_NET_VENDOR_I825XX=y -CONFIG_NET_VENDOR_INTEL=y -# CONFIG_E100 is not set -# CONFIG_E1000 is not set -CONFIG_E1000E=y -# CONFIG_IGB is not set -# CONFIG_IGBVF is not set -# CONFIG_IXGB is not set -# CONFIG_IXGBE is not set -# CONFIG_IXGBEVF is not set -# CONFIG_I40E is not set -# CONFIG_I40EVF is not set -# CONFIG_ICE is not set -# CONFIG_FM10K is not set -# CONFIG_IGC is not set -CONFIG_NET_VENDOR_WANGXUN=y -# CONFIG_NGBE is not set -# CONFIG_TXGBE is not set -# CONFIG_JME is not set -CONFIG_NET_VENDOR_ADI=y -CONFIG_NET_VENDOR_LITEX=y -# CONFIG_LITEX_LITEETH is not set -CONFIG_NET_VENDOR_MARVELL=y -# CONFIG_MVMDIO is not set -# CONFIG_SKGE is not set -# CONFIG_SKY2 is not set -# CONFIG_OCTEON_EP is not set -CONFIG_NET_VENDOR_MELLANOX=y -# CONFIG_MLX4_EN is not set -# CONFIG_MLX5_CORE is not set -# CONFIG_MLXSW_CORE is not set -# CONFIG_MLXFW is not set -CONFIG_NET_VENDOR_MICREL=y -# CONFIG_KS8842 is not set -# CONFIG_KS8851 is not set -# CONFIG_KS8851_MLL is not set -# CONFIG_KSZ884X_PCI is not set -CONFIG_NET_VENDOR_MICROCHIP=y -# CONFIG_ENC28J60 is not set -# CONFIG_ENCX24J600 is not set -# CONFIG_LAN743X is not set -# CONFIG_VCAP is not set -CONFIG_NET_VENDOR_MICROSEMI=y -CONFIG_NET_VENDOR_MICROSOFT=y -CONFIG_NET_VENDOR_MYRI=y -# CONFIG_MYRI10GE is not set -# CONFIG_FEALNX is not set -CONFIG_NET_VENDOR_NI=y -# CONFIG_NI_XGE_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_NATSEMI=y -# CONFIG_NATSEMI is not set -# CONFIG_NS83820 is not set -CONFIG_NET_VENDOR_NETERION=y -# CONFIG_S2IO is not set -CONFIG_NET_VENDOR_NETRONOME=y -# CONFIG_NFP is not set -CONFIG_NET_VENDOR_8390=y -# CONFIG_NE2K_PCI is not set -CONFIG_NET_VENDOR_NVIDIA=y -# CONFIG_FORCEDETH is not set -CONFIG_NET_VENDOR_OKI=y -# CONFIG_ETHOC is not set -CONFIG_NET_VENDOR_PACKET_ENGINES=y -# CONFIG_HAMACHI is not set -# CONFIG_YELLOWFIN is not set -CONFIG_NET_VENDOR_PENSANDO=y -# CONFIG_IONIC is not set -CONFIG_NET_VENDOR_QLOGIC=y -# CONFIG_QLA3XXX is not set -# CONFIG_QLCNIC is not set -# CONFIG_NETXEN_NIC is not set -# CONFIG_QED is not set -CONFIG_NET_VENDOR_BROCADE=y -# CONFIG_BNA is not set -CONFIG_NET_VENDOR_QUALCOMM=y -# CONFIG_QCA7000_SPI is not set -# CONFIG_QCOM_EMAC is not set -# CONFIG_RMNET is not set -CONFIG_NET_VENDOR_RDC=y -# CONFIG_R6040 is not set -CONFIG_NET_VENDOR_REALTEK=y -# CONFIG_8139CP is not set -# CONFIG_8139TOO is not set -CONFIG_R8169=y -CONFIG_NET_VENDOR_RENESAS=y -# CONFIG_SH_ETH is not set -# CONFIG_RAVB is not set -# CONFIG_RENESAS_ETHER_SWITCH is not set -CONFIG_NET_VENDOR_ROCKER=y -CONFIG_NET_VENDOR_SAMSUNG=y -# CONFIG_SXGBE_ETH is not set -CONFIG_NET_VENDOR_SEEQ=y -CONFIG_NET_VENDOR_SILAN=y -# CONFIG_SC92031 is not set -CONFIG_NET_VENDOR_SIS=y -# CONFIG_SIS900 is not set -# CONFIG_SIS190 is not set -CONFIG_NET_VENDOR_SOLARFLARE=y -# CONFIG_SFC is not set -# CONFIG_SFC_FALCON is not set -CONFIG_NET_VENDOR_SMSC=y -# CONFIG_EPIC100 is not set -# CONFIG_SMSC911X is not set -# CONFIG_SMSC9420 is not set -CONFIG_NET_VENDOR_SOCIONEXT=y -CONFIG_NET_VENDOR_STMICRO=y -CONFIG_STMMAC_ETH=m -# CONFIG_STMMAC_SELFTESTS is not set -CONFIG_STMMAC_PLATFORM=m -# CONFIG_DWMAC_DWC_QOS_ETH is not set -CONFIG_DWMAC_GENERIC=m -CONFIG_DWMAC_SUNXI=m -CONFIG_DWMAC_SUN8I=m -# CONFIG_DWMAC_INTEL_PLAT is not set -# CONFIG_DWMAC_LOONGSON is not set -# CONFIG_STMMAC_PCI is not set -CONFIG_NET_VENDOR_SUN=y -# CONFIG_HAPPYMEAL is not set -# CONFIG_SUNGEM is not set -# CONFIG_CASSINI is not set -# CONFIG_NIU is not set -CONFIG_NET_VENDOR_SYNOPSYS=y -# CONFIG_DWC_XLGMAC is not set -CONFIG_NET_VENDOR_TEHUTI=y -# CONFIG_TEHUTI is not set -CONFIG_NET_VENDOR_TI=y -# CONFIG_TI_CPSW_PHY_SEL is not set -# CONFIG_TLAN is not set -CONFIG_NET_VENDOR_VERTEXCOM=y -# CONFIG_MSE102X is not set -CONFIG_NET_VENDOR_VIA=y -# CONFIG_VIA_RHINE is not set -# CONFIG_VIA_VELOCITY is not set -CONFIG_NET_VENDOR_WIZNET=y -# CONFIG_WIZNET_W5100 is not set -# CONFIG_WIZNET_W5300 is not set -CONFIG_NET_VENDOR_XILINX=y -# CONFIG_XILINX_EMACLITE is not set -# CONFIG_XILINX_AXI_EMAC is not set -# CONFIG_XILINX_LL_TEMAC is not set -# CONFIG_FDDI is not set -# CONFIG_HIPPI is not set -CONFIG_PHYLINK=y -CONFIG_PHYLIB=y -CONFIG_SWPHY=y -CONFIG_FIXED_PHY=y -# CONFIG_SFP is not set - -# -# MII PHY device drivers -# -# CONFIG_AMD_PHY is not set -# CONFIG_ADIN_PHY is not set -# CONFIG_ADIN1100_PHY is not set -# CONFIG_AQUANTIA_PHY is not set -# CONFIG_AX88796B_PHY is not set -# CONFIG_BROADCOM_PHY is not set -# CONFIG_BCM54140_PHY is not set -# CONFIG_BCM7XXX_PHY is not set -# CONFIG_BCM84881_PHY is not set -# CONFIG_BCM87XX_PHY is not set -# CONFIG_CICADA_PHY is not set -# CONFIG_CORTINA_PHY is not set -# CONFIG_DAVICOM_PHY is not set -# CONFIG_ICPLUS_PHY is not set -# CONFIG_LXT_PHY is not set -# CONFIG_INTEL_XWAY_PHY is not set -# CONFIG_LSI_ET1011C_PHY is not set -# CONFIG_MARVELL_PHY is not set -# CONFIG_MARVELL_10G_PHY is not set -# CONFIG_MARVELL_88X2222_PHY is not set -# CONFIG_MAXLINEAR_GPHY is not set -# CONFIG_MEDIATEK_GE_PHY is not set -# CONFIG_MICREL_PHY is not set -# CONFIG_MICROCHIP_PHY is not set -# CONFIG_MICROCHIP_T1_PHY is not set -CONFIG_MICROSEMI_PHY=y -# CONFIG_MOTORCOMM_PHY is not set -# CONFIG_NATIONAL_PHY is not set -# CONFIG_NXP_C45_TJA11XX_PHY is not set -# CONFIG_NXP_TJA11XX_PHY is not set -# CONFIG_NCN26000_PHY is not set -# CONFIG_AT803X_PHY is not set -# CONFIG_QSEMI_PHY is not set -CONFIG_REALTEK_PHY=y -# CONFIG_RENESAS_PHY is not set -# CONFIG_ROCKCHIP_PHY is not set -# CONFIG_SMSC_PHY is not set -# CONFIG_STE10XP is not set -# CONFIG_TERANETICS_PHY is not set -# CONFIG_DP83822_PHY is not set -# CONFIG_DP83TC811_PHY is not set -# CONFIG_DP83848_PHY is not set -# CONFIG_DP83867_PHY is not set -# CONFIG_DP83869_PHY is not set -# CONFIG_DP83TD510_PHY is not set -# CONFIG_VITESSE_PHY is not set -# CONFIG_XILINX_GMII2RGMII is not set -# CONFIG_MICREL_KS8995MA is not set -# CONFIG_PSE_CONTROLLER is not set -CONFIG_MDIO_DEVICE=y -CONFIG_MDIO_BUS=y -CONFIG_FWNODE_MDIO=y -CONFIG_OF_MDIO=y -CONFIG_MDIO_DEVRES=y -# CONFIG_MDIO_SUN4I is not set -# CONFIG_MDIO_BITBANG is not set -# CONFIG_MDIO_BCM_UNIMAC is not set -# CONFIG_MDIO_HISI_FEMAC is not set -# CONFIG_MDIO_MVUSB is not set -# CONFIG_MDIO_MSCC_MIIM is not set -# CONFIG_MDIO_OCTEON is not set -# CONFIG_MDIO_IPQ4019 is not set -# CONFIG_MDIO_IPQ8064 is not set -# CONFIG_MDIO_THUNDER is not set - -# -# MDIO Multiplexers -# -CONFIG_MDIO_BUS_MUX=m -# CONFIG_MDIO_BUS_MUX_GPIO is not set -# CONFIG_MDIO_BUS_MUX_MULTIPLEXER is not set -# CONFIG_MDIO_BUS_MUX_MMIOREG is not set - -# -# PCS device drivers -# -CONFIG_PCS_XPCS=m -# end of PCS device drivers - -# CONFIG_PPP is not set -# CONFIG_SLIP is not set -CONFIG_USB_NET_DRIVERS=y -# CONFIG_USB_CATC is not set -# CONFIG_USB_KAWETH is not set -# CONFIG_USB_PEGASUS is not set -# CONFIG_USB_RTL8150 is not set -# CONFIG_USB_RTL8152 is not set -# CONFIG_USB_LAN78XX is not set -# CONFIG_USB_USBNET is not set -# CONFIG_USB_IPHETH is not set -CONFIG_WLAN=y -CONFIG_WLAN_VENDOR_ADMTEK=y -CONFIG_WLAN_VENDOR_ATH=y -# CONFIG_ATH_DEBUG is not set -# CONFIG_ATH5K_PCI is not set -CONFIG_WLAN_VENDOR_ATMEL=y -CONFIG_WLAN_VENDOR_BROADCOM=y -CONFIG_WLAN_VENDOR_CISCO=y -CONFIG_WLAN_VENDOR_INTEL=y -CONFIG_WLAN_VENDOR_INTERSIL=y -# CONFIG_HOSTAP is not set -CONFIG_WLAN_VENDOR_MARVELL=y -CONFIG_WLAN_VENDOR_MEDIATEK=y -CONFIG_WLAN_VENDOR_MICROCHIP=y -CONFIG_WLAN_VENDOR_PURELIFI=y -CONFIG_WLAN_VENDOR_RALINK=y -CONFIG_WLAN_VENDOR_REALTEK=y -CONFIG_WLAN_VENDOR_RSI=y -CONFIG_WLAN_VENDOR_SILABS=y -CONFIG_WLAN_VENDOR_ST=y -CONFIG_WLAN_VENDOR_TI=y -CONFIG_WLAN_VENDOR_ZYDAS=y -CONFIG_WLAN_VENDOR_QUANTENNA=y -# CONFIG_WAN is not set - -# -# Wireless WAN -# -# CONFIG_WWAN is not set -# end of Wireless WAN - -# CONFIG_VMXNET3 is not set -# CONFIG_NETDEVSIM is not set -CONFIG_NET_FAILOVER=y -# CONFIG_ISDN is not set - -# -# Input device support -# -CONFIG_INPUT=y -# CONFIG_INPUT_FF_MEMLESS is not set -# CONFIG_INPUT_SPARSEKMAP is not set -# CONFIG_INPUT_MATRIXKMAP is not set -CONFIG_INPUT_VIVALDIFMAP=y - -# -# Userland interfaces -# -CONFIG_INPUT_MOUSEDEV=y -# CONFIG_INPUT_MOUSEDEV_PSAUX is not set -CONFIG_INPUT_MOUSEDEV_SCREEN_X=1024 -CONFIG_INPUT_MOUSEDEV_SCREEN_Y=768 -# CONFIG_INPUT_JOYDEV is not set -# CONFIG_INPUT_EVDEV is not set -# CONFIG_INPUT_EVBUG is not set - -# -# Input Device Drivers -# -CONFIG_INPUT_KEYBOARD=y -# CONFIG_KEYBOARD_ADC is not set -# CONFIG_KEYBOARD_ADP5588 is not set -# CONFIG_KEYBOARD_ADP5589 is not set -CONFIG_KEYBOARD_ATKBD=y -# CONFIG_KEYBOARD_QT1050 is not set -# CONFIG_KEYBOARD_QT1070 is not set -# CONFIG_KEYBOARD_QT2160 is not set -# CONFIG_KEYBOARD_DLINK_DIR685 is not set -# CONFIG_KEYBOARD_LKKBD is not set -# CONFIG_KEYBOARD_GPIO is not set -# CONFIG_KEYBOARD_GPIO_POLLED is not set -# CONFIG_KEYBOARD_TCA6416 is not set -# CONFIG_KEYBOARD_TCA8418 is not set -# CONFIG_KEYBOARD_MATRIX is not set -# CONFIG_KEYBOARD_LM8333 is not set -# CONFIG_KEYBOARD_MAX7359 is not set -# CONFIG_KEYBOARD_MCS is not set -# CONFIG_KEYBOARD_MPR121 is not set -# CONFIG_KEYBOARD_NEWTON is not set -# CONFIG_KEYBOARD_OPENCORES is not set -# CONFIG_KEYBOARD_PINEPHONE is not set -# CONFIG_KEYBOARD_SAMSUNG is not set -# CONFIG_KEYBOARD_GOLDFISH_EVENTS is not set -# CONFIG_KEYBOARD_STOWAWAY is not set -# CONFIG_KEYBOARD_SUNKBD is not set -CONFIG_KEYBOARD_SUN4I_LRADC=m -# CONFIG_KEYBOARD_OMAP4 is not set -# CONFIG_KEYBOARD_XTKBD is not set -# CONFIG_KEYBOARD_CAP11XX is not set -# CONFIG_KEYBOARD_BCM is not set -# CONFIG_KEYBOARD_CYPRESS_SF is not set -CONFIG_INPUT_MOUSE=y -CONFIG_MOUSE_PS2=y -CONFIG_MOUSE_PS2_ALPS=y -CONFIG_MOUSE_PS2_BYD=y -CONFIG_MOUSE_PS2_LOGIPS2PP=y -CONFIG_MOUSE_PS2_SYNAPTICS=y -CONFIG_MOUSE_PS2_SYNAPTICS_SMBUS=y -CONFIG_MOUSE_PS2_CYPRESS=y -CONFIG_MOUSE_PS2_TRACKPOINT=y -# CONFIG_MOUSE_PS2_ELANTECH is not set -# CONFIG_MOUSE_PS2_SENTELIC is not set -# CONFIG_MOUSE_PS2_TOUCHKIT is not set -CONFIG_MOUSE_PS2_FOCALTECH=y -CONFIG_MOUSE_PS2_SMBUS=y -# CONFIG_MOUSE_SERIAL is not set -# CONFIG_MOUSE_APPLETOUCH is not set -# CONFIG_MOUSE_BCM5974 is not set -# CONFIG_MOUSE_CYAPA is not set -# CONFIG_MOUSE_ELAN_I2C is not set -# CONFIG_MOUSE_VSXXXAA is not set -# CONFIG_MOUSE_GPIO is not set -# CONFIG_MOUSE_SYNAPTICS_I2C is not set -# CONFIG_MOUSE_SYNAPTICS_USB is not set -# CONFIG_INPUT_JOYSTICK is not set -# CONFIG_INPUT_TABLET is not set -# CONFIG_INPUT_TOUCHSCREEN is not set -# CONFIG_INPUT_MISC is not set -# CONFIG_RMI4_CORE is not set - -# -# Hardware I/O ports -# -CONFIG_SERIO=y -CONFIG_SERIO_SERPORT=y -# CONFIG_SERIO_PCIPS2 is not set -CONFIG_SERIO_LIBPS2=y -# CONFIG_SERIO_RAW is not set -# CONFIG_SERIO_ALTERA_PS2 is not set -# CONFIG_SERIO_PS2MULT is not set -# CONFIG_SERIO_ARC_PS2 is not set -# CONFIG_SERIO_APBPS2 is not set -# CONFIG_SERIO_SUN4I_PS2 is not set -# CONFIG_SERIO_GPIO_PS2 is not set -# CONFIG_USERIO is not set -# CONFIG_GAMEPORT is not set -# end of Hardware I/O ports -# end of Input device support - -# -# Character devices -# -CONFIG_TTY=y -CONFIG_VT=y -CONFIG_CONSOLE_TRANSLATIONS=y -CONFIG_VT_CONSOLE=y -CONFIG_HW_CONSOLE=y -CONFIG_VT_HW_CONSOLE_BINDING=y -CONFIG_UNIX98_PTYS=y -CONFIG_LEGACY_PTYS=y -CONFIG_LEGACY_PTY_COUNT=256 -CONFIG_LEGACY_TIOCSTI=y -CONFIG_LDISC_AUTOLOAD=y - -# -# Serial drivers -# -CONFIG_SERIAL_EARLYCON=y -CONFIG_SERIAL_8250=y -CONFIG_SERIAL_8250_DEPRECATED_OPTIONS=y -CONFIG_SERIAL_8250_16550A_VARIANTS=y -# CONFIG_SERIAL_8250_FINTEK is not set -CONFIG_SERIAL_8250_CONSOLE=y -CONFIG_SERIAL_8250_DMA=y -CONFIG_SERIAL_8250_PCILIB=y -CONFIG_SERIAL_8250_PCI=y -CONFIG_SERIAL_8250_EXAR=y -CONFIG_SERIAL_8250_NR_UARTS=4 -CONFIG_SERIAL_8250_RUNTIME_UARTS=4 -# CONFIG_SERIAL_8250_EXTENDED is not set -# CONFIG_SERIAL_8250_PCI1XXXX is not set -CONFIG_SERIAL_8250_DWLIB=y -CONFIG_SERIAL_8250_DW=y -# CONFIG_SERIAL_8250_EM is not set -# CONFIG_SERIAL_8250_RT288X is not set -CONFIG_SERIAL_8250_PERICOM=y -CONFIG_SERIAL_OF_PLATFORM=y - -# -# Non-8250 serial port support -# -# CONFIG_SERIAL_EARLYCON_SEMIHOST is not set -# CONFIG_SERIAL_MAX3100 is not set -# CONFIG_SERIAL_MAX310X is not set -# CONFIG_SERIAL_UARTLITE is not set -CONFIG_SERIAL_SH_SCI=y -CONFIG_SERIAL_SH_SCI_NR_UARTS=18 -CONFIG_SERIAL_SH_SCI_CONSOLE=y -CONFIG_SERIAL_SH_SCI_EARLYCON=y -CONFIG_SERIAL_SH_SCI_DMA=y -CONFIG_SERIAL_CORE=y -CONFIG_SERIAL_CORE_CONSOLE=y -# CONFIG_SERIAL_JSM is not set -CONFIG_SERIAL_SIFIVE=y -CONFIG_SERIAL_SIFIVE_CONSOLE=y -# CONFIG_SERIAL_SCCNXP is not set -# CONFIG_SERIAL_SC16IS7XX is not set -# CONFIG_SERIAL_ALTERA_JTAGUART is not set -# CONFIG_SERIAL_ALTERA_UART is not set -# CONFIG_SERIAL_XILINX_PS_UART is not set -# CONFIG_SERIAL_ARC is not set -# CONFIG_SERIAL_RP2 is not set -# CONFIG_SERIAL_FSL_LPUART is not set -# CONFIG_SERIAL_FSL_LINFLEXUART is not set -# CONFIG_SERIAL_CONEXANT_DIGICOLOR is not set -# CONFIG_SERIAL_SPRD is not set -# end of Serial drivers - -CONFIG_SERIAL_MCTRL_GPIO=y -# CONFIG_SERIAL_NONSTANDARD is not set -# CONFIG_GOLDFISH_TTY is not set -# CONFIG_N_GSM is not set -# CONFIG_NOZOMI is not set -# CONFIG_NULL_TTY is not set -CONFIG_HVC_DRIVER=y -# CONFIG_RPMSG_TTY is not set -# CONFIG_SERIAL_DEV_BUS is not set -# CONFIG_TTY_PRINTK is not set -CONFIG_VIRTIO_CONSOLE=y -# CONFIG_IPMI_HANDLER is not set -CONFIG_HW_RANDOM=y -# CONFIG_HW_RANDOM_TIMERIOMEM is not set -# CONFIG_HW_RANDOM_BA431 is not set -CONFIG_HW_RANDOM_VIRTIO=y -CONFIG_HW_RANDOM_POLARFIRE_SOC=y -# CONFIG_HW_RANDOM_CCTRNG is not set -# CONFIG_HW_RANDOM_XIPHERA is not set -# CONFIG_HW_RANDOM_JH7110 is not set -# CONFIG_APPLICOM is not set -CONFIG_DEVMEM=y -CONFIG_DEVPORT=y -# CONFIG_TCG_TPM is not set -# CONFIG_XILLYBUS is not set -# CONFIG_XILLYUSB is not set -# end of Character devices - -# -# I2C support -# -CONFIG_I2C=y -CONFIG_I2C_BOARDINFO=y -CONFIG_I2C_COMPAT=y -# CONFIG_I2C_CHARDEV is not set -CONFIG_I2C_MUX=m - -# -# Multiplexer I2C Chip support -# -# CONFIG_I2C_ARB_GPIO_CHALLENGE is not set -# CONFIG_I2C_MUX_GPIO is not set -# CONFIG_I2C_MUX_GPMUX is not set -# CONFIG_I2C_MUX_LTC4306 is not set -# CONFIG_I2C_MUX_PCA9541 is not set -# CONFIG_I2C_MUX_PCA954x is not set -# CONFIG_I2C_MUX_PINCTRL is not set -# CONFIG_I2C_MUX_REG is not set -# CONFIG_I2C_DEMUX_PINCTRL is not set -# CONFIG_I2C_MUX_MLXCPLD is not set -# end of Multiplexer I2C Chip support - -CONFIG_I2C_HELPER_AUTO=y - -# -# I2C Hardware Bus support -# - -# -# PC SMBus host controller drivers -# -# CONFIG_I2C_ALI1535 is not set -# CONFIG_I2C_ALI1563 is not set -# CONFIG_I2C_ALI15X3 is not set -# CONFIG_I2C_AMD756 is not set -# CONFIG_I2C_AMD8111 is not set -# CONFIG_I2C_I801 is not set -# CONFIG_I2C_ISCH is not set -# CONFIG_I2C_PIIX4 is not set -# CONFIG_I2C_NFORCE2 is not set -# CONFIG_I2C_NVIDIA_GPU is not set -# CONFIG_I2C_SIS5595 is not set -# CONFIG_I2C_SIS630 is not set -# CONFIG_I2C_SIS96X is not set -# CONFIG_I2C_VIA is not set -# CONFIG_I2C_VIAPRO is not set - -# -# I2C system bus drivers (mostly embedded / system-on-chip) -# -# CONFIG_I2C_CBUS_GPIO is not set -# CONFIG_I2C_DESIGNWARE_PLATFORM is not set -# CONFIG_I2C_DESIGNWARE_PCI is not set -# CONFIG_I2C_EMEV2 is not set -# CONFIG_I2C_GPIO is not set -CONFIG_I2C_MICROCHIP_CORE=y -CONFIG_I2C_MV64XXX=m -# CONFIG_I2C_OCORES is not set -# CONFIG_I2C_PCA_PLATFORM is not set -# CONFIG_I2C_RIIC is not set -# CONFIG_I2C_RK3X is not set -# CONFIG_I2C_RZV2M is not set -# CONFIG_I2C_SH_MOBILE is not set -# CONFIG_I2C_SIMTEC is not set -# CONFIG_I2C_XILINX is not set -# CONFIG_I2C_RCAR is not set - -# -# External I2C/SMBus adapter drivers -# -# CONFIG_I2C_DIOLAN_U2C is not set -# CONFIG_I2C_CP2615 is not set -# CONFIG_I2C_PCI1XXXX is not set -# CONFIG_I2C_ROBOTFUZZ_OSIF is not set -# CONFIG_I2C_TAOS_EVM is not set -# CONFIG_I2C_TINY_USB is not set - -# -# Other I2C/SMBus bus drivers -# -# CONFIG_I2C_VIRTIO is not set -# end of I2C Hardware Bus support - -# CONFIG_I2C_STUB is not set -# CONFIG_I2C_SLAVE is not set -# CONFIG_I2C_DEBUG_CORE is not set -# CONFIG_I2C_DEBUG_ALGO is not set -# CONFIG_I2C_DEBUG_BUS is not set -# end of I2C support - -# CONFIG_I3C is not set -CONFIG_SPI=y -# CONFIG_SPI_DEBUG is not set -CONFIG_SPI_MASTER=y -# CONFIG_SPI_MEM is not set - -# -# SPI Master Controller Drivers -# -# CONFIG_SPI_ALTERA is not set -# CONFIG_SPI_AXI_SPI_ENGINE is not set -# CONFIG_SPI_BITBANG is not set -# CONFIG_SPI_CADENCE is not set -# CONFIG_SPI_DESIGNWARE is not set -# CONFIG_SPI_NXP_FLEXSPI is not set -# CONFIG_SPI_GPIO is not set -# CONFIG_SPI_FSL_SPI is not set -CONFIG_SPI_MICROCHIP_CORE=y -CONFIG_SPI_MICROCHIP_CORE_QSPI=y -# CONFIG_SPI_OC_TINY is not set -# CONFIG_SPI_PCI1XXXX is not set -# CONFIG_SPI_PXA2XX is not set -# CONFIG_SPI_ROCKCHIP is not set -# CONFIG_SPI_RSPI is not set -# CONFIG_SPI_SC18IS602 is not set -# CONFIG_SPI_SH_MSIOF is not set -# CONFIG_SPI_SH_HSPI is not set -CONFIG_SPI_SIFIVE=y -# CONFIG_SPI_SUN4I is not set -CONFIG_SPI_SUN6I=y -# CONFIG_SPI_MXIC is not set -# CONFIG_SPI_XCOMM is not set -# CONFIG_SPI_XILINX is not set -# CONFIG_SPI_ZYNQMP_GQSPI is not set -# CONFIG_SPI_AMD is not set - -# -# SPI Multiplexer support -# -# CONFIG_SPI_MUX is not set - -# -# SPI Protocol Masters -# -CONFIG_SPI_SPIDEV=m -# CONFIG_SPI_LOOPBACK_TEST is not set -# CONFIG_SPI_TLE62X0 is not set -# CONFIG_SPI_SLAVE is not set -CONFIG_SPI_DYNAMIC=y -# CONFIG_SPMI is not set -# CONFIG_HSI is not set -# CONFIG_PPS is not set - -# -# PTP clock support -# -# CONFIG_PTP_1588_CLOCK is not set -CONFIG_PTP_1588_CLOCK_OPTIONAL=y - -# -# Enable PHYLIB and NETWORK_PHY_TIMESTAMPING to see the additional clocks. -# -# end of PTP clock support - -CONFIG_PINCTRL=y -CONFIG_GENERIC_PINCTRL_GROUPS=y -CONFIG_PINMUX=y -CONFIG_GENERIC_PINMUX_FUNCTIONS=y -CONFIG_PINCONF=y -CONFIG_GENERIC_PINCONF=y -# CONFIG_DEBUG_PINCTRL is not set -# CONFIG_PINCTRL_CY8C95X0 is not set -# CONFIG_PINCTRL_MCP23S08 is not set -# CONFIG_PINCTRL_MICROCHIP_SGPIO is not set -# CONFIG_PINCTRL_OCELOT is not set -# CONFIG_PINCTRL_SINGLE is not set -# CONFIG_PINCTRL_STMFX is not set -# CONFIG_PINCTRL_SX150X is not set - -# -# Renesas pinctrl drivers -# -CONFIG_PINCTRL_RENESAS=y -CONFIG_PINCTRL_RZG2L=y -# end of Renesas pinctrl drivers - -CONFIG_PINCTRL_STARFIVE_JH7100=y -CONFIG_PINCTRL_STARFIVE_JH7110=y -CONFIG_PINCTRL_STARFIVE_JH7110_SYS=y -CONFIG_PINCTRL_STARFIVE_JH7110_AON=y -CONFIG_PINCTRL_SUNXI=y -# CONFIG_PINCTRL_SUN4I_A10 is not set -# CONFIG_PINCTRL_SUN5I is not set -# CONFIG_PINCTRL_SUN6I_A31 is not set -# CONFIG_PINCTRL_SUN6I_A31_R is not set -# CONFIG_PINCTRL_SUN8I_A23 is not set -# CONFIG_PINCTRL_SUN8I_A33 is not set -# CONFIG_PINCTRL_SUN8I_A83T is not set -# CONFIG_PINCTRL_SUN8I_A83T_R is not set -# CONFIG_PINCTRL_SUN8I_A23_R is not set -# CONFIG_PINCTRL_SUN8I_H3 is not set -# CONFIG_PINCTRL_SUN8I_H3_R is not set -# CONFIG_PINCTRL_SUN8I_V3S is not set -# CONFIG_PINCTRL_SUN9I_A80 is not set -# CONFIG_PINCTRL_SUN9I_A80_R is not set -CONFIG_PINCTRL_SUN20I_D1=y -# CONFIG_PINCTRL_SUN50I_A64 is not set -# CONFIG_PINCTRL_SUN50I_A64_R is not set -# CONFIG_PINCTRL_SUN50I_A100 is not set -# CONFIG_PINCTRL_SUN50I_A100_R is not set -# CONFIG_PINCTRL_SUN50I_H5 is not set -# CONFIG_PINCTRL_SUN50I_H6 is not set -# CONFIG_PINCTRL_SUN50I_H6_R is not set -# CONFIG_PINCTRL_SUN50I_H616 is not set -# CONFIG_PINCTRL_SUN50I_H616_R is not set -CONFIG_GPIOLIB=y -CONFIG_GPIOLIB_FASTPATH_LIMIT=512 -CONFIG_OF_GPIO=y -CONFIG_GPIOLIB_IRQCHIP=y -# CONFIG_DEBUG_GPIO is not set -CONFIG_GPIO_SYSFS=y -CONFIG_GPIO_CDEV=y -CONFIG_GPIO_CDEV_V1=y -CONFIG_GPIO_GENERIC=y - -# -# Memory mapped GPIO drivers -# -# CONFIG_GPIO_74XX_MMIO is not set -# CONFIG_GPIO_ALTERA is not set -# CONFIG_GPIO_CADENCE is not set -# CONFIG_GPIO_DWAPB is not set -# CONFIG_GPIO_EXAR is not set -# CONFIG_GPIO_FTGPIO010 is not set -# CONFIG_GPIO_GENERIC_PLATFORM is not set -# CONFIG_GPIO_GRGPIO is not set -# CONFIG_GPIO_HLWD is not set -# CONFIG_GPIO_LOGICVC is not set -# CONFIG_GPIO_MB86S7X is not set -# CONFIG_GPIO_RCAR is not set -CONFIG_GPIO_SIFIVE=y -# CONFIG_GPIO_SYSCON is not set -# CONFIG_GPIO_XILINX is not set -# CONFIG_GPIO_AMD_FCH is not set -# end of Memory mapped GPIO drivers - -# -# I2C GPIO expanders -# -# CONFIG_GPIO_ADNP is not set -# CONFIG_GPIO_GW_PLD is not set -# CONFIG_GPIO_MAX7300 is not set -# CONFIG_GPIO_MAX732X is not set -# CONFIG_GPIO_PCA953X is not set -# CONFIG_GPIO_PCA9570 is not set -# CONFIG_GPIO_PCF857X is not set -# CONFIG_GPIO_TPIC2810 is not set -# end of I2C GPIO expanders - -# -# MFD GPIO expanders -# -# end of MFD GPIO expanders - -# -# PCI GPIO expanders -# -# CONFIG_GPIO_BT8XX is not set -# CONFIG_GPIO_PCI_IDIO_16 is not set -# CONFIG_GPIO_PCIE_IDIO_24 is not set -# CONFIG_GPIO_RDC321X is not set -# end of PCI GPIO expanders - -# -# SPI GPIO expanders -# -# CONFIG_GPIO_74X164 is not set -# CONFIG_GPIO_MAX3191X is not set -# CONFIG_GPIO_MAX7301 is not set -# CONFIG_GPIO_MC33880 is not set -# CONFIG_GPIO_PISOSR is not set -# CONFIG_GPIO_XRA1403 is not set -# end of SPI GPIO expanders - -# -# USB GPIO expanders -# -# end of USB GPIO expanders - -# -# Virtual GPIO drivers -# -# CONFIG_GPIO_AGGREGATOR is not set -# CONFIG_GPIO_LATCH is not set -# CONFIG_GPIO_MOCKUP is not set -# CONFIG_GPIO_VIRTIO is not set -# CONFIG_GPIO_SIM is not set -# end of Virtual GPIO drivers - -# CONFIG_W1 is not set -CONFIG_POWER_RESET=y -# CONFIG_POWER_RESET_GPIO is not set -# CONFIG_POWER_RESET_GPIO_RESTART is not set -# CONFIG_POWER_RESET_LTC2952 is not set -# CONFIG_POWER_RESET_REGULATOR is not set -# CONFIG_POWER_RESET_RESTART is not set -CONFIG_POWER_RESET_SYSCON=y -CONFIG_POWER_RESET_SYSCON_POWEROFF=y -# CONFIG_SYSCON_REBOOT_MODE is not set -# CONFIG_NVMEM_REBOOT_MODE is not set -CONFIG_POWER_SUPPLY=y -# CONFIG_POWER_SUPPLY_DEBUG is not set -CONFIG_POWER_SUPPLY_HWMON=y -# CONFIG_GENERIC_ADC_BATTERY is not set -# CONFIG_IP5XXX_POWER is not set -# CONFIG_TEST_POWER is not set -# CONFIG_CHARGER_ADP5061 is not set -# CONFIG_BATTERY_CW2015 is not set -# CONFIG_BATTERY_DS2780 is not set -# CONFIG_BATTERY_DS2781 is not set -# CONFIG_BATTERY_DS2782 is not set -# CONFIG_BATTERY_SAMSUNG_SDI is not set -# CONFIG_BATTERY_SBS is not set -# CONFIG_CHARGER_SBS is not set -# CONFIG_MANAGER_SBS is not set -# CONFIG_BATTERY_BQ27XXX is not set -# CONFIG_BATTERY_MAX17040 is not set -# CONFIG_BATTERY_MAX17042 is not set -# CONFIG_CHARGER_ISP1704 is not set -# CONFIG_CHARGER_MAX8903 is not set -# CONFIG_CHARGER_LP8727 is not set -# CONFIG_CHARGER_GPIO is not set -# CONFIG_CHARGER_MANAGER is not set -# CONFIG_CHARGER_LT3651 is not set -# CONFIG_CHARGER_LTC4162L is not set -# CONFIG_CHARGER_DETECTOR_MAX14656 is not set -# CONFIG_CHARGER_MAX77976 is not set -# CONFIG_CHARGER_BQ2415X is not set -# CONFIG_CHARGER_BQ24190 is not set -# CONFIG_CHARGER_BQ24257 is not set -# CONFIG_CHARGER_BQ24735 is not set -# CONFIG_CHARGER_BQ2515X is not set -# CONFIG_CHARGER_BQ25890 is not set -# CONFIG_CHARGER_BQ25980 is not set -# CONFIG_CHARGER_BQ256XX is not set -# CONFIG_CHARGER_SMB347 is not set -# CONFIG_BATTERY_GAUGE_LTC2941 is not set -# CONFIG_BATTERY_GOLDFISH is not set -# CONFIG_BATTERY_RT5033 is not set -# CONFIG_CHARGER_RT9455 is not set -# CONFIG_CHARGER_RT9467 is not set -# CONFIG_CHARGER_RT9471 is not set -# CONFIG_CHARGER_UCS1002 is not set -# CONFIG_CHARGER_BD99954 is not set -# CONFIG_BATTERY_UG3105 is not set -CONFIG_HWMON=y -# CONFIG_HWMON_DEBUG_CHIP is not set - -# -# Native drivers -# -# CONFIG_SENSORS_AD7314 is not set -# CONFIG_SENSORS_AD7414 is not set -# CONFIG_SENSORS_AD7418 is not set -# CONFIG_SENSORS_ADM1021 is not set -# CONFIG_SENSORS_ADM1025 is not set -# CONFIG_SENSORS_ADM1026 is not set -# CONFIG_SENSORS_ADM1029 is not set -# CONFIG_SENSORS_ADM1031 is not set -# CONFIG_SENSORS_ADM1177 is not set -# CONFIG_SENSORS_ADM9240 is not set -# CONFIG_SENSORS_ADT7310 is not set -# CONFIG_SENSORS_ADT7410 is not set -# CONFIG_SENSORS_ADT7411 is not set -# CONFIG_SENSORS_ADT7462 is not set -# CONFIG_SENSORS_ADT7470 is not set -# CONFIG_SENSORS_ADT7475 is not set -# CONFIG_SENSORS_AHT10 is not set -# CONFIG_SENSORS_AQUACOMPUTER_D5NEXT is not set -# CONFIG_SENSORS_AS370 is not set -# CONFIG_SENSORS_ASC7621 is not set -# CONFIG_SENSORS_AXI_FAN_CONTROL is not set -# CONFIG_SENSORS_ATXP1 is not set -# CONFIG_SENSORS_CORSAIR_CPRO is not set -# CONFIG_SENSORS_CORSAIR_PSU is not set -# CONFIG_SENSORS_DRIVETEMP is not set -# CONFIG_SENSORS_DS620 is not set -# CONFIG_SENSORS_DS1621 is not set -# CONFIG_SENSORS_I5K_AMB is not set -# CONFIG_SENSORS_F71805F is not set -# CONFIG_SENSORS_F71882FG is not set -# CONFIG_SENSORS_F75375S is not set -# CONFIG_SENSORS_FTSTEUTATES is not set -# CONFIG_SENSORS_GL518SM is not set -# CONFIG_SENSORS_GL520SM is not set -# CONFIG_SENSORS_G760A is not set -# CONFIG_SENSORS_G762 is not set -# CONFIG_SENSORS_GPIO_FAN is not set -# CONFIG_SENSORS_HIH6130 is not set -# CONFIG_SENSORS_IIO_HWMON is not set -# CONFIG_SENSORS_IT87 is not set -# CONFIG_SENSORS_JC42 is not set -# CONFIG_SENSORS_POWR1220 is not set -# CONFIG_SENSORS_LINEAGE is not set -# CONFIG_SENSORS_LTC2945 is not set -# CONFIG_SENSORS_LTC2947_I2C is not set -# CONFIG_SENSORS_LTC2947_SPI is not set -# CONFIG_SENSORS_LTC2990 is not set -# CONFIG_SENSORS_LTC2992 is not set -# CONFIG_SENSORS_LTC4151 is not set -# CONFIG_SENSORS_LTC4215 is not set -# CONFIG_SENSORS_LTC4222 is not set -# CONFIG_SENSORS_LTC4245 is not set -# CONFIG_SENSORS_LTC4260 is not set -# CONFIG_SENSORS_LTC4261 is not set -# CONFIG_SENSORS_MAX1111 is not set -# CONFIG_SENSORS_MAX127 is not set -# CONFIG_SENSORS_MAX16065 is not set -# CONFIG_SENSORS_MAX1619 is not set -# CONFIG_SENSORS_MAX1668 is not set -# CONFIG_SENSORS_MAX197 is not set -# CONFIG_SENSORS_MAX31722 is not set -# CONFIG_SENSORS_MAX31730 is not set -# CONFIG_SENSORS_MAX31760 is not set -# CONFIG_SENSORS_MAX6620 is not set -# CONFIG_SENSORS_MAX6621 is not set -# CONFIG_SENSORS_MAX6639 is not set -# CONFIG_SENSORS_MAX6642 is not set -# CONFIG_SENSORS_MAX6650 is not set -# CONFIG_SENSORS_MAX6697 is not set -# CONFIG_SENSORS_MAX31790 is not set -# CONFIG_SENSORS_MC34VR500 is not set -# CONFIG_SENSORS_MCP3021 is not set -# CONFIG_SENSORS_TC654 is not set -# CONFIG_SENSORS_TPS23861 is not set -# CONFIG_SENSORS_MR75203 is not set -# CONFIG_SENSORS_ADCXX is not set -# CONFIG_SENSORS_LM63 is not set -# CONFIG_SENSORS_LM70 is not set -# CONFIG_SENSORS_LM73 is not set -# CONFIG_SENSORS_LM75 is not set -# CONFIG_SENSORS_LM77 is not set -# CONFIG_SENSORS_LM78 is not set -# CONFIG_SENSORS_LM80 is not set -# CONFIG_SENSORS_LM83 is not set -# CONFIG_SENSORS_LM85 is not set -# CONFIG_SENSORS_LM87 is not set -# CONFIG_SENSORS_LM90 is not set -# CONFIG_SENSORS_LM92 is not set -# CONFIG_SENSORS_LM93 is not set -# CONFIG_SENSORS_LM95234 is not set -# CONFIG_SENSORS_LM95241 is not set -# CONFIG_SENSORS_LM95245 is not set -# CONFIG_SENSORS_PC87360 is not set -# CONFIG_SENSORS_PC87427 is not set -# CONFIG_SENSORS_NTC_THERMISTOR is not set -# CONFIG_SENSORS_NCT6683 is not set -# CONFIG_SENSORS_NCT6775_I2C is not set -# CONFIG_SENSORS_NCT7802 is not set -# CONFIG_SENSORS_NCT7904 is not set -# CONFIG_SENSORS_NPCM7XX is not set -# CONFIG_SENSORS_NZXT_KRAKEN2 is not set -# CONFIG_SENSORS_NZXT_SMART2 is not set -# CONFIG_SENSORS_OCC_P8_I2C is not set -# CONFIG_SENSORS_PCF8591 is not set -# CONFIG_PMBUS is not set -# CONFIG_SENSORS_SBTSI is not set -# CONFIG_SENSORS_SBRMI is not set -# CONFIG_SENSORS_SHT15 is not set -# CONFIG_SENSORS_SHT21 is not set -# CONFIG_SENSORS_SHT3x is not set -# CONFIG_SENSORS_SHT4x is not set -# CONFIG_SENSORS_SHTC1 is not set -# CONFIG_SENSORS_SIS5595 is not set -# CONFIG_SENSORS_DME1737 is not set -# CONFIG_SENSORS_EMC1403 is not set -# CONFIG_SENSORS_EMC2103 is not set -# CONFIG_SENSORS_EMC2305 is not set -# CONFIG_SENSORS_EMC6W201 is not set -# CONFIG_SENSORS_SMSC47M1 is not set -# CONFIG_SENSORS_SMSC47M192 is not set -# CONFIG_SENSORS_SMSC47B397 is not set -# CONFIG_SENSORS_SCH5627 is not set -# CONFIG_SENSORS_SCH5636 is not set -# CONFIG_SENSORS_STTS751 is not set -# CONFIG_SENSORS_SMM665 is not set -# CONFIG_SENSORS_ADC128D818 is not set -# CONFIG_SENSORS_ADS7828 is not set -# CONFIG_SENSORS_ADS7871 is not set -# CONFIG_SENSORS_AMC6821 is not set -# CONFIG_SENSORS_INA209 is not set -# CONFIG_SENSORS_INA2XX is not set -# CONFIG_SENSORS_INA238 is not set -# CONFIG_SENSORS_INA3221 is not set -# CONFIG_SENSORS_TC74 is not set -# CONFIG_SENSORS_THMC50 is not set -# CONFIG_SENSORS_TMP102 is not set -# CONFIG_SENSORS_TMP103 is not set -# CONFIG_SENSORS_TMP108 is not set -# CONFIG_SENSORS_TMP401 is not set -# CONFIG_SENSORS_TMP421 is not set -# CONFIG_SENSORS_TMP464 is not set -# CONFIG_SENSORS_TMP513 is not set -# CONFIG_SENSORS_VIA686A is not set -# CONFIG_SENSORS_VT1211 is not set -# CONFIG_SENSORS_VT8231 is not set -# CONFIG_SENSORS_W83773G is not set -# CONFIG_SENSORS_W83781D is not set -# CONFIG_SENSORS_W83791D is not set -# CONFIG_SENSORS_W83792D is not set -# CONFIG_SENSORS_W83793 is not set -# CONFIG_SENSORS_W83795 is not set -# CONFIG_SENSORS_W83L785TS is not set -# CONFIG_SENSORS_W83L786NG is not set -# CONFIG_SENSORS_W83627HF is not set -# CONFIG_SENSORS_W83627EHF is not set -# CONFIG_THERMAL is not set -CONFIG_WATCHDOG=y -CONFIG_WATCHDOG_CORE=y -# CONFIG_WATCHDOG_NOWAYOUT is not set -CONFIG_WATCHDOG_HANDLE_BOOT_ENABLED=y -CONFIG_WATCHDOG_OPEN_TIMEOUT=0 -# CONFIG_WATCHDOG_SYSFS is not set -# CONFIG_WATCHDOG_HRTIMER_PRETIMEOUT is not set - -# -# Watchdog Pretimeout Governors -# -# CONFIG_WATCHDOG_PRETIMEOUT_GOV is not set - -# -# Watchdog Device Drivers -# -# CONFIG_SOFT_WATCHDOG is not set -# CONFIG_GPIO_WATCHDOG is not set -# CONFIG_XILINX_WATCHDOG is not set -# CONFIG_ZIIRAVE_WATCHDOG is not set -# CONFIG_CADENCE_WATCHDOG is not set -# CONFIG_DW_WATCHDOG is not set -CONFIG_SUNXI_WATCHDOG=y -# CONFIG_MAX63XX_WATCHDOG is not set -# CONFIG_RENESAS_WDT is not set -# CONFIG_RENESAS_RZAWDT is not set -# CONFIG_RENESAS_RZN1WDT is not set -# CONFIG_RENESAS_RZG2LWDT is not set -# CONFIG_ALIM7101_WDT is not set -# CONFIG_I6300ESB_WDT is not set -# CONFIG_MEN_A21_WDT is not set - -# -# PCI-based Watchdog Cards -# -# CONFIG_PCIPCWATCHDOG is not set -# CONFIG_WDTPCI is not set - -# -# USB-based Watchdog Cards -# -# CONFIG_USBPCWATCHDOG is not set -CONFIG_SSB_POSSIBLE=y -# CONFIG_SSB is not set -CONFIG_BCMA_POSSIBLE=y -# CONFIG_BCMA is not set - -# -# Multifunction device drivers -# -# CONFIG_MFD_ACT8945A is not set -# CONFIG_MFD_SUN4I_GPADC is not set -# CONFIG_MFD_AS3711 is not set -# CONFIG_MFD_SMPRO is not set -# CONFIG_MFD_AS3722 is not set -# CONFIG_PMIC_ADP5520 is not set -# CONFIG_MFD_AAT2870_CORE is not set -# CONFIG_MFD_ATMEL_FLEXCOM is not set -# CONFIG_MFD_ATMEL_HLCDC is not set -# CONFIG_MFD_BCM590XX is not set -# CONFIG_MFD_BD9571MWV is not set -# CONFIG_MFD_AXP20X_I2C is not set -# CONFIG_MFD_MADERA is not set -# CONFIG_PMIC_DA903X is not set -# CONFIG_MFD_DA9052_SPI is not set -# CONFIG_MFD_DA9052_I2C is not set -# CONFIG_MFD_DA9055 is not set -# CONFIG_MFD_DA9062 is not set -# CONFIG_MFD_DA9063 is not set -# CONFIG_MFD_DA9150 is not set -# CONFIG_MFD_DLN2 is not set -# CONFIG_MFD_GATEWORKS_GSC is not set -# CONFIG_MFD_MC13XXX_SPI is not set -# CONFIG_MFD_MC13XXX_I2C is not set -# CONFIG_MFD_MP2629 is not set -# CONFIG_MFD_HI6421_PMIC is not set -# CONFIG_LPC_ICH is not set -# CONFIG_LPC_SCH is not set -# CONFIG_MFD_IQS62X is not set -# CONFIG_MFD_JANZ_CMODIO is not set -# CONFIG_MFD_KEMPLD is not set -# CONFIG_MFD_88PM800 is not set -# CONFIG_MFD_88PM805 is not set -# CONFIG_MFD_88PM860X is not set -# CONFIG_MFD_MAX14577 is not set -# CONFIG_MFD_MAX77620 is not set -# CONFIG_MFD_MAX77650 is not set -# CONFIG_MFD_MAX77686 is not set -# CONFIG_MFD_MAX77693 is not set -# CONFIG_MFD_MAX77714 is not set -# CONFIG_MFD_MAX77843 is not set -# CONFIG_MFD_MAX8907 is not set -# CONFIG_MFD_MAX8925 is not set -# CONFIG_MFD_MAX8997 is not set -# CONFIG_MFD_MAX8998 is not set -# CONFIG_MFD_MT6360 is not set -# CONFIG_MFD_MT6370 is not set -# CONFIG_MFD_MT6397 is not set -# CONFIG_MFD_MENF21BMC is not set -# CONFIG_MFD_OCELOT is not set -# CONFIG_EZX_PCAP is not set -# CONFIG_MFD_CPCAP is not set -# CONFIG_MFD_VIPERBOARD is not set -# CONFIG_MFD_NTXEC is not set -# CONFIG_MFD_RETU is not set -# CONFIG_MFD_PCF50633 is not set -# CONFIG_MFD_SY7636A is not set -# CONFIG_MFD_RDC321X is not set -# CONFIG_MFD_RT4831 is not set -# CONFIG_MFD_RT5033 is not set -# CONFIG_MFD_RT5120 is not set -# CONFIG_MFD_RC5T583 is not set -# CONFIG_MFD_RK808 is not set -# CONFIG_MFD_RN5T618 is not set -# CONFIG_MFD_SEC_CORE is not set -# CONFIG_MFD_SI476X_CORE is not set -# CONFIG_MFD_SM501 is not set -# CONFIG_MFD_SKY81452 is not set -# CONFIG_MFD_STMPE is not set -# CONFIG_MFD_SUN6I_PRCM is not set -CONFIG_MFD_SYSCON=y -# CONFIG_MFD_TI_AM335X_TSCADC is not set -# CONFIG_MFD_LP3943 is not set -# CONFIG_MFD_LP8788 is not set -# CONFIG_MFD_TI_LMU is not set -# CONFIG_MFD_PALMAS is not set -# CONFIG_TPS6105X is not set -# CONFIG_TPS65010 is not set -# CONFIG_TPS6507X is not set -# CONFIG_MFD_TPS65086 is not set -# CONFIG_MFD_TPS65090 is not set -# CONFIG_MFD_TPS65217 is not set -# CONFIG_MFD_TI_LP873X is not set -# CONFIG_MFD_TI_LP87565 is not set -# CONFIG_MFD_TPS65218 is not set -# CONFIG_MFD_TPS65219 is not set -# CONFIG_MFD_TPS6586X is not set -# CONFIG_MFD_TPS65910 is not set -# CONFIG_MFD_TPS65912_I2C is not set -# CONFIG_MFD_TPS65912_SPI is not set -# CONFIG_TWL4030_CORE is not set -# CONFIG_TWL6040_CORE is not set -# CONFIG_MFD_WL1273_CORE is not set -# CONFIG_MFD_LM3533 is not set -# CONFIG_MFD_TC3589X is not set -# CONFIG_MFD_TQMX86 is not set -# CONFIG_MFD_VX855 is not set -# CONFIG_MFD_LOCHNAGAR is not set -# CONFIG_MFD_ARIZONA_I2C is not set -# CONFIG_MFD_ARIZONA_SPI is not set -# CONFIG_MFD_WM8400 is not set -# CONFIG_MFD_WM831X_I2C is not set -# CONFIG_MFD_WM831X_SPI is not set -# CONFIG_MFD_WM8350_I2C is not set -# CONFIG_MFD_WM8994 is not set -# CONFIG_MFD_ROHM_BD718XX is not set -# CONFIG_MFD_ROHM_BD71828 is not set -# CONFIG_MFD_ROHM_BD957XMUF is not set -# CONFIG_MFD_STPMIC1 is not set -# CONFIG_MFD_STMFX is not set -# CONFIG_MFD_ATC260X_I2C is not set -# CONFIG_MFD_QCOM_PM8008 is not set -# CONFIG_MFD_INTEL_M10_BMC_SPI is not set -# CONFIG_MFD_RSMU_I2C is not set -# CONFIG_MFD_RSMU_SPI is not set -# end of Multifunction device drivers - -CONFIG_REGULATOR=y -# CONFIG_REGULATOR_DEBUG is not set -CONFIG_REGULATOR_FIXED_VOLTAGE=y -# CONFIG_REGULATOR_VIRTUAL_CONSUMER is not set -# CONFIG_REGULATOR_USERSPACE_CONSUMER is not set -# CONFIG_REGULATOR_88PG86X is not set -# CONFIG_REGULATOR_ACT8865 is not set -# CONFIG_REGULATOR_AD5398 is not set -# CONFIG_REGULATOR_DA9121 is not set -# CONFIG_REGULATOR_DA9210 is not set -# CONFIG_REGULATOR_DA9211 is not set -# CONFIG_REGULATOR_FAN53555 is not set -# CONFIG_REGULATOR_FAN53880 is not set -# CONFIG_REGULATOR_GPIO is not set -# CONFIG_REGULATOR_ISL9305 is not set -# CONFIG_REGULATOR_ISL6271A is not set -# CONFIG_REGULATOR_LP3971 is not set -# CONFIG_REGULATOR_LP3972 is not set -# CONFIG_REGULATOR_LP872X is not set -# CONFIG_REGULATOR_LP8755 is not set -# CONFIG_REGULATOR_LTC3589 is not set -# CONFIG_REGULATOR_LTC3676 is not set -# CONFIG_REGULATOR_MAX1586 is not set -# CONFIG_REGULATOR_MAX8649 is not set -# CONFIG_REGULATOR_MAX8660 is not set -# CONFIG_REGULATOR_MAX8893 is not set -# CONFIG_REGULATOR_MAX8952 is not set -# CONFIG_REGULATOR_MAX20086 is not set -# CONFIG_REGULATOR_MAX20411 is not set -# CONFIG_REGULATOR_MAX77826 is not set -# CONFIG_REGULATOR_MCP16502 is not set -# CONFIG_REGULATOR_MP5416 is not set -# CONFIG_REGULATOR_MP8859 is not set -# CONFIG_REGULATOR_MP886X is not set -# CONFIG_REGULATOR_MPQ7920 is not set -# CONFIG_REGULATOR_MT6311 is not set -# CONFIG_REGULATOR_PCA9450 is not set -# CONFIG_REGULATOR_PF8X00 is not set -# CONFIG_REGULATOR_PFUZE100 is not set -# CONFIG_REGULATOR_PV88060 is not set -# CONFIG_REGULATOR_PV88080 is not set -# CONFIG_REGULATOR_PV88090 is not set -# CONFIG_REGULATOR_RASPBERRYPI_TOUCHSCREEN_ATTINY is not set -# CONFIG_REGULATOR_RT4801 is not set -# CONFIG_REGULATOR_RT5190A is not set -# CONFIG_REGULATOR_RT5759 is not set -# CONFIG_REGULATOR_RT6160 is not set -# CONFIG_REGULATOR_RT6190 is not set -# CONFIG_REGULATOR_RT6245 is not set -# CONFIG_REGULATOR_RTQ2134 is not set -# CONFIG_REGULATOR_RTMV20 is not set -# CONFIG_REGULATOR_RTQ6752 is not set -# CONFIG_REGULATOR_SLG51000 is not set -# CONFIG_REGULATOR_SY8106A is not set -# CONFIG_REGULATOR_SY8824X is not set -# CONFIG_REGULATOR_SY8827N is not set -# CONFIG_REGULATOR_TPS51632 is not set -# CONFIG_REGULATOR_TPS62360 is not set -# CONFIG_REGULATOR_TPS6286X is not set -# CONFIG_REGULATOR_TPS65023 is not set -# CONFIG_REGULATOR_TPS6507X is not set -# CONFIG_REGULATOR_TPS65132 is not set -# CONFIG_REGULATOR_TPS6524X is not set -# CONFIG_REGULATOR_VCTRL is not set -# CONFIG_RC_CORE is not set - -# -# CEC support -# -# CONFIG_MEDIA_CEC_SUPPORT is not set -# end of CEC support - -CONFIG_MEDIA_SUPPORT=m -CONFIG_MEDIA_SUPPORT_FILTER=y -CONFIG_MEDIA_SUBDRV_AUTOSELECT=y - -# -# Media device types -# -CONFIG_MEDIA_CAMERA_SUPPORT=y -# CONFIG_MEDIA_ANALOG_TV_SUPPORT is not set -# CONFIG_MEDIA_DIGITAL_TV_SUPPORT is not set -# CONFIG_MEDIA_RADIO_SUPPORT is not set -# CONFIG_MEDIA_SDR_SUPPORT is not set -# CONFIG_MEDIA_PLATFORM_SUPPORT is not set -# CONFIG_MEDIA_TEST_SUPPORT is not set -# end of Media device types - -CONFIG_VIDEO_DEV=m -CONFIG_MEDIA_CONTROLLER=y - -# -# Video4Linux options -# -CONFIG_VIDEO_V4L2_I2C=y -CONFIG_VIDEO_V4L2_SUBDEV_API=y -# CONFIG_VIDEO_ADV_DEBUG is not set -# CONFIG_VIDEO_FIXED_MINOR_RANGES is not set -CONFIG_V4L2_FWNODE=m -CONFIG_V4L2_ASYNC=m -# end of Video4Linux options - -# -# Media controller options -# -# end of Media controller options - -# -# Media drivers -# - -# -# Drivers filtered as selected at 'Filter media drivers' -# - -# -# Media drivers -# -# CONFIG_MEDIA_USB_SUPPORT is not set -# CONFIG_MEDIA_PCI_SUPPORT is not set -CONFIG_UVC_COMMON=m -CONFIG_VIDEOBUF2_CORE=m -CONFIG_VIDEOBUF2_V4L2=m -CONFIG_VIDEOBUF2_MEMOPS=m -CONFIG_VIDEOBUF2_VMALLOC=m -CONFIG_VIDEOBUF2_DMA_SG=m -# end of Media drivers - -# -# Media ancillary drivers -# - -# -# Camera sensor devices -# -# CONFIG_VIDEO_AR0521 is not set -# CONFIG_VIDEO_HI556 is not set -# CONFIG_VIDEO_HI846 is not set -# CONFIG_VIDEO_HI847 is not set -# CONFIG_VIDEO_IMX208 is not set -# CONFIG_VIDEO_IMX214 is not set -CONFIG_VIDEO_IMX219=m -# CONFIG_VIDEO_IMX258 is not set -# CONFIG_VIDEO_IMX274 is not set -# CONFIG_VIDEO_IMX290 is not set -# CONFIG_VIDEO_IMX296 is not set -# CONFIG_VIDEO_IMX319 is not set -# CONFIG_VIDEO_IMX334 is not set -# CONFIG_VIDEO_IMX335 is not set -# CONFIG_VIDEO_IMX355 is not set -# CONFIG_VIDEO_IMX412 is not set -# CONFIG_VIDEO_IMX415 is not set -# CONFIG_VIDEO_MT9M001 is not set -# CONFIG_VIDEO_MT9M032 is not set -# CONFIG_VIDEO_MT9M111 is not set -# CONFIG_VIDEO_MT9P031 is not set -# CONFIG_VIDEO_MT9T001 is not set -# CONFIG_VIDEO_MT9T112 is not set -# CONFIG_VIDEO_MT9V011 is not set -# CONFIG_VIDEO_MT9V032 is not set -# CONFIG_VIDEO_MT9V111 is not set -# CONFIG_VIDEO_NOON010PC30 is not set -# CONFIG_VIDEO_OG01A1B is not set -# CONFIG_VIDEO_OV02A10 is not set -# CONFIG_VIDEO_OV08D10 is not set -# CONFIG_VIDEO_OV08X40 is not set -# CONFIG_VIDEO_OV13858 is not set -# CONFIG_VIDEO_OV13B10 is not set -# CONFIG_VIDEO_OV2640 is not set -# CONFIG_VIDEO_OV2659 is not set -# CONFIG_VIDEO_OV2680 is not set -# CONFIG_VIDEO_OV2685 is not set -# CONFIG_VIDEO_OV4689 is not set -# CONFIG_VIDEO_OV5640 is not set -# CONFIG_VIDEO_OV5645 is not set -# CONFIG_VIDEO_OV5647 is not set -# CONFIG_VIDEO_OV5648 is not set -# CONFIG_VIDEO_OV5670 is not set -# CONFIG_VIDEO_OV5675 is not set -# CONFIG_VIDEO_OV5693 is not set -# CONFIG_VIDEO_OV5695 is not set -# CONFIG_VIDEO_OV6650 is not set -# CONFIG_VIDEO_OV7251 is not set -# CONFIG_VIDEO_OV7640 is not set -# CONFIG_VIDEO_OV7670 is not set -# CONFIG_VIDEO_OV772X is not set -# CONFIG_VIDEO_OV7740 is not set -# CONFIG_VIDEO_OV8856 is not set -# CONFIG_VIDEO_OV8858 is not set -# CONFIG_VIDEO_OV8865 is not set -# CONFIG_VIDEO_OV9282 is not set -# CONFIG_VIDEO_OV9640 is not set -# CONFIG_VIDEO_OV9650 is not set -# CONFIG_VIDEO_RDACM20 is not set -# CONFIG_VIDEO_RDACM21 is not set -# CONFIG_VIDEO_RJ54N1 is not set -# CONFIG_VIDEO_S5C73M3 is not set -# CONFIG_VIDEO_S5K5BAF is not set -# CONFIG_VIDEO_S5K6A3 is not set -# CONFIG_VIDEO_S5K6AA is not set -# CONFIG_VIDEO_SR030PC30 is not set -# CONFIG_VIDEO_ST_VGXY61 is not set -# CONFIG_VIDEO_VS6624 is not set -# CONFIG_VIDEO_CCS is not set -# CONFIG_VIDEO_ET8EK8 is not set -# CONFIG_VIDEO_M5MOLS is not set -# end of Camera sensor devices - -# -# Lens drivers -# -# CONFIG_VIDEO_AD5820 is not set -# CONFIG_VIDEO_AK7375 is not set -# CONFIG_VIDEO_DW9714 is not set -# CONFIG_VIDEO_DW9768 is not set -# CONFIG_VIDEO_DW9807_VCM is not set -# end of Lens drivers - -# -# Flash devices -# -# CONFIG_VIDEO_ADP1653 is not set -# CONFIG_VIDEO_LM3560 is not set -# CONFIG_VIDEO_LM3646 is not set -# end of Flash devices - -# -# Audio decoders, processors and mixers -# -# CONFIG_VIDEO_CS3308 is not set -# CONFIG_VIDEO_CS5345 is not set -# CONFIG_VIDEO_CS53L32A is not set -# CONFIG_VIDEO_MSP3400 is not set -# CONFIG_VIDEO_SONY_BTF_MPX is not set -# CONFIG_VIDEO_TDA7432 is not set -# CONFIG_VIDEO_TDA9840 is not set -# CONFIG_VIDEO_TEA6415C is not set -# CONFIG_VIDEO_TEA6420 is not set -# CONFIG_VIDEO_TLV320AIC23B is not set -# CONFIG_VIDEO_TVAUDIO is not set -# CONFIG_VIDEO_UDA1342 is not set -# CONFIG_VIDEO_VP27SMPX is not set -# CONFIG_VIDEO_WM8739 is not set -# CONFIG_VIDEO_WM8775 is not set -# end of Audio decoders, processors and mixers - -# -# RDS decoders -# -# CONFIG_VIDEO_SAA6588 is not set -# end of RDS decoders - -# -# Video decoders -# -# CONFIG_VIDEO_ADV7180 is not set -# CONFIG_VIDEO_ADV7183 is not set -# CONFIG_VIDEO_ADV748X is not set -# CONFIG_VIDEO_ADV7604 is not set -# CONFIG_VIDEO_ADV7842 is not set -# CONFIG_VIDEO_BT819 is not set -# CONFIG_VIDEO_BT856 is not set -# CONFIG_VIDEO_BT866 is not set -# CONFIG_VIDEO_ISL7998X is not set -# CONFIG_VIDEO_KS0127 is not set -# CONFIG_VIDEO_MAX9286 is not set -# CONFIG_VIDEO_ML86V7667 is not set -# CONFIG_VIDEO_SAA7110 is not set -# CONFIG_VIDEO_SAA711X is not set -# CONFIG_VIDEO_TC358743 is not set -# CONFIG_VIDEO_TC358746 is not set -# CONFIG_VIDEO_TVP514X is not set -# CONFIG_VIDEO_TVP5150 is not set -# CONFIG_VIDEO_TVP7002 is not set -# CONFIG_VIDEO_TW2804 is not set -# CONFIG_VIDEO_TW9903 is not set -# CONFIG_VIDEO_TW9906 is not set -# CONFIG_VIDEO_TW9910 is not set -# CONFIG_VIDEO_VPX3220 is not set - -# -# Video and audio decoders -# -# CONFIG_VIDEO_SAA717X is not set -# CONFIG_VIDEO_CX25840 is not set -# end of Video decoders - -# -# Video encoders -# -# CONFIG_VIDEO_AD9389B is not set -# CONFIG_VIDEO_ADV7170 is not set -# CONFIG_VIDEO_ADV7175 is not set -# CONFIG_VIDEO_ADV7343 is not set -# CONFIG_VIDEO_ADV7393 is not set -# CONFIG_VIDEO_ADV7511 is not set -# CONFIG_VIDEO_AK881X is not set -# CONFIG_VIDEO_SAA7127 is not set -# CONFIG_VIDEO_SAA7185 is not set -# CONFIG_VIDEO_THS8200 is not set -# end of Video encoders - -# -# Video improvement chips -# -# CONFIG_VIDEO_UPD64031A is not set -# CONFIG_VIDEO_UPD64083 is not set -# end of Video improvement chips - -# -# Audio/Video compression chips -# -# CONFIG_VIDEO_SAA6752HS is not set -# end of Audio/Video compression chips - -# -# SDR tuner chips -# -# end of SDR tuner chips - -# -# Miscellaneous helper chips -# -# CONFIG_VIDEO_I2C is not set -# CONFIG_VIDEO_M52790 is not set -# CONFIG_VIDEO_ST_MIPID02 is not set -# CONFIG_VIDEO_THS7303 is not set -# end of Miscellaneous helper chips - -# -# Media SPI Adapters -# -# CONFIG_VIDEO_GS1662 is not set -# end of Media SPI Adapters -# end of Media ancillary drivers - -# -# Graphics support -# -CONFIG_APERTURE_HELPERS=y -# CONFIG_DRM is not set -# CONFIG_DRM_DEBUG_MODESET_LOCK is not set - -# -# ARM devices -# -# end of ARM devices - -# -# Frame buffer Devices -# -CONFIG_FB_CMDLINE=y -CONFIG_FB_NOTIFY=y -CONFIG_FB=y -# CONFIG_FIRMWARE_EDID is not set -# CONFIG_FB_FOREIGN_ENDIAN is not set -# CONFIG_FB_MODE_HELPERS is not set -# CONFIG_FB_TILEBLITTING is not set - -# -# Frame buffer hardware drivers -# -# CONFIG_FB_CIRRUS is not set -# CONFIG_FB_PM2 is not set -# CONFIG_FB_CYBER2000 is not set -# CONFIG_FB_ASILIANT is not set -# CONFIG_FB_IMSTT is not set -# CONFIG_FB_EFI is not set -# CONFIG_FB_OPENCORES is not set -# CONFIG_FB_S1D13XXX is not set -# CONFIG_FB_NVIDIA is not set -# CONFIG_FB_RIVA is not set -# CONFIG_FB_I740 is not set -# CONFIG_FB_MATROX is not set -# CONFIG_FB_RADEON is not set -# CONFIG_FB_ATY128 is not set -# CONFIG_FB_ATY is not set -# CONFIG_FB_S3 is not set -# CONFIG_FB_SAVAGE is not set -# CONFIG_FB_SIS is not set -# CONFIG_FB_NEOMAGIC is not set -# CONFIG_FB_KYRO is not set -# CONFIG_FB_3DFX is not set -# CONFIG_FB_VOODOO1 is not set -# CONFIG_FB_VT8623 is not set -# CONFIG_FB_TRIDENT is not set -# CONFIG_FB_ARK is not set -# CONFIG_FB_PM3 is not set -# CONFIG_FB_CARMINE is not set -# CONFIG_FB_SH_MOBILE_LCDC is not set -# CONFIG_FB_SMSCUFX is not set -# CONFIG_FB_UDL is not set -# CONFIG_FB_IBM_GXT4500 is not set -# CONFIG_FB_GOLDFISH is not set -# CONFIG_FB_VIRTUAL is not set -# CONFIG_FB_METRONOME is not set -# CONFIG_FB_MB862XX is not set -# CONFIG_FB_SIMPLE is not set -# CONFIG_FB_SSD1307 is not set -# CONFIG_FB_SM712 is not set -# end of Frame buffer Devices - -# -# Backlight & LCD device support -# -# CONFIG_LCD_CLASS_DEVICE is not set -CONFIG_BACKLIGHT_CLASS_DEVICE=m -# CONFIG_BACKLIGHT_KTD253 is not set -# CONFIG_BACKLIGHT_KTZ8866 is not set -# CONFIG_BACKLIGHT_QCOM_WLED is not set -# CONFIG_BACKLIGHT_ADP8860 is not set -# CONFIG_BACKLIGHT_ADP8870 is not set -# CONFIG_BACKLIGHT_LM3639 is not set -# CONFIG_BACKLIGHT_GPIO is not set -# CONFIG_BACKLIGHT_LV5207LP is not set -# CONFIG_BACKLIGHT_BD6107 is not set -# CONFIG_BACKLIGHT_ARCXCNN is not set -# end of Backlight & LCD device support - -# -# Console display driver support -# -CONFIG_VGA_CONSOLE=y -CONFIG_DUMMY_CONSOLE=y -CONFIG_DUMMY_CONSOLE_COLUMNS=80 -CONFIG_DUMMY_CONSOLE_ROWS=25 -CONFIG_FRAMEBUFFER_CONSOLE=y -# CONFIG_FRAMEBUFFER_CONSOLE_LEGACY_ACCELERATION is not set -CONFIG_FRAMEBUFFER_CONSOLE_DETECT_PRIMARY=y -# CONFIG_FRAMEBUFFER_CONSOLE_ROTATION is not set -# CONFIG_FRAMEBUFFER_CONSOLE_DEFERRED_TAKEOVER is not set -# end of Console display driver support - -# CONFIG_LOGO is not set -# end of Graphics support - -# CONFIG_SOUND is not set -CONFIG_HID_SUPPORT=y -CONFIG_HID=y -# CONFIG_HID_BATTERY_STRENGTH is not set -# CONFIG_HIDRAW is not set -# CONFIG_UHID is not set -CONFIG_HID_GENERIC=y - -# -# Special HID drivers -# -# CONFIG_HID_A4TECH is not set -# CONFIG_HID_ACCUTOUCH is not set -# CONFIG_HID_ACRUX is not set -# CONFIG_HID_APPLEIR is not set -# CONFIG_HID_AUREAL is not set -# CONFIG_HID_BELKIN is not set -# CONFIG_HID_BETOP_FF is not set -# CONFIG_HID_CHERRY is not set -# CONFIG_HID_CHICONY is not set -# CONFIG_HID_COUGAR is not set -# CONFIG_HID_MACALLY is not set -# CONFIG_HID_CMEDIA is not set -# CONFIG_HID_CREATIVE_SB0540 is not set -# CONFIG_HID_CYPRESS is not set -# CONFIG_HID_DRAGONRISE is not set -# CONFIG_HID_EMS_FF is not set -# CONFIG_HID_ELECOM is not set -# CONFIG_HID_ELO is not set -# CONFIG_HID_EVISION is not set -# CONFIG_HID_EZKEY is not set -# CONFIG_HID_GEMBIRD is not set -# CONFIG_HID_GFRM is not set -# CONFIG_HID_GLORIOUS is not set -# CONFIG_HID_HOLTEK is not set -# CONFIG_HID_VIVALDI is not set -# CONFIG_HID_KEYTOUCH is not set -# CONFIG_HID_KYE is not set -# CONFIG_HID_UCLOGIC is not set -# CONFIG_HID_WALTOP is not set -# CONFIG_HID_VIEWSONIC is not set -# CONFIG_HID_VRC2 is not set -# CONFIG_HID_XIAOMI is not set -# CONFIG_HID_GYRATION is not set -# CONFIG_HID_ICADE is not set -# CONFIG_HID_ITE is not set -# CONFIG_HID_JABRA is not set -# CONFIG_HID_TWINHAN is not set -# CONFIG_HID_KENSINGTON is not set -# CONFIG_HID_LCPOWER is not set -# CONFIG_HID_LENOVO is not set -# CONFIG_HID_LETSKETCH is not set -# CONFIG_HID_MAGICMOUSE is not set -# CONFIG_HID_MALTRON is not set -# CONFIG_HID_MAYFLASH is not set -# CONFIG_HID_MEGAWORLD_FF is not set -# CONFIG_HID_REDRAGON is not set -# CONFIG_HID_MICROSOFT is not set -# CONFIG_HID_MONTEREY is not set -# CONFIG_HID_MULTITOUCH is not set -# CONFIG_HID_NTI is not set -# CONFIG_HID_NTRIG is not set -# CONFIG_HID_ORTEK is not set -# CONFIG_HID_PANTHERLORD is not set -# CONFIG_HID_PENMOUNT is not set -# CONFIG_HID_PETALYNX is not set -# CONFIG_HID_PICOLCD is not set -# CONFIG_HID_PLANTRONICS is not set -# CONFIG_HID_PXRC is not set -# CONFIG_HID_RAZER is not set -# CONFIG_HID_PRIMAX is not set -# CONFIG_HID_RETRODE is not set -# CONFIG_HID_ROCCAT is not set -# CONFIG_HID_SAITEK is not set -# CONFIG_HID_SAMSUNG is not set -# CONFIG_HID_SEMITEK is not set -# CONFIG_HID_SIGMAMICRO is not set -# CONFIG_HID_SPEEDLINK is not set -# CONFIG_HID_STEAM is not set -# CONFIG_HID_STEELSERIES is not set -# CONFIG_HID_SUNPLUS is not set -# CONFIG_HID_RMI is not set -# CONFIG_HID_GREENASIA is not set -# CONFIG_HID_SMARTJOYPLUS is not set -# CONFIG_HID_TIVO is not set -# CONFIG_HID_TOPSEED is not set -# CONFIG_HID_TOPRE is not set -# CONFIG_HID_THRUSTMASTER is not set -# CONFIG_HID_UDRAW_PS3 is not set -# CONFIG_HID_WACOM is not set -# CONFIG_HID_XINMO is not set -# CONFIG_HID_ZEROPLUS is not set -# CONFIG_HID_ZYDACRON is not set -# CONFIG_HID_SENSOR_HUB is not set -# CONFIG_HID_ALPS is not set -# CONFIG_HID_MCP2221 is not set -# end of Special HID drivers - -# -# HID-BPF support -# -# end of HID-BPF support - -# -# USB HID support -# -CONFIG_USB_HID=y -# CONFIG_HID_PID is not set -# CONFIG_USB_HIDDEV is not set -# end of USB HID support - -CONFIG_I2C_HID=m -# CONFIG_I2C_HID_OF is not set -# CONFIG_I2C_HID_OF_ELAN is not set -# CONFIG_I2C_HID_OF_GOODIX is not set -CONFIG_USB_OHCI_LITTLE_ENDIAN=y -CONFIG_USB_SUPPORT=y -CONFIG_USB_COMMON=y -# CONFIG_USB_ULPI_BUS is not set -# CONFIG_USB_CONN_GPIO is not set -CONFIG_USB_ARCH_HAS_HCD=y -CONFIG_USB=y -CONFIG_USB_PCI=y -# CONFIG_USB_ANNOUNCE_NEW_DEVICES is not set - -# -# Miscellaneous USB options -# -CONFIG_USB_DEFAULT_PERSIST=y -# CONFIG_USB_FEW_INIT_RETRIES is not set -# CONFIG_USB_DYNAMIC_MINORS is not set -# CONFIG_USB_OTG is not set -# CONFIG_USB_OTG_PRODUCTLIST is not set -# CONFIG_USB_OTG_DISABLE_EXTERNAL_HUB is not set -CONFIG_USB_AUTOSUSPEND_DELAY=2 -# CONFIG_USB_MON is not set - -# -# USB Host Controller Drivers -# -# CONFIG_USB_C67X00_HCD is not set -CONFIG_USB_XHCI_HCD=y -# CONFIG_USB_XHCI_DBGCAP is not set -CONFIG_USB_XHCI_PCI=y -# CONFIG_USB_XHCI_PCI_RENESAS is not set -CONFIG_USB_XHCI_PLATFORM=y -CONFIG_USB_XHCI_RCAR=y -CONFIG_USB_EHCI_HCD=y -# CONFIG_USB_EHCI_ROOT_HUB_TT is not set -CONFIG_USB_EHCI_TT_NEWSCHED=y -CONFIG_USB_EHCI_PCI=y -# CONFIG_USB_EHCI_FSL is not set -CONFIG_USB_EHCI_HCD_PLATFORM=y -# CONFIG_USB_OXU210HP_HCD is not set -# CONFIG_USB_ISP116X_HCD is not set -# CONFIG_USB_MAX3421_HCD is not set -CONFIG_USB_OHCI_HCD=y -CONFIG_USB_OHCI_HCD_PCI=y -CONFIG_USB_OHCI_HCD_PLATFORM=y -# CONFIG_USB_UHCI_HCD is not set -# CONFIG_USB_SL811_HCD is not set -# CONFIG_USB_R8A66597_HCD is not set -# CONFIG_USB_HCD_TEST_MODE is not set -# CONFIG_USB_RENESAS_USBHS is not set - -# -# USB Device Class drivers -# -# CONFIG_USB_ACM is not set -# CONFIG_USB_PRINTER is not set -# CONFIG_USB_WDM is not set -# CONFIG_USB_TMC is not set - -# -# NOTE: USB_STORAGE depends on SCSI but BLK_DEV_SD may -# - -# -# also be needed; see USB_STORAGE Help for more info -# -CONFIG_USB_STORAGE=y -# CONFIG_USB_STORAGE_DEBUG is not set -# CONFIG_USB_STORAGE_REALTEK is not set -# CONFIG_USB_STORAGE_DATAFAB is not set -# CONFIG_USB_STORAGE_FREECOM is not set -# CONFIG_USB_STORAGE_ISD200 is not set -# CONFIG_USB_STORAGE_USBAT is not set -# CONFIG_USB_STORAGE_SDDR09 is not set -# CONFIG_USB_STORAGE_SDDR55 is not set -# CONFIG_USB_STORAGE_JUMPSHOT is not set -# CONFIG_USB_STORAGE_ALAUDA is not set -# CONFIG_USB_STORAGE_ONETOUCH is not set -# CONFIG_USB_STORAGE_KARMA is not set -# CONFIG_USB_STORAGE_CYPRESS_ATACB is not set -# CONFIG_USB_STORAGE_ENE_UB6250 is not set -CONFIG_USB_UAS=y - -# -# USB Imaging devices -# -# CONFIG_USB_MDC800 is not set -# CONFIG_USB_MICROTEK is not set -# CONFIG_USBIP_CORE is not set - -# -# USB dual-mode controller drivers -# -# CONFIG_USB_CDNS_SUPPORT is not set -CONFIG_USB_MUSB_HDRC=y -# CONFIG_USB_MUSB_HOST is not set -# CONFIG_USB_MUSB_GADGET is not set -CONFIG_USB_MUSB_DUAL_ROLE=y - -# -# Platform Glue Layer -# -CONFIG_USB_MUSB_SUNXI=m -CONFIG_USB_MUSB_POLARFIRE_SOC=y - -# -# MUSB DMA mode -# -# CONFIG_MUSB_PIO_ONLY is not set -# CONFIG_USB_INVENTRA_DMA is not set -# CONFIG_USB_DWC3 is not set -# CONFIG_USB_DWC2 is not set -# CONFIG_USB_CHIPIDEA is not set -# CONFIG_USB_ISP1760 is not set - -# -# USB port drivers -# -# CONFIG_USB_SERIAL is not set - -# -# USB Miscellaneous drivers -# -# CONFIG_USB_EMI62 is not set -# CONFIG_USB_EMI26 is not set -# CONFIG_USB_ADUTUX is not set -# CONFIG_USB_SEVSEG is not set -# CONFIG_USB_LEGOTOWER is not set -# CONFIG_USB_LCD is not set -# CONFIG_USB_CYPRESS_CY7C63 is not set -# CONFIG_USB_CYTHERM is not set -# CONFIG_USB_IDMOUSE is not set -# CONFIG_USB_FTDI_ELAN is not set -# CONFIG_USB_APPLEDISPLAY is not set -# CONFIG_APPLE_MFI_FASTCHARGE is not set -# CONFIG_USB_SISUSBVGA is not set -# CONFIG_USB_LD is not set -# CONFIG_USB_TRANCEVIBRATOR is not set -# CONFIG_USB_IOWARRIOR is not set -# CONFIG_USB_TEST is not set -# CONFIG_USB_EHSET_TEST_FIXTURE is not set -# CONFIG_USB_ISIGHTFW is not set -# CONFIG_USB_YUREX is not set -# CONFIG_USB_EZUSB_FX2 is not set -# CONFIG_USB_HUB_USB251XB is not set -# CONFIG_USB_HSIC_USB3503 is not set -# CONFIG_USB_HSIC_USB4604 is not set -# CONFIG_USB_LINK_LAYER_TEST is not set -# CONFIG_USB_CHAOSKEY is not set -# CONFIG_USB_ONBOARD_HUB is not set - -# -# USB Physical Layer drivers -# -CONFIG_USB_PHY=y -CONFIG_NOP_USB_XCEIV=y -# CONFIG_USB_GPIO_VBUS is not set -# CONFIG_USB_ISP1301 is not set -# end of USB Physical Layer drivers - -CONFIG_USB_GADGET=y -# CONFIG_USB_GADGET_DEBUG is not set -# CONFIG_USB_GADGET_DEBUG_FILES is not set -# CONFIG_USB_GADGET_DEBUG_FS is not set -CONFIG_USB_GADGET_VBUS_DRAW=2 -CONFIG_USB_GADGET_STORAGE_NUM_BUFFERS=2 -# CONFIG_U_SERIAL_CONSOLE is not set - -# -# USB Peripheral Controller -# -# CONFIG_USB_GR_UDC is not set -# CONFIG_USB_R8A66597 is not set -# CONFIG_USB_RENESAS_USB3 is not set -# CONFIG_USB_RENESAS_USBF is not set -# CONFIG_USB_PXA27X is not set -# CONFIG_USB_MV_UDC is not set -# CONFIG_USB_MV_U3D is not set -# CONFIG_USB_SNP_UDC_PLAT is not set -# CONFIG_USB_M66592 is not set -# CONFIG_USB_BDC_UDC is not set -# CONFIG_USB_AMD5536UDC is not set -# CONFIG_USB_NET2272 is not set -# CONFIG_USB_NET2280 is not set -# CONFIG_USB_GOKU is not set -# CONFIG_USB_EG20T is not set -# CONFIG_USB_GADGET_XILINX is not set -# CONFIG_USB_MAX3420_UDC is not set -# CONFIG_USB_DUMMY_HCD is not set -# end of USB Peripheral Controller - -CONFIG_USB_LIBCOMPOSITE=y -CONFIG_USB_F_ACM=y -CONFIG_USB_F_SS_LB=y -CONFIG_USB_U_SERIAL=y -CONFIG_USB_U_ETHER=y -CONFIG_USB_F_SERIAL=y -CONFIG_USB_F_OBEX=y -CONFIG_USB_F_NCM=y -CONFIG_USB_F_ECM=y -CONFIG_USB_F_EEM=y -CONFIG_USB_F_SUBSET=y -CONFIG_USB_F_RNDIS=y -CONFIG_USB_F_MASS_STORAGE=y -CONFIG_USB_F_FS=y -CONFIG_USB_F_UVC=m -CONFIG_USB_F_HID=y -CONFIG_USB_F_PRINTER=y -CONFIG_USB_CONFIGFS=y -CONFIG_USB_CONFIGFS_SERIAL=y -CONFIG_USB_CONFIGFS_ACM=y -CONFIG_USB_CONFIGFS_OBEX=y -CONFIG_USB_CONFIGFS_NCM=y -CONFIG_USB_CONFIGFS_ECM=y -CONFIG_USB_CONFIGFS_ECM_SUBSET=y -CONFIG_USB_CONFIGFS_RNDIS=y -CONFIG_USB_CONFIGFS_EEM=y -CONFIG_USB_CONFIGFS_MASS_STORAGE=y -CONFIG_USB_CONFIGFS_F_LB_SS=y -CONFIG_USB_CONFIGFS_F_FS=y -CONFIG_USB_CONFIGFS_F_HID=y -CONFIG_USB_CONFIGFS_F_UVC=y -CONFIG_USB_CONFIGFS_F_PRINTER=y - -# -# USB Gadget precomposed configurations -# -# CONFIG_USB_ZERO is not set -# CONFIG_USB_ETH is not set -# CONFIG_USB_G_NCM is not set -# CONFIG_USB_GADGETFS is not set -# CONFIG_USB_FUNCTIONFS is not set -# CONFIG_USB_MASS_STORAGE is not set -# CONFIG_USB_G_SERIAL is not set -# CONFIG_USB_G_PRINTER is not set -# CONFIG_USB_CDC_COMPOSITE is not set -# CONFIG_USB_G_ACM_MS is not set -# CONFIG_USB_G_MULTI is not set -# CONFIG_USB_G_HID is not set -# CONFIG_USB_G_DBGP is not set -# CONFIG_USB_G_WEBCAM is not set -# CONFIG_USB_RAW_GADGET is not set -# end of USB Gadget precomposed configurations - -# CONFIG_TYPEC is not set -# CONFIG_USB_ROLE_SWITCH is not set -CONFIG_MMC=y -CONFIG_PWRSEQ_EMMC=y -CONFIG_PWRSEQ_SIMPLE=y -CONFIG_MMC_BLOCK=y -CONFIG_MMC_BLOCK_MINORS=8 -# CONFIG_SDIO_UART is not set -# CONFIG_MMC_TEST is not set - -# -# MMC/SD/SDIO Host Controller Drivers -# -# CONFIG_MMC_DEBUG is not set -CONFIG_MMC_SDHCI=y -# CONFIG_MMC_SDHCI_PCI is not set -CONFIG_MMC_SDHCI_PLTFM=y -# CONFIG_MMC_SDHCI_OF_ARASAN is not set -# CONFIG_MMC_SDHCI_OF_AT91 is not set -# CONFIG_MMC_SDHCI_OF_DWCMSHC is not set -CONFIG_MMC_SDHCI_CADENCE=y -# CONFIG_MMC_SDHCI_F_SDH30 is not set -# CONFIG_MMC_SDHCI_MILBEAUT is not set -# CONFIG_MMC_TIFM_SD is not set -CONFIG_MMC_SPI=y -# CONFIG_MMC_SDHI is not set -# CONFIG_MMC_CB710 is not set -# CONFIG_MMC_VIA_SDMMC is not set -# CONFIG_MMC_DW is not set -# CONFIG_MMC_SH_MMCIF is not set -# CONFIG_MMC_VUB300 is not set -# CONFIG_MMC_USHC is not set -# CONFIG_MMC_USDHI6ROL0 is not set -CONFIG_MMC_SUNXI=y -# CONFIG_MMC_CQHCI is not set -# CONFIG_MMC_HSQ is not set -# CONFIG_MMC_TOSHIBA_PCI is not set -# CONFIG_MMC_MTK is not set -# CONFIG_MMC_SDHCI_XENON is not set -# CONFIG_MMC_SDHCI_OMAP is not set -# CONFIG_MMC_SDHCI_AM654 is not set -# CONFIG_SCSI_UFSHCD is not set -# CONFIG_MEMSTICK is not set -# CONFIG_NEW_LEDS is not set -# CONFIG_ACCESSIBILITY is not set -# CONFIG_INFINIBAND is not set -CONFIG_EDAC_SUPPORT=y -CONFIG_RTC_LIB=y -CONFIG_RTC_CLASS=y -CONFIG_RTC_HCTOSYS=y -CONFIG_RTC_HCTOSYS_DEVICE="rtc0" -CONFIG_RTC_SYSTOHC=y -CONFIG_RTC_SYSTOHC_DEVICE="rtc0" -# CONFIG_RTC_DEBUG is not set -CONFIG_RTC_NVMEM=y - -# -# RTC interfaces -# -CONFIG_RTC_INTF_SYSFS=y -CONFIG_RTC_INTF_PROC=y -CONFIG_RTC_INTF_DEV=y -# CONFIG_RTC_INTF_DEV_UIE_EMUL is not set -# CONFIG_RTC_DRV_TEST is not set - -# -# I2C RTC drivers -# -# CONFIG_RTC_DRV_ABB5ZES3 is not set -# CONFIG_RTC_DRV_ABEOZ9 is not set -# CONFIG_RTC_DRV_ABX80X is not set -# CONFIG_RTC_DRV_DS1307 is not set -# CONFIG_RTC_DRV_DS1374 is not set -# CONFIG_RTC_DRV_DS1672 is not set -# CONFIG_RTC_DRV_HYM8563 is not set -# CONFIG_RTC_DRV_MAX6900 is not set -# CONFIG_RTC_DRV_NCT3018Y is not set -# CONFIG_RTC_DRV_RS5C372 is not set -# CONFIG_RTC_DRV_ISL1208 is not set -# CONFIG_RTC_DRV_ISL12022 is not set -# CONFIG_RTC_DRV_ISL12026 is not set -# CONFIG_RTC_DRV_X1205 is not set -# CONFIG_RTC_DRV_PCF8523 is not set -# CONFIG_RTC_DRV_PCF85063 is not set -# CONFIG_RTC_DRV_PCF85363 is not set -# CONFIG_RTC_DRV_PCF8563 is not set -# CONFIG_RTC_DRV_PCF8583 is not set -# CONFIG_RTC_DRV_M41T80 is not set -# CONFIG_RTC_DRV_BQ32K is not set -# CONFIG_RTC_DRV_S35390A is not set -# CONFIG_RTC_DRV_FM3130 is not set -# CONFIG_RTC_DRV_RX8010 is not set -# CONFIG_RTC_DRV_RX8581 is not set -# CONFIG_RTC_DRV_RX8025 is not set -# CONFIG_RTC_DRV_EM3027 is not set -# CONFIG_RTC_DRV_RV3028 is not set -# CONFIG_RTC_DRV_RV3032 is not set -# CONFIG_RTC_DRV_RV8803 is not set -# CONFIG_RTC_DRV_SD3078 is not set - -# -# SPI RTC drivers -# -# CONFIG_RTC_DRV_M41T93 is not set -# CONFIG_RTC_DRV_M41T94 is not set -# CONFIG_RTC_DRV_DS1302 is not set -# CONFIG_RTC_DRV_DS1305 is not set -# CONFIG_RTC_DRV_DS1343 is not set -# CONFIG_RTC_DRV_DS1347 is not set -# CONFIG_RTC_DRV_DS1390 is not set -# CONFIG_RTC_DRV_MAX6916 is not set -# CONFIG_RTC_DRV_R9701 is not set -# CONFIG_RTC_DRV_RX4581 is not set -# CONFIG_RTC_DRV_RS5C348 is not set -# CONFIG_RTC_DRV_MAX6902 is not set -# CONFIG_RTC_DRV_PCF2123 is not set -# CONFIG_RTC_DRV_MCP795 is not set -CONFIG_RTC_I2C_AND_SPI=y - -# -# SPI and I2C RTC drivers -# -# CONFIG_RTC_DRV_DS3232 is not set -# CONFIG_RTC_DRV_PCF2127 is not set -# CONFIG_RTC_DRV_RV3029C2 is not set -# CONFIG_RTC_DRV_RX6110 is not set - -# -# Platform RTC drivers -# -# CONFIG_RTC_DRV_DS1286 is not set -# CONFIG_RTC_DRV_DS1511 is not set -# CONFIG_RTC_DRV_DS1553 is not set -# CONFIG_RTC_DRV_DS1685_FAMILY is not set -# CONFIG_RTC_DRV_DS1742 is not set -# CONFIG_RTC_DRV_DS2404 is not set -# CONFIG_RTC_DRV_EFI is not set -# CONFIG_RTC_DRV_STK17TA8 is not set -# CONFIG_RTC_DRV_M48T86 is not set -# CONFIG_RTC_DRV_M48T35 is not set -# CONFIG_RTC_DRV_M48T59 is not set -# CONFIG_RTC_DRV_MSM6242 is not set -# CONFIG_RTC_DRV_BQ4802 is not set -# CONFIG_RTC_DRV_RP5C01 is not set -# CONFIG_RTC_DRV_ZYNQMP is not set - -# -# on-CPU RTC drivers -# -# CONFIG_RTC_DRV_SH is not set -CONFIG_RTC_DRV_SUN6I=y -# CONFIG_RTC_DRV_CADENCE is not set -# CONFIG_RTC_DRV_FTRTC010 is not set -# CONFIG_RTC_DRV_R7301 is not set - -# -# HID Sensor RTC drivers -# -CONFIG_RTC_DRV_GOLDFISH=y -# CONFIG_RTC_DRV_POLARFIRE_SOC is not set -CONFIG_DMADEVICES=y -# CONFIG_DMADEVICES_DEBUG is not set - -# -# DMA Devices -# -CONFIG_DMA_ENGINE=y -CONFIG_DMA_VIRTUAL_CHANNELS=m -CONFIG_DMA_OF=y -# CONFIG_ALTERA_MSGDMA is not set -CONFIG_DMA_SUN6I=m -# CONFIG_DW_AXI_DMAC is not set -# CONFIG_FSL_EDMA is not set -# CONFIG_INTEL_IDMA64 is not set -# CONFIG_PLX_DMA is not set -# CONFIG_XILINX_XDMA is not set -# CONFIG_XILINX_ZYNQMP_DPDMA is not set -# CONFIG_QCOM_HIDMA_MGMT is not set -# CONFIG_QCOM_HIDMA is not set -# CONFIG_DW_DMAC is not set -# CONFIG_DW_DMAC_PCI is not set -# CONFIG_DW_EDMA is not set -# CONFIG_SF_PDMA is not set -# CONFIG_RCAR_DMAC is not set -# CONFIG_RENESAS_USB_DMAC is not set -# CONFIG_RZ_DMAC is not set - -# -# DMA Clients -# -# CONFIG_ASYNC_TX_DMA is not set -# CONFIG_DMATEST is not set - -# -# DMABUF options -# -CONFIG_SYNC_FILE=y -# CONFIG_SW_SYNC is not set -# CONFIG_UDMABUF is not set -# CONFIG_DMABUF_MOVE_NOTIFY is not set -# CONFIG_DMABUF_DEBUG is not set -# CONFIG_DMABUF_SELFTESTS is not set -# CONFIG_DMABUF_HEAPS is not set -# CONFIG_DMABUF_SYSFS_STATS is not set -# end of DMABUF options - -# CONFIG_AUXDISPLAY is not set -# CONFIG_UIO is not set -# CONFIG_VFIO is not set -# CONFIG_VIRT_DRIVERS is not set -CONFIG_VIRTIO_ANCHOR=y -CONFIG_VIRTIO=y -CONFIG_VIRTIO_PCI_LIB=y -CONFIG_VIRTIO_PCI_LIB_LEGACY=y -CONFIG_VIRTIO_MENU=y -CONFIG_VIRTIO_PCI=y -CONFIG_VIRTIO_PCI_LEGACY=y -# CONFIG_VIRTIO_PMEM is not set -CONFIG_VIRTIO_BALLOON=y -CONFIG_VIRTIO_INPUT=y -CONFIG_VIRTIO_MMIO=y -# CONFIG_VIRTIO_MMIO_CMDLINE_DEVICES is not set -# CONFIG_VDPA is not set -CONFIG_VHOST_MENU=y -# CONFIG_VHOST_NET is not set -# CONFIG_VHOST_CROSS_ENDIAN_LEGACY is not set - -# -# Microsoft Hyper-V guest support -# -# end of Microsoft Hyper-V guest support - -# CONFIG_GREYBUS is not set -# CONFIG_COMEDI is not set -# CONFIG_STAGING is not set -CONFIG_GOLDFISH=y -# CONFIG_GOLDFISH_PIPE is not set -CONFIG_HAVE_CLK=y -CONFIG_HAVE_CLK_PREPARE=y -CONFIG_COMMON_CLK=y -# CONFIG_LMK04832 is not set -# CONFIG_COMMON_CLK_MAX9485 is not set -# CONFIG_COMMON_CLK_SI5341 is not set -# CONFIG_COMMON_CLK_SI5351 is not set -# CONFIG_COMMON_CLK_SI514 is not set -# CONFIG_COMMON_CLK_SI544 is not set -# CONFIG_COMMON_CLK_SI570 is not set -# CONFIG_COMMON_CLK_CDCE706 is not set -# CONFIG_COMMON_CLK_CDCE925 is not set -# CONFIG_COMMON_CLK_CS2000_CP is not set -# CONFIG_COMMON_CLK_AXI_CLKGEN is not set -# CONFIG_COMMON_CLK_RS9_PCIE is not set -# CONFIG_COMMON_CLK_VC5 is not set -# CONFIG_COMMON_CLK_VC7 is not set -# CONFIG_COMMON_CLK_FIXED_MMIO is not set -CONFIG_CLK_ANALOGBITS_WRPLL_CLN28HPC=y -CONFIG_MCHP_CLK_MPFS=y -CONFIG_CLK_RENESAS=y -CONFIG_CLK_R9A07G043=y -# CONFIG_CLK_RCAR_USB2_CLOCK_SEL is not set -CONFIG_CLK_RZG2L=y -CONFIG_CLK_SIFIVE=y -CONFIG_CLK_SIFIVE_PRCI=y -CONFIG_CLK_STARFIVE_JH7100=y -CONFIG_CLK_STARFIVE_JH7100_AUDIO=m -CONFIG_SUNXI_CCU=y -CONFIG_SUN20I_D1_CCU=y -CONFIG_SUN20I_D1_R_CCU=y -CONFIG_SUN6I_RTC_CCU=y -CONFIG_SUN8I_DE2_CCU=m -# CONFIG_XILINX_VCU is not set -# CONFIG_COMMON_CLK_XLNX_CLKWZRD is not set -# CONFIG_HWSPINLOCK is not set - -# -# Clock Source drivers -# -CONFIG_TIMER_OF=y -CONFIG_TIMER_PROBE=y -CONFIG_CLKSRC_MMIO=y -CONFIG_SUN4I_TIMER=y -# CONFIG_RENESAS_OSTM is not set -CONFIG_RISCV_TIMER=y -# end of Clock Source drivers - -CONFIG_MAILBOX=y -# CONFIG_PLATFORM_MHU is not set -# CONFIG_ALTERA_MBOX is not set -# CONFIG_MAILBOX_TEST is not set -CONFIG_POLARFIRE_SOC_MAILBOX=y -# CONFIG_SUN6I_MSGBOX is not set -CONFIG_IOMMU_API=y -CONFIG_IOMMU_SUPPORT=y - -# -# Generic IOMMU Pagetable Support -# -# end of Generic IOMMU Pagetable Support - -# CONFIG_IOMMU_DEBUGFS is not set -CONFIG_IOMMU_DEFAULT_DMA_STRICT=y -# CONFIG_IOMMU_DEFAULT_DMA_LAZY is not set -# CONFIG_IOMMU_DEFAULT_PASSTHROUGH is not set -CONFIG_OF_IOMMU=y -# CONFIG_IOMMUFD is not set -CONFIG_SUN50I_IOMMU=y - -# -# Remoteproc drivers -# -CONFIG_REMOTEPROC=y -CONFIG_REMOTEPROC_CDEV=y -# CONFIG_RCAR_REMOTEPROC is not set -# end of Remoteproc drivers - -# -# Rpmsg drivers -# -CONFIG_RPMSG=y -CONFIG_RPMSG_CHAR=y -CONFIG_RPMSG_CTRL=y -CONFIG_RPMSG_NS=y -# CONFIG_RPMSG_QCOM_GLINK_RPM is not set -CONFIG_RPMSG_VIRTIO=y -# end of Rpmsg drivers - -# CONFIG_SOUNDWIRE is not set - -# -# SOC (System On Chip) specific Drivers -# - -# -# Amlogic SoC drivers -# -# end of Amlogic SoC drivers - -# -# Broadcom SoC drivers -# -# end of Broadcom SoC drivers - -# -# NXP/Freescale QorIQ SoC drivers -# -# end of NXP/Freescale QorIQ SoC drivers - -# -# fujitsu SoC drivers -# -# end of fujitsu SoC drivers - -# -# i.MX SoC drivers -# -# end of i.MX SoC drivers - -# -# Enable LiteX SoC Builder specific drivers -# -# CONFIG_LITEX_SOC_CONTROLLER is not set -# end of Enable LiteX SoC Builder specific drivers - -CONFIG_POLARFIRE_SOC_SYS_CTRL=y -# CONFIG_WPCM450_SOC is not set - -# -# Qualcomm SoC drivers -# -# end of Qualcomm SoC drivers - -CONFIG_SOC_RENESAS=y -CONFIG_ARCH_RZG2L=y -CONFIG_ARCH_R9A07G043=y -# CONFIG_SIFIVE_CCACHE is not set -CONFIG_JH71XX_PMU=y -CONFIG_SUNXI_SRAM=y -# CONFIG_SUN20I_PPU is not set -# CONFIG_SOC_TI is not set - -# -# Xilinx SoC drivers -# -# end of Xilinx SoC drivers -# end of SOC (System On Chip) specific Drivers - -# CONFIG_PM_DEVFREQ is not set -CONFIG_EXTCON=y - -# -# Extcon Device Drivers -# -# CONFIG_EXTCON_ADC_JACK is not set -# CONFIG_EXTCON_FSA9480 is not set -# CONFIG_EXTCON_GPIO is not set -# CONFIG_EXTCON_MAX3355 is not set -# CONFIG_EXTCON_PTN5150 is not set -# CONFIG_EXTCON_RT8973A is not set -# CONFIG_EXTCON_SM5502 is not set -# CONFIG_EXTCON_USB_GPIO is not set -# CONFIG_MEMORY is not set -CONFIG_IIO=m -# CONFIG_IIO_BUFFER is not set -# CONFIG_IIO_CONFIGFS is not set -# CONFIG_IIO_TRIGGER is not set -# CONFIG_IIO_SW_DEVICE is not set -# CONFIG_IIO_SW_TRIGGER is not set -# CONFIG_IIO_TRIGGERED_EVENT is not set - -# -# Accelerometers -# -# CONFIG_ADIS16201 is not set -# CONFIG_ADIS16209 is not set -# CONFIG_ADXL313_I2C is not set -# CONFIG_ADXL313_SPI is not set -# CONFIG_ADXL345_I2C is not set -# CONFIG_ADXL345_SPI is not set -# CONFIG_ADXL355_I2C is not set -# CONFIG_ADXL355_SPI is not set -# CONFIG_ADXL367_SPI is not set -# CONFIG_ADXL367_I2C is not set -# CONFIG_ADXL372_SPI is not set -# CONFIG_ADXL372_I2C is not set -# CONFIG_BMA180 is not set -# CONFIG_BMA220 is not set -# CONFIG_BMA400 is not set -# CONFIG_BMC150_ACCEL is not set -# CONFIG_BMI088_ACCEL is not set -# CONFIG_DA280 is not set -# CONFIG_DA311 is not set -# CONFIG_DMARD06 is not set -# CONFIG_DMARD09 is not set -# CONFIG_DMARD10 is not set -# CONFIG_FXLS8962AF_I2C is not set -# CONFIG_FXLS8962AF_SPI is not set -# CONFIG_IIO_ST_ACCEL_3AXIS is not set -# CONFIG_IIO_KX022A_SPI is not set -# CONFIG_IIO_KX022A_I2C is not set -# CONFIG_KXSD9 is not set -# CONFIG_KXCJK1013 is not set -# CONFIG_MC3230 is not set -# CONFIG_MMA7455_I2C is not set -# CONFIG_MMA7455_SPI is not set -# CONFIG_MMA7660 is not set -# CONFIG_MMA8452 is not set -# CONFIG_MMA9551 is not set -# CONFIG_MMA9553 is not set -# CONFIG_MSA311 is not set -# CONFIG_MXC4005 is not set -# CONFIG_MXC6255 is not set -# CONFIG_SCA3000 is not set -# CONFIG_SCA3300 is not set -# CONFIG_STK8312 is not set -# CONFIG_STK8BA50 is not set -# end of Accelerometers - -# -# Analog to digital converters -# -# CONFIG_AD4130 is not set -# CONFIG_AD7091R5 is not set -# CONFIG_AD7124 is not set -# CONFIG_AD7192 is not set -# CONFIG_AD7266 is not set -# CONFIG_AD7280 is not set -# CONFIG_AD7291 is not set -# CONFIG_AD7292 is not set -# CONFIG_AD7298 is not set -# CONFIG_AD7476 is not set -# CONFIG_AD7606_IFACE_PARALLEL is not set -# CONFIG_AD7606_IFACE_SPI is not set -# CONFIG_AD7766 is not set -# CONFIG_AD7768_1 is not set -# CONFIG_AD7780 is not set -# CONFIG_AD7791 is not set -# CONFIG_AD7793 is not set -# CONFIG_AD7887 is not set -# CONFIG_AD7923 is not set -# CONFIG_AD7949 is not set -# CONFIG_AD799X is not set -# CONFIG_ADI_AXI_ADC is not set -# CONFIG_CC10001_ADC is not set -# CONFIG_ENVELOPE_DETECTOR is not set -# CONFIG_HI8435 is not set -# CONFIG_HX711 is not set -# CONFIG_INA2XX_ADC is not set -# CONFIG_LTC2471 is not set -# CONFIG_LTC2485 is not set -# CONFIG_LTC2496 is not set -# CONFIG_LTC2497 is not set -# CONFIG_MAX1027 is not set -# CONFIG_MAX11100 is not set -# CONFIG_MAX1118 is not set -# CONFIG_MAX11205 is not set -# CONFIG_MAX11410 is not set -# CONFIG_MAX1241 is not set -# CONFIG_MAX1363 is not set -# CONFIG_MAX9611 is not set -# CONFIG_MCP320X is not set -# CONFIG_MCP3422 is not set -# CONFIG_MCP3911 is not set -# CONFIG_NAU7802 is not set -# CONFIG_RICHTEK_RTQ6056 is not set -# CONFIG_RZG2L_ADC is not set -# CONFIG_SD_ADC_MODULATOR is not set -# CONFIG_TI_ADC081C is not set -# CONFIG_TI_ADC0832 is not set -# CONFIG_TI_ADC084S021 is not set -# CONFIG_TI_ADC12138 is not set -# CONFIG_TI_ADC108S102 is not set -# CONFIG_TI_ADC128S052 is not set -# CONFIG_TI_ADC161S626 is not set -# CONFIG_TI_ADS1015 is not set -# CONFIG_TI_ADS7924 is not set -# CONFIG_TI_ADS7950 is not set -# CONFIG_TI_ADS8344 is not set -# CONFIG_TI_ADS8688 is not set -# CONFIG_TI_ADS124S08 is not set -# CONFIG_TI_ADS131E08 is not set -# CONFIG_TI_LMP92064 is not set -# CONFIG_TI_TLC4541 is not set -# CONFIG_TI_TSC2046 is not set -# CONFIG_VF610_ADC is not set -# CONFIG_XILINX_XADC is not set -# end of Analog to digital converters - -# -# Analog to digital and digital to analog converters -# -# CONFIG_AD74115 is not set -# CONFIG_AD74413R is not set -# end of Analog to digital and digital to analog converters - -# -# Analog Front Ends -# -# CONFIG_IIO_RESCALE is not set -# end of Analog Front Ends - -# -# Amplifiers -# -# CONFIG_AD8366 is not set -# CONFIG_ADA4250 is not set -# CONFIG_HMC425 is not set -# end of Amplifiers - -# -# Capacitance to digital converters -# -# CONFIG_AD7150 is not set -# CONFIG_AD7746 is not set -# end of Capacitance to digital converters - -# -# Chemical Sensors -# -# CONFIG_ATLAS_PH_SENSOR is not set -# CONFIG_ATLAS_EZO_SENSOR is not set -# CONFIG_BME680 is not set -# CONFIG_CCS811 is not set -# CONFIG_IAQCORE is not set -# CONFIG_SCD30_CORE is not set -# CONFIG_SCD4X is not set -# CONFIG_SENSIRION_SGP30 is not set -# CONFIG_SENSIRION_SGP40 is not set -# CONFIG_SPS30_I2C is not set -# CONFIG_SENSEAIR_SUNRISE_CO2 is not set -# CONFIG_VZ89X is not set -# end of Chemical Sensors - -# -# Hid Sensor IIO Common -# -# end of Hid Sensor IIO Common - -# -# IIO SCMI Sensors -# -# end of IIO SCMI Sensors - -# -# SSP Sensor Common -# -# CONFIG_IIO_SSP_SENSORHUB is not set -# end of SSP Sensor Common - -# -# Digital to analog converters -# -# CONFIG_AD3552R is not set -# CONFIG_AD5064 is not set -# CONFIG_AD5360 is not set -# CONFIG_AD5380 is not set -# CONFIG_AD5421 is not set -# CONFIG_AD5446 is not set -# CONFIG_AD5449 is not set -# CONFIG_AD5592R is not set -# CONFIG_AD5593R is not set -# CONFIG_AD5504 is not set -# CONFIG_AD5624R_SPI is not set -# CONFIG_LTC2688 is not set -# CONFIG_AD5686_SPI is not set -# CONFIG_AD5696_I2C is not set -# CONFIG_AD5755 is not set -# CONFIG_AD5758 is not set -# CONFIG_AD5761 is not set -# CONFIG_AD5764 is not set -# CONFIG_AD5766 is not set -# CONFIG_AD5770R is not set -# CONFIG_AD5791 is not set -# CONFIG_AD7293 is not set -# CONFIG_AD7303 is not set -# CONFIG_AD8801 is not set -# CONFIG_DPOT_DAC is not set -# CONFIG_DS4424 is not set -# CONFIG_LTC1660 is not set -# CONFIG_LTC2632 is not set -# CONFIG_M62332 is not set -# CONFIG_MAX517 is not set -# CONFIG_MAX5522 is not set -# CONFIG_MAX5821 is not set -# CONFIG_MCP4725 is not set -# CONFIG_MCP4922 is not set -# CONFIG_TI_DAC082S085 is not set -# CONFIG_TI_DAC5571 is not set -# CONFIG_TI_DAC7311 is not set -# CONFIG_TI_DAC7612 is not set -# CONFIG_VF610_DAC is not set -# end of Digital to analog converters - -# -# IIO dummy driver -# -# end of IIO dummy driver - -# -# Filters -# -# CONFIG_ADMV8818 is not set -# end of Filters - -# -# Frequency Synthesizers DDS/PLL -# - -# -# Clock Generator/Distribution -# -# CONFIG_AD9523 is not set -# end of Clock Generator/Distribution - -# -# Phase-Locked Loop (PLL) frequency synthesizers -# -# CONFIG_ADF4350 is not set -# CONFIG_ADF4371 is not set -# CONFIG_ADF4377 is not set -# CONFIG_ADMV1013 is not set -# CONFIG_ADMV1014 is not set -# CONFIG_ADMV4420 is not set -# CONFIG_ADRF6780 is not set -# end of Phase-Locked Loop (PLL) frequency synthesizers -# end of Frequency Synthesizers DDS/PLL - -# -# Digital gyroscope sensors -# -# CONFIG_ADIS16080 is not set -# CONFIG_ADIS16130 is not set -# CONFIG_ADIS16136 is not set -# CONFIG_ADIS16260 is not set -# CONFIG_ADXRS290 is not set -# CONFIG_ADXRS450 is not set -# CONFIG_BMG160 is not set -# CONFIG_FXAS21002C is not set -# CONFIG_MPU3050_I2C is not set -# CONFIG_IIO_ST_GYRO_3AXIS is not set -# CONFIG_ITG3200 is not set -# end of Digital gyroscope sensors - -# -# Health Sensors -# - -# -# Heart Rate Monitors -# -# CONFIG_AFE4403 is not set -# CONFIG_AFE4404 is not set -# CONFIG_MAX30100 is not set -# CONFIG_MAX30102 is not set -# end of Heart Rate Monitors -# end of Health Sensors - -# -# Humidity sensors -# -# CONFIG_AM2315 is not set -# CONFIG_DHT11 is not set -# CONFIG_HDC100X is not set -# CONFIG_HDC2010 is not set -# CONFIG_HTS221 is not set -# CONFIG_HTU21 is not set -# CONFIG_SI7005 is not set -# CONFIG_SI7020 is not set -# end of Humidity sensors - -# -# Inertial measurement units -# -# CONFIG_ADIS16400 is not set -# CONFIG_ADIS16460 is not set -# CONFIG_ADIS16475 is not set -# CONFIG_ADIS16480 is not set -# CONFIG_BMI160_I2C is not set -# CONFIG_BMI160_SPI is not set -# CONFIG_BOSCH_BNO055_I2C is not set -# CONFIG_FXOS8700_I2C is not set -# CONFIG_FXOS8700_SPI is not set -# CONFIG_KMX61 is not set -# CONFIG_INV_ICM42600_I2C is not set -# CONFIG_INV_ICM42600_SPI is not set -# CONFIG_INV_MPU6050_I2C is not set -# CONFIG_INV_MPU6050_SPI is not set -# CONFIG_IIO_ST_LSM6DSX is not set -# CONFIG_IIO_ST_LSM9DS0 is not set -# end of Inertial measurement units - -# -# Light sensors -# -# CONFIG_ADJD_S311 is not set -# CONFIG_ADUX1020 is not set -# CONFIG_AL3010 is not set -# CONFIG_AL3320A is not set -# CONFIG_APDS9300 is not set -# CONFIG_APDS9960 is not set -# CONFIG_AS73211 is not set -# CONFIG_BH1750 is not set -# CONFIG_BH1780 is not set -# CONFIG_CM32181 is not set -# CONFIG_CM3232 is not set -# CONFIG_CM3323 is not set -# CONFIG_CM3605 is not set -# CONFIG_CM36651 is not set -# CONFIG_GP2AP002 is not set -# CONFIG_GP2AP020A00F is not set -# CONFIG_SENSORS_ISL29018 is not set -# CONFIG_SENSORS_ISL29028 is not set -# CONFIG_ISL29125 is not set -# CONFIG_JSA1212 is not set -# CONFIG_RPR0521 is not set -# CONFIG_LTR501 is not set -# CONFIG_LTRF216A is not set -# CONFIG_LV0104CS is not set -# CONFIG_MAX44000 is not set -# CONFIG_MAX44009 is not set -# CONFIG_NOA1305 is not set -# CONFIG_OPT3001 is not set -# CONFIG_PA12203001 is not set -# CONFIG_SI1133 is not set -# CONFIG_SI1145 is not set -# CONFIG_STK3310 is not set -# CONFIG_ST_UVIS25 is not set -# CONFIG_TCS3414 is not set -# CONFIG_TCS3472 is not set -# CONFIG_SENSORS_TSL2563 is not set -# CONFIG_TSL2583 is not set -# CONFIG_TSL2591 is not set -# CONFIG_TSL2772 is not set -# CONFIG_TSL4531 is not set -# CONFIG_US5182D is not set -# CONFIG_VCNL4000 is not set -# CONFIG_VCNL4035 is not set -# CONFIG_VEML6030 is not set -# CONFIG_VEML6070 is not set -# CONFIG_VL6180 is not set -# CONFIG_ZOPT2201 is not set -# end of Light sensors - -# -# Magnetometer sensors -# -# CONFIG_AK8974 is not set -# CONFIG_AK8975 is not set -# CONFIG_AK09911 is not set -# CONFIG_BMC150_MAGN_I2C is not set -# CONFIG_BMC150_MAGN_SPI is not set -# CONFIG_MAG3110 is not set -# CONFIG_MMC35240 is not set -# CONFIG_IIO_ST_MAGN_3AXIS is not set -# CONFIG_SENSORS_HMC5843_I2C is not set -# CONFIG_SENSORS_HMC5843_SPI is not set -# CONFIG_SENSORS_RM3100_I2C is not set -# CONFIG_SENSORS_RM3100_SPI is not set -# CONFIG_TI_TMAG5273 is not set -# CONFIG_YAMAHA_YAS530 is not set -# end of Magnetometer sensors - -# -# Multiplexers -# -# CONFIG_IIO_MUX is not set -# end of Multiplexers - -# -# Inclinometer sensors -# -# end of Inclinometer sensors - -# -# Linear and angular position sensors -# -# end of Linear and angular position sensors - -# -# Digital potentiometers -# -# CONFIG_AD5110 is not set -# CONFIG_AD5272 is not set -# CONFIG_DS1803 is not set -# CONFIG_MAX5432 is not set -# CONFIG_MAX5481 is not set -# CONFIG_MAX5487 is not set -# CONFIG_MCP4018 is not set -# CONFIG_MCP4131 is not set -# CONFIG_MCP4531 is not set -# CONFIG_MCP41010 is not set -# CONFIG_TPL0102 is not set -# end of Digital potentiometers - -# -# Digital potentiostats -# -# CONFIG_LMP91000 is not set -# end of Digital potentiostats - -# -# Pressure sensors -# -# CONFIG_ABP060MG is not set -# CONFIG_BMP280 is not set -# CONFIG_DLHL60D is not set -# CONFIG_DPS310 is not set -# CONFIG_HP03 is not set -# CONFIG_ICP10100 is not set -# CONFIG_MPL115_I2C is not set -# CONFIG_MPL115_SPI is not set -# CONFIG_MPL3115 is not set -# CONFIG_MS5611 is not set -# CONFIG_MS5637 is not set -# CONFIG_IIO_ST_PRESS is not set -# CONFIG_T5403 is not set -# CONFIG_HP206C is not set -# CONFIG_ZPA2326 is not set -# end of Pressure sensors - -# -# Lightning sensors -# -# CONFIG_AS3935 is not set -# end of Lightning sensors - -# -# Proximity and distance sensors -# -# CONFIG_ISL29501 is not set -# CONFIG_LIDAR_LITE_V2 is not set -# CONFIG_MB1232 is not set -# CONFIG_PING is not set -# CONFIG_RFD77402 is not set -# CONFIG_SRF04 is not set -# CONFIG_SX9310 is not set -# CONFIG_SX9324 is not set -# CONFIG_SX9360 is not set -# CONFIG_SX9500 is not set -# CONFIG_SRF08 is not set -# CONFIG_VCNL3020 is not set -# CONFIG_VL53L0X_I2C is not set -# end of Proximity and distance sensors - -# -# Resolver to digital converters -# -# CONFIG_AD2S90 is not set -# CONFIG_AD2S1200 is not set -# end of Resolver to digital converters - -# -# Temperature sensors -# -# CONFIG_LTC2983 is not set -# CONFIG_MAXIM_THERMOCOUPLE is not set -# CONFIG_MLX90614 is not set -# CONFIG_MLX90632 is not set -# CONFIG_TMP006 is not set -# CONFIG_TMP007 is not set -# CONFIG_TMP117 is not set -# CONFIG_TSYS01 is not set -# CONFIG_TSYS02D is not set -# CONFIG_MAX30208 is not set -# CONFIG_MAX31856 is not set -# CONFIG_MAX31865 is not set -# end of Temperature sensors - -# CONFIG_NTB is not set -# CONFIG_PWM is not set - -# -# IRQ chip support -# -CONFIG_IRQCHIP=y -# CONFIG_AL_FIC is not set -CONFIG_RENESAS_RZG2L_IRQC=y -# CONFIG_XILINX_INTC is not set -CONFIG_RISCV_INTC=y -CONFIG_SIFIVE_PLIC=y -# end of IRQ chip support - -# CONFIG_IPACK_BUS is not set -CONFIG_RESET_CONTROLLER=y -CONFIG_RESET_POLARFIRE_SOC=y -# CONFIG_RESET_RZG2L_USBPHY_CTRL is not set -CONFIG_RESET_SIMPLE=y -CONFIG_RESET_STARFIVE_JH7100=y -CONFIG_RESET_SUNXI=y -# CONFIG_RESET_TI_SYSCON is not set -# CONFIG_RESET_TI_TPS380X is not set - -# -# PHY Subsystem -# -CONFIG_GENERIC_PHY=y -CONFIG_GENERIC_PHY_MIPI_DPHY=y -# CONFIG_PHY_CAN_TRANSCEIVER is not set -CONFIG_PHY_SUN4I_USB=m -CONFIG_PHY_SUN6I_MIPI_DPHY=m -# CONFIG_PHY_SUN9I_USB is not set -# CONFIG_PHY_SUN50I_USB3 is not set - -# -# PHY drivers for Broadcom platforms -# -# CONFIG_BCM_KONA_USB2_PHY is not set -# end of PHY drivers for Broadcom platforms - -# CONFIG_PHY_CADENCE_TORRENT is not set -# CONFIG_PHY_CADENCE_DPHY is not set -# CONFIG_PHY_CADENCE_DPHY_RX is not set -# CONFIG_PHY_CADENCE_SIERRA is not set -# CONFIG_PHY_CADENCE_SALVO is not set -# CONFIG_PHY_PXA_28NM_HSIC is not set -# CONFIG_PHY_PXA_28NM_USB2 is not set -# CONFIG_PHY_LAN966X_SERDES is not set -# CONFIG_PHY_CPCAP_USB is not set -# CONFIG_PHY_MAPPHONE_MDM6600 is not set -# CONFIG_PHY_OCELOT_SERDES is not set -# CONFIG_PHY_R8A779F0_ETHERNET_SERDES is not set -# CONFIG_PHY_RCAR_GEN2 is not set -# CONFIG_PHY_RCAR_GEN3_PCIE is not set -# CONFIG_PHY_RCAR_GEN3_USB2 is not set -# CONFIG_PHY_RCAR_GEN3_USB3 is not set -# end of PHY Subsystem - -# CONFIG_POWERCAP is not set -# CONFIG_MCB is not set - -# -# Performance monitor support -# -CONFIG_RISCV_PMU=y -CONFIG_RISCV_PMU_LEGACY=y -CONFIG_RISCV_PMU_SBI=y -# end of Performance monitor support - -# CONFIG_RAS is not set -# CONFIG_USB4 is not set - -# -# Android -# -# CONFIG_ANDROID_BINDER_IPC is not set -# end of Android - -CONFIG_LIBNVDIMM=y -CONFIG_BLK_DEV_PMEM=y -CONFIG_ND_CLAIM=y -CONFIG_ND_BTT=y -CONFIG_BTT=y -CONFIG_OF_PMEM=y -CONFIG_DAX=y -CONFIG_NVMEM=y -CONFIG_NVMEM_SYSFS=y -# CONFIG_NVMEM_RMEM is not set -CONFIG_NVMEM_SUNXI_SID=y - -# -# HW tracing support -# -# CONFIG_STM is not set -# CONFIG_INTEL_TH is not set -# end of HW tracing support - -# CONFIG_FPGA is not set -# CONFIG_FSI is not set -# CONFIG_SIOX is not set -# CONFIG_SLIMBUS is not set -# CONFIG_INTERCONNECT is not set -# CONFIG_COUNTER is not set -# CONFIG_MOST is not set -# CONFIG_PECI is not set -# CONFIG_HTE is not set -# end of Device Drivers - -# -# File systems -# -# CONFIG_VALIDATE_FS_PARSER is not set -CONFIG_FS_IOMAP=y -CONFIG_LEGACY_DIRECT_IO=y -# CONFIG_EXT2_FS is not set -# CONFIG_EXT3_FS is not set -CONFIG_EXT4_FS=y -CONFIG_EXT4_USE_FOR_EXT2=y -CONFIG_EXT4_FS_POSIX_ACL=y -CONFIG_EXT4_FS_SECURITY=y -# CONFIG_EXT4_DEBUG is not set -CONFIG_JBD2=y -# CONFIG_JBD2_DEBUG is not set -CONFIG_FS_MBCACHE=y -# CONFIG_REISERFS_FS is not set -# CONFIG_JFS_FS is not set -# CONFIG_XFS_FS is not set -# CONFIG_GFS2_FS is not set -# CONFIG_OCFS2_FS is not set -CONFIG_BTRFS_FS=m -CONFIG_BTRFS_FS_POSIX_ACL=y -# CONFIG_BTRFS_FS_CHECK_INTEGRITY is not set -# CONFIG_BTRFS_FS_RUN_SANITY_TESTS is not set -# CONFIG_BTRFS_DEBUG is not set -# CONFIG_BTRFS_ASSERT is not set -# CONFIG_BTRFS_FS_REF_VERIFY is not set -# CONFIG_NILFS2_FS is not set -# CONFIG_F2FS_FS is not set -CONFIG_FS_POSIX_ACL=y -CONFIG_EXPORTFS=y -# CONFIG_EXPORTFS_BLOCK_OPS is not set -CONFIG_FILE_LOCKING=y -# CONFIG_FS_ENCRYPTION is not set -# CONFIG_FS_VERITY is not set -CONFIG_FSNOTIFY=y -CONFIG_DNOTIFY=y -CONFIG_INOTIFY_USER=y -# CONFIG_FANOTIFY is not set -# CONFIG_QUOTA is not set -CONFIG_AUTOFS4_FS=y -CONFIG_AUTOFS_FS=y -# CONFIG_FUSE_FS is not set -CONFIG_OVERLAY_FS=m -# CONFIG_OVERLAY_FS_REDIRECT_DIR is not set -CONFIG_OVERLAY_FS_REDIRECT_ALWAYS_FOLLOW=y -# CONFIG_OVERLAY_FS_INDEX is not set -# CONFIG_OVERLAY_FS_XINO_AUTO is not set -# CONFIG_OVERLAY_FS_METACOPY is not set - -# -# Caches -# -CONFIG_NETFS_SUPPORT=y -# CONFIG_NETFS_STATS is not set -# CONFIG_FSCACHE is not set -# end of Caches - -# -# CD-ROM/DVD Filesystems -# -CONFIG_ISO9660_FS=y -CONFIG_JOLIET=y -CONFIG_ZISOFS=y -# CONFIG_UDF_FS is not set -# end of CD-ROM/DVD Filesystems - -# -# DOS/FAT/EXFAT/NT Filesystems -# -CONFIG_FAT_FS=y -CONFIG_MSDOS_FS=y -CONFIG_VFAT_FS=y -CONFIG_FAT_DEFAULT_CODEPAGE=437 -CONFIG_FAT_DEFAULT_IOCHARSET="iso8859-1" -# CONFIG_FAT_DEFAULT_UTF8 is not set -# CONFIG_EXFAT_FS is not set -# CONFIG_NTFS_FS is not set -# CONFIG_NTFS3_FS is not set -# end of DOS/FAT/EXFAT/NT Filesystems - -# -# Pseudo filesystems -# -CONFIG_PROC_FS=y -# CONFIG_PROC_KCORE is not set -CONFIG_PROC_SYSCTL=y -CONFIG_PROC_PAGE_MONITOR=y -CONFIG_PROC_CHILDREN=y -CONFIG_KERNFS=y -CONFIG_SYSFS=y -CONFIG_TMPFS=y -CONFIG_TMPFS_POSIX_ACL=y -CONFIG_TMPFS_XATTR=y -# CONFIG_TMPFS_INODE64 is not set -CONFIG_ARCH_SUPPORTS_HUGETLBFS=y -CONFIG_HUGETLBFS=y -CONFIG_HUGETLB_PAGE=y -CONFIG_ARCH_WANT_HUGETLB_PAGE_OPTIMIZE_VMEMMAP=y -CONFIG_HUGETLB_PAGE_OPTIMIZE_VMEMMAP=y -# CONFIG_HUGETLB_PAGE_OPTIMIZE_VMEMMAP_DEFAULT_ON is not set -CONFIG_MEMFD_CREATE=y -CONFIG_ARCH_HAS_GIGANTIC_PAGE=y -CONFIG_CONFIGFS_FS=y -CONFIG_EFIVAR_FS=m -# end of Pseudo filesystems - -CONFIG_MISC_FILESYSTEMS=y -# CONFIG_ORANGEFS_FS is not set -# CONFIG_ADFS_FS is not set -# CONFIG_AFFS_FS is not set -# CONFIG_ECRYPT_FS is not set -# CONFIG_HFS_FS is not set -# CONFIG_HFSPLUS_FS is not set -# CONFIG_BEFS_FS is not set -# CONFIG_BFS_FS is not set -# CONFIG_EFS_FS is not set -# CONFIG_CRAMFS is not set -# CONFIG_SQUASHFS is not set -# CONFIG_VXFS_FS is not set -# CONFIG_MINIX_FS is not set -# CONFIG_OMFS_FS is not set -# CONFIG_HPFS_FS is not set -# CONFIG_QNX4FS_FS is not set -# CONFIG_QNX6FS_FS is not set -# CONFIG_ROMFS_FS is not set -# CONFIG_PSTORE is not set -# CONFIG_SYSV_FS is not set -# CONFIG_UFS_FS is not set -# CONFIG_EROFS_FS is not set -CONFIG_NETWORK_FILESYSTEMS=y -CONFIG_NFS_FS=y -CONFIG_NFS_V2=y -CONFIG_NFS_V3=y -# CONFIG_NFS_V3_ACL is not set -CONFIG_NFS_V4=y -# CONFIG_NFS_SWAP is not set -CONFIG_NFS_V4_1=y -CONFIG_NFS_V4_2=y -CONFIG_PNFS_FILE_LAYOUT=y -CONFIG_PNFS_BLOCK=y -CONFIG_PNFS_FLEXFILE_LAYOUT=y -CONFIG_NFS_V4_1_IMPLEMENTATION_ID_DOMAIN="kernel.org" -# CONFIG_NFS_V4_1_MIGRATION is not set -CONFIG_NFS_V4_SECURITY_LABEL=y -CONFIG_ROOT_NFS=y -# CONFIG_NFS_USE_LEGACY_DNS is not set -CONFIG_NFS_USE_KERNEL_DNS=y -CONFIG_NFS_DISABLE_UDP_SUPPORT=y -# CONFIG_NFS_V4_2_READ_PLUS is not set -# CONFIG_NFSD is not set -CONFIG_GRACE_PERIOD=y -CONFIG_LOCKD=y -CONFIG_LOCKD_V4=y -CONFIG_NFS_COMMON=y -CONFIG_NFS_V4_2_SSC_HELPER=y -CONFIG_SUNRPC=y -CONFIG_SUNRPC_GSS=y -CONFIG_SUNRPC_BACKCHANNEL=y -CONFIG_RPCSEC_GSS_KRB5=y -# CONFIG_SUNRPC_DEBUG is not set -# CONFIG_CEPH_FS is not set -# CONFIG_CIFS is not set -# CONFIG_SMB_SERVER is not set -# CONFIG_CODA_FS is not set -# CONFIG_AFS_FS is not set -CONFIG_9P_FS=y -# CONFIG_9P_FS_POSIX_ACL is not set -# CONFIG_9P_FS_SECURITY is not set -CONFIG_NLS=y -CONFIG_NLS_DEFAULT="iso8859-1" -CONFIG_NLS_CODEPAGE_437=y -# CONFIG_NLS_CODEPAGE_737 is not set -# CONFIG_NLS_CODEPAGE_775 is not set -# CONFIG_NLS_CODEPAGE_850 is not set -# CONFIG_NLS_CODEPAGE_852 is not set -# CONFIG_NLS_CODEPAGE_855 is not set -# CONFIG_NLS_CODEPAGE_857 is not set -# CONFIG_NLS_CODEPAGE_860 is not set -# CONFIG_NLS_CODEPAGE_861 is not set -# CONFIG_NLS_CODEPAGE_862 is not set -# CONFIG_NLS_CODEPAGE_863 is not set -# CONFIG_NLS_CODEPAGE_864 is not set -# CONFIG_NLS_CODEPAGE_865 is not set -# CONFIG_NLS_CODEPAGE_866 is not set -# CONFIG_NLS_CODEPAGE_869 is not set -# CONFIG_NLS_CODEPAGE_936 is not set -# CONFIG_NLS_CODEPAGE_950 is not set -# CONFIG_NLS_CODEPAGE_932 is not set -# CONFIG_NLS_CODEPAGE_949 is not set -# CONFIG_NLS_CODEPAGE_874 is not set -# CONFIG_NLS_ISO8859_8 is not set -# CONFIG_NLS_CODEPAGE_1250 is not set -# CONFIG_NLS_CODEPAGE_1251 is not set -# CONFIG_NLS_ASCII is not set -CONFIG_NLS_ISO8859_1=y -# CONFIG_NLS_ISO8859_2 is not set -# CONFIG_NLS_ISO8859_3 is not set -# CONFIG_NLS_ISO8859_4 is not set -# CONFIG_NLS_ISO8859_5 is not set -# CONFIG_NLS_ISO8859_6 is not set -# CONFIG_NLS_ISO8859_7 is not set -# CONFIG_NLS_ISO8859_9 is not set -# CONFIG_NLS_ISO8859_13 is not set -# CONFIG_NLS_ISO8859_14 is not set -# CONFIG_NLS_ISO8859_15 is not set -# CONFIG_NLS_KOI8_R is not set -# CONFIG_NLS_KOI8_U is not set -# CONFIG_NLS_MAC_ROMAN is not set -# CONFIG_NLS_MAC_CELTIC is not set -# CONFIG_NLS_MAC_CENTEURO is not set -# CONFIG_NLS_MAC_CROATIAN is not set -# CONFIG_NLS_MAC_CYRILLIC is not set -# CONFIG_NLS_MAC_GAELIC is not set -# CONFIG_NLS_MAC_GREEK is not set -# CONFIG_NLS_MAC_ICELAND is not set -# CONFIG_NLS_MAC_INUIT is not set -# CONFIG_NLS_MAC_ROMANIAN is not set -# CONFIG_NLS_MAC_TURKISH is not set -# CONFIG_NLS_UTF8 is not set -# CONFIG_DLM is not set -# CONFIG_UNICODE is not set -CONFIG_IO_WQ=y -# end of File systems - -# -# Security options -# -CONFIG_KEYS=y -# CONFIG_KEYS_REQUEST_CACHE is not set -# CONFIG_PERSISTENT_KEYRINGS is not set -# CONFIG_TRUSTED_KEYS is not set -# CONFIG_ENCRYPTED_KEYS is not set -# CONFIG_KEY_DH_OPERATIONS is not set -# CONFIG_SECURITY_DMESG_RESTRICT is not set -CONFIG_SECURITY=y -CONFIG_SECURITYFS=y -CONFIG_SECURITY_NETWORK=y -# CONFIG_SECURITY_NETWORK_XFRM is not set -CONFIG_SECURITY_PATH=y -CONFIG_LSM_MMAP_MIN_ADDR=65536 -CONFIG_HAVE_HARDENED_USERCOPY_ALLOCATOR=y -# CONFIG_HARDENED_USERCOPY is not set -# CONFIG_FORTIFY_SOURCE is not set -# CONFIG_STATIC_USERMODEHELPER is not set -CONFIG_SECURITY_SELINUX=y -# CONFIG_SECURITY_SELINUX_BOOTPARAM is not set -# CONFIG_SECURITY_SELINUX_DISABLE is not set -CONFIG_SECURITY_SELINUX_DEVELOP=y -CONFIG_SECURITY_SELINUX_AVC_STATS=y -CONFIG_SECURITY_SELINUX_CHECKREQPROT_VALUE=0 -CONFIG_SECURITY_SELINUX_SIDTAB_HASH_BITS=9 -CONFIG_SECURITY_SELINUX_SID2STR_CACHE_SIZE=256 -# CONFIG_SECURITY_SMACK is not set -# CONFIG_SECURITY_TOMOYO is not set -CONFIG_SECURITY_APPARMOR=y -# CONFIG_SECURITY_APPARMOR_DEBUG is not set -CONFIG_SECURITY_APPARMOR_INTROSPECT_POLICY=y -CONFIG_SECURITY_APPARMOR_HASH=y -CONFIG_SECURITY_APPARMOR_HASH_DEFAULT=y -CONFIG_SECURITY_APPARMOR_EXPORT_BINARY=y -CONFIG_SECURITY_APPARMOR_PARANOID_LOAD=y -# CONFIG_SECURITY_LOADPIN is not set -# CONFIG_SECURITY_YAMA is not set -# CONFIG_SECURITY_SAFESETID is not set -# CONFIG_SECURITY_LOCKDOWN_LSM is not set -# CONFIG_SECURITY_LANDLOCK is not set -CONFIG_INTEGRITY=y -# CONFIG_INTEGRITY_SIGNATURE is not set -CONFIG_INTEGRITY_AUDIT=y -# CONFIG_IMA is not set -# CONFIG_EVM is not set -# CONFIG_DEFAULT_SECURITY_SELINUX is not set -# CONFIG_DEFAULT_SECURITY_APPARMOR is not set -CONFIG_DEFAULT_SECURITY_DAC=y -CONFIG_LSM="landlock,lockdown,yama,loadpin,safesetid,integrity,bpf" - -# -# Kernel hardening options -# - -# -# Memory initialization -# -CONFIG_INIT_STACK_NONE=y -# CONFIG_GCC_PLUGIN_STRUCTLEAK_USER is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF_ALL is not set -# CONFIG_INIT_ON_ALLOC_DEFAULT_ON is not set -# CONFIG_INIT_ON_FREE_DEFAULT_ON is not set -CONFIG_CC_HAS_ZERO_CALL_USED_REGS=y -# CONFIG_ZERO_CALL_USED_REGS is not set -# end of Memory initialization - -CONFIG_RANDSTRUCT_NONE=y -# CONFIG_RANDSTRUCT_FULL is not set -# CONFIG_RANDSTRUCT_PERFORMANCE is not set -# end of Kernel hardening options -# end of Security options - -CONFIG_XOR_BLOCKS=m -CONFIG_CRYPTO=y - -# -# Crypto core or helper -# -CONFIG_CRYPTO_ALGAPI=y -CONFIG_CRYPTO_ALGAPI2=y -CONFIG_CRYPTO_AEAD=y -CONFIG_CRYPTO_AEAD2=y -CONFIG_CRYPTO_SKCIPHER=y -CONFIG_CRYPTO_SKCIPHER2=y -CONFIG_CRYPTO_HASH=y -CONFIG_CRYPTO_HASH2=y -CONFIG_CRYPTO_RNG=m -CONFIG_CRYPTO_RNG2=y -CONFIG_CRYPTO_RNG_DEFAULT=m -CONFIG_CRYPTO_AKCIPHER2=y -CONFIG_CRYPTO_AKCIPHER=y -CONFIG_CRYPTO_KPP2=y -CONFIG_CRYPTO_ACOMP2=y -CONFIG_CRYPTO_MANAGER=y -CONFIG_CRYPTO_MANAGER2=y -# CONFIG_CRYPTO_USER is not set -CONFIG_CRYPTO_MANAGER_DISABLE_TESTS=y -CONFIG_CRYPTO_NULL=m -CONFIG_CRYPTO_NULL2=y -# CONFIG_CRYPTO_PCRYPT is not set -# CONFIG_CRYPTO_CRYPTD is not set -CONFIG_CRYPTO_AUTHENC=m -# CONFIG_CRYPTO_TEST is not set -CONFIG_CRYPTO_ENGINE=y -# end of Crypto core or helper - -# -# Public-key cryptography -# -CONFIG_CRYPTO_RSA=y -# CONFIG_CRYPTO_DH is not set -# CONFIG_CRYPTO_ECDH is not set -# CONFIG_CRYPTO_ECDSA is not set -# CONFIG_CRYPTO_ECRDSA is not set -# CONFIG_CRYPTO_SM2 is not set -# CONFIG_CRYPTO_CURVE25519 is not set -# end of Public-key cryptography - -# -# Block ciphers -# -CONFIG_CRYPTO_AES=m -# CONFIG_CRYPTO_AES_TI is not set -# CONFIG_CRYPTO_ANUBIS is not set -# CONFIG_CRYPTO_ARIA is not set -# CONFIG_CRYPTO_BLOWFISH is not set -# CONFIG_CRYPTO_CAMELLIA is not set -# CONFIG_CRYPTO_CAST5 is not set -# CONFIG_CRYPTO_CAST6 is not set -# CONFIG_CRYPTO_DES is not set -# CONFIG_CRYPTO_FCRYPT is not set -# CONFIG_CRYPTO_KHAZAD is not set -# CONFIG_CRYPTO_SEED is not set -# CONFIG_CRYPTO_SERPENT is not set -# CONFIG_CRYPTO_SM4_GENERIC is not set -# CONFIG_CRYPTO_TEA is not set -# CONFIG_CRYPTO_TWOFISH is not set -# end of Block ciphers - -# -# Length-preserving ciphers and modes -# -# CONFIG_CRYPTO_ADIANTUM is not set -# CONFIG_CRYPTO_ARC4 is not set -# CONFIG_CRYPTO_CHACHA20 is not set -CONFIG_CRYPTO_CBC=m -# CONFIG_CRYPTO_CFB is not set -CONFIG_CRYPTO_CTR=m -# CONFIG_CRYPTO_CTS is not set -# CONFIG_CRYPTO_ECB is not set -# CONFIG_CRYPTO_HCTR2 is not set -# CONFIG_CRYPTO_KEYWRAP is not set -# CONFIG_CRYPTO_LRW is not set -# CONFIG_CRYPTO_OFB is not set -# CONFIG_CRYPTO_PCBC is not set -# CONFIG_CRYPTO_XTS is not set -# end of Length-preserving ciphers and modes - -# -# AEAD (authenticated encryption with associated data) ciphers -# -# CONFIG_CRYPTO_AEGIS128 is not set -# CONFIG_CRYPTO_CHACHA20POLY1305 is not set -# CONFIG_CRYPTO_CCM is not set -CONFIG_CRYPTO_GCM=m -CONFIG_CRYPTO_SEQIV=m -CONFIG_CRYPTO_ECHAINIV=m -# CONFIG_CRYPTO_ESSIV is not set -# end of AEAD (authenticated encryption with associated data) ciphers - -# -# Hashes, digests, and MACs -# -CONFIG_CRYPTO_BLAKE2B=m -# CONFIG_CRYPTO_CMAC is not set -CONFIG_CRYPTO_GHASH=m -CONFIG_CRYPTO_HMAC=m -# CONFIG_CRYPTO_MD4 is not set -# CONFIG_CRYPTO_MD5 is not set -# CONFIG_CRYPTO_MICHAEL_MIC is not set -# CONFIG_CRYPTO_POLY1305 is not set -# CONFIG_CRYPTO_RMD160 is not set -CONFIG_CRYPTO_SHA1=y -CONFIG_CRYPTO_SHA256=m -CONFIG_CRYPTO_SHA512=m -# CONFIG_CRYPTO_SHA3 is not set -# CONFIG_CRYPTO_SM3_GENERIC is not set -# CONFIG_CRYPTO_STREEBOG is not set -# CONFIG_CRYPTO_VMAC is not set -# CONFIG_CRYPTO_WP512 is not set -# CONFIG_CRYPTO_XCBC is not set -CONFIG_CRYPTO_XXHASH=m -# end of Hashes, digests, and MACs - -# -# CRCs (cyclic redundancy checks) -# -CONFIG_CRYPTO_CRC32C=y -# CONFIG_CRYPTO_CRC32 is not set -# CONFIG_CRYPTO_CRCT10DIF is not set -# end of CRCs (cyclic redundancy checks) - -# -# Compression -# -# CONFIG_CRYPTO_DEFLATE is not set -# CONFIG_CRYPTO_LZO is not set -# CONFIG_CRYPTO_842 is not set -# CONFIG_CRYPTO_LZ4 is not set -# CONFIG_CRYPTO_LZ4HC is not set -# CONFIG_CRYPTO_ZSTD is not set -# end of Compression - -# -# Random number generation -# -# CONFIG_CRYPTO_ANSI_CPRNG is not set -CONFIG_CRYPTO_DRBG_MENU=m -CONFIG_CRYPTO_DRBG_HMAC=y -# CONFIG_CRYPTO_DRBG_HASH is not set -# CONFIG_CRYPTO_DRBG_CTR is not set -CONFIG_CRYPTO_DRBG=m -CONFIG_CRYPTO_JITTERENTROPY=m -# end of Random number generation - -# -# Userspace interface -# -CONFIG_CRYPTO_USER_API=y -CONFIG_CRYPTO_USER_API_HASH=y -# CONFIG_CRYPTO_USER_API_SKCIPHER is not set -# CONFIG_CRYPTO_USER_API_RNG is not set -# CONFIG_CRYPTO_USER_API_AEAD is not set -CONFIG_CRYPTO_USER_API_ENABLE_OBSOLETE=y -# end of Userspace interface - -CONFIG_CRYPTO_HW=y -CONFIG_CRYPTO_DEV_ALLWINNER=y -# CONFIG_CRYPTO_DEV_SUN4I_SS is not set -# CONFIG_CRYPTO_DEV_SUN8I_CE is not set -# CONFIG_CRYPTO_DEV_SUN8I_SS is not set -# CONFIG_CRYPTO_DEV_ATMEL_ECC is not set -# CONFIG_CRYPTO_DEV_ATMEL_SHA204A is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCC is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXX is not set -# CONFIG_CRYPTO_DEV_QAT_C62X is not set -# CONFIG_CRYPTO_DEV_QAT_4XXX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCCVF is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXXVF is not set -# CONFIG_CRYPTO_DEV_QAT_C62XVF is not set -# CONFIG_CRYPTO_DEV_NITROX_CNN55XX is not set -CONFIG_CRYPTO_DEV_VIRTIO=y -# CONFIG_CRYPTO_DEV_SAFEXCEL is not set -# CONFIG_CRYPTO_DEV_CCREE is not set -# CONFIG_CRYPTO_DEV_AMLOGIC_GXL is not set -# CONFIG_ASYMMETRIC_KEY_TYPE is not set - -# -# Certificates for signature checking -# -# CONFIG_SYSTEM_BLACKLIST_KEYRING is not set -# end of Certificates for signature checking - -CONFIG_BINARY_PRINTF=y - -# -# Library routines -# -CONFIG_RAID6_PQ=m -CONFIG_RAID6_PQ_BENCHMARK=y -CONFIG_LINEAR_RANGES=y -# CONFIG_PACKING is not set -CONFIG_BITREVERSE=y -CONFIG_GENERIC_STRNCPY_FROM_USER=y -CONFIG_GENERIC_STRNLEN_USER=y -CONFIG_GENERIC_NET_UTILS=y -# CONFIG_CORDIC is not set -# CONFIG_PRIME_NUMBERS is not set -CONFIG_RATIONAL=y -CONFIG_GENERIC_PCI_IOMAP=y - -# -# Crypto library routines -# -CONFIG_CRYPTO_LIB_UTILS=y -CONFIG_CRYPTO_LIB_AES=m -CONFIG_CRYPTO_LIB_GF128MUL=m -CONFIG_CRYPTO_LIB_BLAKE2S_GENERIC=y -# CONFIG_CRYPTO_LIB_CHACHA is not set -# CONFIG_CRYPTO_LIB_CURVE25519 is not set -CONFIG_CRYPTO_LIB_POLY1305_RSIZE=1 -# CONFIG_CRYPTO_LIB_POLY1305 is not set -# CONFIG_CRYPTO_LIB_CHACHA20POLY1305 is not set -CONFIG_CRYPTO_LIB_SHA1=y -CONFIG_CRYPTO_LIB_SHA256=m -# end of Crypto library routines - -CONFIG_CRC_CCITT=m -CONFIG_CRC16=y -# CONFIG_CRC_T10DIF is not set -# CONFIG_CRC64_ROCKSOFT is not set -CONFIG_CRC_ITU_T=y -CONFIG_CRC32=y -# CONFIG_CRC32_SELFTEST is not set -CONFIG_CRC32_SLICEBY8=y -# CONFIG_CRC32_SLICEBY4 is not set -# CONFIG_CRC32_SARWATE is not set -# CONFIG_CRC32_BIT is not set -# CONFIG_CRC64 is not set -# CONFIG_CRC4 is not set -CONFIG_CRC7=y -CONFIG_LIBCRC32C=m -# CONFIG_CRC8 is not set -CONFIG_XXHASH=y -CONFIG_AUDIT_GENERIC=y -# CONFIG_RANDOM32_SELFTEST is not set -CONFIG_ZLIB_INFLATE=y -CONFIG_ZLIB_DEFLATE=m -CONFIG_LZO_COMPRESS=m -CONFIG_LZO_DECOMPRESS=y -CONFIG_LZ4_DECOMPRESS=y -CONFIG_ZSTD_COMMON=y -CONFIG_ZSTD_COMPRESS=y -CONFIG_ZSTD_DECOMPRESS=y -CONFIG_XZ_DEC=y -CONFIG_XZ_DEC_X86=y -CONFIG_XZ_DEC_POWERPC=y -CONFIG_XZ_DEC_IA64=y -CONFIG_XZ_DEC_ARM=y -CONFIG_XZ_DEC_ARMTHUMB=y -CONFIG_XZ_DEC_SPARC=y -# CONFIG_XZ_DEC_MICROLZMA is not set -CONFIG_XZ_DEC_BCJ=y -# CONFIG_XZ_DEC_TEST is not set -CONFIG_DECOMPRESS_GZIP=y -CONFIG_DECOMPRESS_BZIP2=y -CONFIG_DECOMPRESS_LZMA=y -CONFIG_DECOMPRESS_XZ=y -CONFIG_DECOMPRESS_LZO=y -CONFIG_DECOMPRESS_LZ4=y -CONFIG_DECOMPRESS_ZSTD=y -CONFIG_GENERIC_ALLOCATOR=y -CONFIG_INTERVAL_TREE=y -CONFIG_ASSOCIATIVE_ARRAY=y -CONFIG_HAS_IOMEM=y -CONFIG_HAS_IOPORT_MAP=y -CONFIG_HAS_DMA=y -CONFIG_NEED_DMA_MAP_STATE=y -CONFIG_ARCH_DMA_ADDR_T_64BIT=y -CONFIG_DMA_DECLARE_COHERENT=y -CONFIG_ARCH_HAS_SETUP_DMA_OPS=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_DEVICE=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_CPU=y -CONFIG_ARCH_HAS_DMA_PREP_COHERENT=y -CONFIG_SWIOTLB=y -# CONFIG_DMA_RESTRICTED_POOL is not set -CONFIG_DMA_NONCOHERENT_MMAP=y -CONFIG_DMA_COHERENT_POOL=y -CONFIG_DMA_DIRECT_REMAP=y -# CONFIG_DMA_API_DEBUG is not set -# CONFIG_DMA_MAP_BENCHMARK is not set -CONFIG_SGL_ALLOC=y -# CONFIG_CPUMASK_OFFSTACK is not set -# CONFIG_FORCE_NR_CPUS is not set -CONFIG_CPU_RMAP=y -CONFIG_DQL=y -CONFIG_GLOB=y -# CONFIG_GLOB_SELFTEST is not set -CONFIG_NLATTR=y -CONFIG_CLZ_TAB=y -# CONFIG_IRQ_POLL is not set -CONFIG_MPILIB=y -CONFIG_LIBFDT=y -CONFIG_OID_REGISTRY=y -CONFIG_UCS2_STRING=y -CONFIG_HAVE_GENERIC_VDSO=y -CONFIG_GENERIC_GETTIMEOFDAY=y -CONFIG_GENERIC_VDSO_TIME_NS=y -CONFIG_FONT_SUPPORT=y -# CONFIG_FONTS is not set -CONFIG_FONT_8x8=y -CONFIG_FONT_8x16=y -CONFIG_SG_POOL=y -CONFIG_ARCH_HAS_PMEM_API=y -CONFIG_MEMREGION=y -CONFIG_ARCH_STACKWALK=y -CONFIG_STACKDEPOT=y -CONFIG_SBITMAP=y -# end of Library routines - -CONFIG_GENERIC_IOREMAP=y -CONFIG_GENERIC_LIB_DEVMEM_IS_ALLOWED=y - -# -# Kernel hacking -# - -# -# printk and dmesg options -# -CONFIG_PRINTK_TIME=y -# CONFIG_PRINTK_CALLER is not set -# CONFIG_STACKTRACE_BUILD_ID is not set -CONFIG_CONSOLE_LOGLEVEL_DEFAULT=7 -CONFIG_CONSOLE_LOGLEVEL_QUIET=4 -CONFIG_MESSAGE_LOGLEVEL_DEFAULT=4 -# CONFIG_BOOT_PRINTK_DELAY is not set -# CONFIG_DYNAMIC_DEBUG is not set -# CONFIG_DYNAMIC_DEBUG_CORE is not set -CONFIG_SYMBOLIC_ERRNAME=y -CONFIG_DEBUG_BUGVERBOSE=y -# end of printk and dmesg options - -CONFIG_DEBUG_KERNEL=y -CONFIG_DEBUG_MISC=y - -# -# Compile-time checks and compiler options -# -CONFIG_DEBUG_INFO_NONE=y -# CONFIG_DEBUG_INFO_DWARF_TOOLCHAIN_DEFAULT is not set -# CONFIG_DEBUG_INFO_DWARF4 is not set -# CONFIG_DEBUG_INFO_DWARF5 is not set -CONFIG_FRAME_WARN=2048 -# CONFIG_STRIP_ASM_SYMS is not set -# CONFIG_READABLE_ASM is not set -# CONFIG_HEADERS_INSTALL is not set -# CONFIG_DEBUG_SECTION_MISMATCH is not set -CONFIG_SECTION_MISMATCH_WARN_ONLY=y -CONFIG_ARCH_WANT_FRAME_POINTERS=y -CONFIG_FRAME_POINTER=y -# CONFIG_VMLINUX_MAP is not set -# CONFIG_DEBUG_FORCE_WEAK_PER_CPU is not set -# end of Compile-time checks and compiler options - -# -# Generic Kernel Debugging Instruments -# -# CONFIG_MAGIC_SYSRQ is not set -CONFIG_DEBUG_FS=y -CONFIG_DEBUG_FS_ALLOW_ALL=y -# CONFIG_DEBUG_FS_DISALLOW_MOUNT is not set -# CONFIG_DEBUG_FS_ALLOW_NONE is not set -CONFIG_HAVE_ARCH_KGDB=y -CONFIG_HAVE_ARCH_KGDB_QXFER_PKT=y -# CONFIG_KGDB is not set -CONFIG_ARCH_HAS_UBSAN_SANITIZE_ALL=y -# CONFIG_UBSAN is not set -CONFIG_HAVE_KCSAN_COMPILER=y -# end of Generic Kernel Debugging Instruments - -# -# Networking Debugging -# -# CONFIG_NET_DEV_REFCNT_TRACKER is not set -# CONFIG_NET_NS_REFCNT_TRACKER is not set -# CONFIG_DEBUG_NET is not set -# end of Networking Debugging - -# -# Memory Debugging -# -# CONFIG_PAGE_EXTENSION is not set -CONFIG_DEBUG_PAGEALLOC=y -# CONFIG_DEBUG_PAGEALLOC_ENABLE_DEFAULT is not set -CONFIG_SLUB_DEBUG=y -# CONFIG_SLUB_DEBUG_ON is not set -# CONFIG_PAGE_OWNER is not set -# CONFIG_PAGE_POISONING is not set -# CONFIG_DEBUG_RODATA_TEST is not set -CONFIG_ARCH_HAS_DEBUG_WX=y -# CONFIG_DEBUG_WX is not set -CONFIG_GENERIC_PTDUMP=y -# CONFIG_PTDUMP_DEBUGFS is not set -CONFIG_HAVE_DEBUG_KMEMLEAK=y -# CONFIG_DEBUG_KMEMLEAK is not set -# CONFIG_DEBUG_OBJECTS is not set -# CONFIG_SHRINKER_DEBUG is not set -# CONFIG_DEBUG_STACK_USAGE is not set -CONFIG_SCHED_STACK_END_CHECK=y -CONFIG_ARCH_HAS_DEBUG_VM_PGTABLE=y -CONFIG_DEBUG_VM_IRQSOFF=y -CONFIG_DEBUG_VM=y -# CONFIG_DEBUG_VM_MAPLE_TREE is not set -# CONFIG_DEBUG_VM_RB is not set -CONFIG_DEBUG_VM_PGFLAGS=y -CONFIG_DEBUG_VM_PGTABLE=y -CONFIG_ARCH_HAS_DEBUG_VIRTUAL=y -# CONFIG_DEBUG_VIRTUAL is not set -CONFIG_DEBUG_MEMORY_INIT=y -CONFIG_DEBUG_PER_CPU_MAPS=y -CONFIG_HAVE_ARCH_KASAN=y -CONFIG_HAVE_ARCH_KASAN_VMALLOC=y -CONFIG_CC_HAS_KASAN_GENERIC=y -CONFIG_CC_HAS_WORKING_NOSANITIZE_ADDRESS=y -# CONFIG_KASAN is not set -CONFIG_HAVE_ARCH_KFENCE=y -# CONFIG_KFENCE is not set -# end of Memory Debugging - -# CONFIG_DEBUG_SHIRQ is not set - -# -# Debug Oops, Lockups and Hangs -# -# CONFIG_PANIC_ON_OOPS is not set -CONFIG_PANIC_ON_OOPS_VALUE=0 -CONFIG_PANIC_TIMEOUT=0 -CONFIG_LOCKUP_DETECTOR=y -CONFIG_SOFTLOCKUP_DETECTOR=y -# CONFIG_BOOTPARAM_SOFTLOCKUP_PANIC is not set -CONFIG_DETECT_HUNG_TASK=y -CONFIG_DEFAULT_HUNG_TASK_TIMEOUT=120 -# CONFIG_BOOTPARAM_HUNG_TASK_PANIC is not set -CONFIG_WQ_WATCHDOG=y -# CONFIG_TEST_LOCKUP is not set -# end of Debug Oops, Lockups and Hangs - -# -# Scheduler Debugging -# -CONFIG_SCHED_DEBUG=y -# CONFIG_SCHEDSTATS is not set -# end of Scheduler Debugging - -CONFIG_DEBUG_TIMEKEEPING=y - -# -# Lock Debugging (spinlocks, mutexes, etc...) -# -CONFIG_LOCK_DEBUGGING_SUPPORT=y -# CONFIG_PROVE_LOCKING is not set -# CONFIG_LOCK_STAT is not set -CONFIG_DEBUG_RT_MUTEXES=y -CONFIG_DEBUG_SPINLOCK=y -CONFIG_DEBUG_MUTEXES=y -# CONFIG_DEBUG_WW_MUTEX_SLOWPATH is not set -CONFIG_DEBUG_RWSEMS=y -# CONFIG_DEBUG_LOCK_ALLOC is not set -CONFIG_DEBUG_ATOMIC_SLEEP=y -# CONFIG_DEBUG_LOCKING_API_SELFTESTS is not set -# CONFIG_LOCK_TORTURE_TEST is not set -# CONFIG_WW_MUTEX_SELFTEST is not set -# CONFIG_SCF_TORTURE_TEST is not set -# CONFIG_CSD_LOCK_WAIT_DEBUG is not set -# end of Lock Debugging (spinlocks, mutexes, etc...) - -# CONFIG_DEBUG_IRQFLAGS is not set -CONFIG_STACKTRACE=y -# CONFIG_WARN_ALL_UNSEEDED_RANDOM is not set -# CONFIG_DEBUG_KOBJECT is not set - -# -# Debug kernel data structures -# -CONFIG_DEBUG_LIST=y -CONFIG_DEBUG_PLIST=y -CONFIG_DEBUG_SG=y -# CONFIG_DEBUG_NOTIFIERS is not set -# CONFIG_BUG_ON_DATA_CORRUPTION is not set -# CONFIG_DEBUG_MAPLE_TREE is not set -# end of Debug kernel data structures - -# CONFIG_DEBUG_CREDENTIALS is not set - -# -# RCU Debugging -# -# CONFIG_RCU_SCALE_TEST is not set -# CONFIG_RCU_TORTURE_TEST is not set -# CONFIG_RCU_REF_SCALE_TEST is not set -CONFIG_RCU_CPU_STALL_TIMEOUT=21 -CONFIG_RCU_EXP_CPU_STALL_TIMEOUT=0 -# CONFIG_RCU_CPU_STALL_CPUTIME is not set -# CONFIG_RCU_TRACE is not set -CONFIG_RCU_EQS_DEBUG=y -# end of RCU Debugging - -# CONFIG_DEBUG_WQ_FORCE_RR_CPU is not set -# CONFIG_CPU_HOTPLUG_STATE_CONTROL is not set -# CONFIG_LATENCYTOP is not set -CONFIG_HAVE_RETHOOK=y -CONFIG_HAVE_FUNCTION_TRACER=y -CONFIG_HAVE_FUNCTION_GRAPH_TRACER=y -CONFIG_HAVE_DYNAMIC_FTRACE=y -CONFIG_HAVE_DYNAMIC_FTRACE_WITH_REGS=y -CONFIG_HAVE_FTRACE_MCOUNT_RECORD=y -CONFIG_HAVE_SYSCALL_TRACEPOINTS=y -CONFIG_TRACING_SUPPORT=y -# CONFIG_FTRACE is not set -# CONFIG_SAMPLES is not set -# CONFIG_STRICT_DEVMEM is not set - -# -# riscv Debugging -# -# end of riscv Debugging - -# -# Kernel Testing and Coverage -# -# CONFIG_KUNIT is not set -# CONFIG_NOTIFIER_ERROR_INJECTION is not set -# CONFIG_FAULT_INJECTION is not set -CONFIG_ARCH_HAS_KCOV=y -CONFIG_CC_HAS_SANCOV_TRACE_PC=y -# CONFIG_KCOV is not set -# CONFIG_RUNTIME_TESTING_MENU is not set -CONFIG_ARCH_USE_MEMTEST=y -CONFIG_MEMTEST=y -# end of Kernel Testing and Coverage - -# -# Rust hacking -# -# end of Rust hacking -# end of Kernel hacking diff --git a/patches/linux/linux-6.3.y/dts/mpfs-beaglev-fire-fabric.dtsi b/patches/linux/linux-6.3.y/dts/mpfs-beaglev-fire-fabric.dtsi deleted file mode 100644 index 1069134..0000000 --- a/patches/linux/linux-6.3.y/dts/mpfs-beaglev-fire-fabric.dtsi +++ /dev/null @@ -1,71 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/ { - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs-icicle-kit", - "microchip,mpfs"; - - core_pwm0: pwm@40000000 { - compatible = "microchip,corepwm-rtl-v4"; - reg = <0x0 0x40000000 0x0 0xF0>; - microchip,sync-update-mask = /bits/ 32 <0>; - #pwm-cells = <3>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - status = "disabled"; - }; - - i2c2: i2c@40000200 { - compatible = "microchip,corei2c-rtl-v7"; - reg = <0x0 0x40000200 0x0 0x100>; - #address-cells = <1>; - #size-cells = <0>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - interrupt-parent = <&plic>; - interrupts = <122>; - clock-frequency = <100000>; - status = "disabled"; - }; - - pcie: pcie@3000000000 { - compatible = "microchip,pcie-host-1.0"; - #address-cells = <0x3>; - #interrupt-cells = <0x1>; - #size-cells = <0x2>; - device_type = "pci"; - reg = <0x30 0x0 0x0 0x8000000>, <0x0 0x43000000 0x0 0x10000>; - reg-names = "cfg", "apb"; - bus-range = <0x0 0x7f>; - interrupt-parent = <&plic>; - interrupts = <119>; - interrupt-map = <0 0 0 1 &pcie_intc 0>, - <0 0 0 2 &pcie_intc 1>, - <0 0 0 3 &pcie_intc 2>, - <0 0 0 4 &pcie_intc 3>; - interrupt-map-mask = <0 0 0 7>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT1>, <&ccc_nw CLK_CCC_PLL0_OUT3>; - clock-names = "fic1", "fic3"; - ranges = <0x3000000 0x0 0x8000000 0x30 0x8000000 0x0 0x80000000>; - dma-ranges = <0x02000000 0x0 0x00000000 0x0 0x00000000 0x1 0x00000000>; - msi-parent = <&pcie>; - msi-controller; - status = "disabled"; - pcie_intc: interrupt-controller { - #address-cells = <0>; - #interrupt-cells = <1>; - interrupt-controller; - }; - }; - - refclk_ccc: cccrefclk { - compatible = "fixed-clock"; - #clock-cells = <0>; - }; -}; - -&ccc_nw { - clocks = <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, - <&refclk_ccc>, <&refclk_ccc>; - clock-names = "pll0_ref0", "pll0_ref1", "pll1_ref0", "pll1_ref1", - "dll0_ref", "dll1_ref"; - status = "okay"; -}; diff --git a/patches/linux/linux-6.3.y/dts/mpfs-beaglev-fire.dts b/patches/linux/linux-6.3.y/dts/mpfs-beaglev-fire.dts deleted file mode 100644 index c811d50..0000000 --- a/patches/linux/linux-6.3.y/dts/mpfs-beaglev-fire.dts +++ /dev/null @@ -1,323 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/dts-v1/; - -#include "mpfs.dtsi" -#include "mpfs-beaglev-fire-fabric.dtsi" -#include -#include - -/* Clock frequency (in Hz) of the rtcclk */ -#define RTCCLK_FREQ 1000000 - -/ { - #address-cells = <2>; - #size-cells = <2>; - model = "BeagleBoard BeagleV-Fire"; - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs"; - - aliases { - mmc0 = &mmc; - ethernet0 = &mac1; - serial0 = &mmuart0; - serial1 = &mmuart1; - serial2 = &mmuart2; - serial3 = &mmuart3; - serial4 = &mmuart4; - }; - - chosen { - stdout-path = "serial0:115200n8"; - }; - - cpus { - timebase-frequency = ; - }; - - ddrc_cache_lo: memory@80000000 { - device_type = "memory"; - reg = <0x0 0x80000000 0x0 0x40000000>; - status = "okay"; - }; - - ddrc_cache_hi: memory@1040000000 { - device_type = "memory"; - reg = <0x10 0x40000000 0x0 0x40000000>; - status = "okay"; - }; - - reserved-memory { - #address-cells = <2>; - #size-cells = <2>; - ranges; - - hss_payload: region@BFC00000 { - reg = <0x0 0xBFC00000 0x0 0x400000>; - no-map; - }; - }; - - imx219_vana: fixedregulator@0 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vana"; - regulator-min-microvolt = <2800000>; - regulator-max-microvolt = <2800000>; - }; - imx219_vdig: fixedregulator@1 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vdig"; - regulator-min-microvolt = <1800000>; - regulator-max-microvolt = <1800000>; - }; - imx219_vddl: fixedregulator@2 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vddl"; - regulator-min-microvolt = <1200000>; - regulator-max-microvolt = <1200000>; - }; - - imx219_clk: camera-clk { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <24000000>; - }; -}; - -&gpio0 { - ngpios=<14>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", "", "", "SD_CARD_CS", "USER_BUTTON"; - status = "okay"; - - sd_card_cs { - gpio-hog; - gpios = <12 12>; - output_high; - line-name = "SD_CARD_CS"; - }; - - user_button { - gpio-hog; - gpios = <13 13>; - input; - line-name = "USER_BUTTON"; - }; -}; - -&gpio1 { - ngpios=<24>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", - "", "", "", "", "", "", "", "", "", "", - "ADC_IRQn", "", "", "USB_OCn"; - status = "okay"; - - adc_irqn { - gpio-hog; - gpios = <20 20>; - input; - line-name = "ADC_IRQn"; - }; - - user_button { - gpio-hog; - gpios = <23 23>; - input; - line-name = "USB_OCn"; - }; - -}; - -&gpio2 { - interrupts = <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>; - gpio-line-names = "P8_PIN3_USER_LED_0", "P8_PIN4_USER_LED_1", "P8_PIN5_USER_LED_2", - "P8_PIN6_USER_LED_3", "P8_PIN7_USER_LED_4", "P8_PIN8_USER_LED_5", - "P8_PIN9_USER_LED_6", "P8_PIN10_USER_LED_7", "P8_PIN11_USER_LED_8", - "P8_PIN12_USER_LED_9", "P8_PIN13_USER_LED_10", "P8_PIN14_USER_LED_11", - "P8_PIN15", "P8_PIN16", "P8_PIN17", "P8_PIN18", "P8_PIN19", - "P8_PIN20", "P8_PIN21", "P8_PIN22", "P8_PIN23", "P8_PIN24", - "P8_PIN25", "P8_PIN26", "P8_PIN27", "P8_PIN28", "P8_PIN29", - "P8_PIN30", - "M2_W_DISABLE1", "M2_W_DISABLE2", - "VIO_ENABLE", "SD_DET"; - status = "okay"; - - vio_enable { - gpio-hog; - gpios = <30 30>; - output_high; - line-name = "VIO_ENABLE"; - }; - - sd_det { - gpio-hog; - gpios = <31 31>; - input; - line-name = "SD_DET"; - }; -}; - -&i2c0 { - status = "okay"; -}; - -&i2c1 { - status = "okay"; - eeprom: eeprom@50 { - compatible = "at,24c32"; - reg = <0x50>; - }; - - imx219: sensor@10 { - compatible = "sony,imx219"; - reg = <0x10>; - clocks = <&imx219_clk>; - VANA-supply = <&imx219_vana>; /* 2.8v */ - VDIG-supply = <&imx219_vdig>; /* 1.8v */ - VDDL-supply = <&imx219_vddl>; /* 1.2v */ - - port { - imx219_0: endpoint { -// remote-endpoint = <&csi1_ep>; - data-lanes = <1 2>; - clock-noncontinuous; - link-frequencies = /bits/ 64 <456000000>; - }; - }; - }; -}; - -&mac0 { - phy-mode = "sgmii"; - phy-handle = <&phy0>; - status = "okay"; - - phy0: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mac1 { - phy-mode = "sgmii"; - phy-handle = <&phy1>; - status = "okay"; - - phy1: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mbox { - status = "okay"; -}; - -//&mmc { -// status = "okay"; -// bus-width = <8>; -// disable-wp; -// cap-mmc-highspeed; -// mmc-ddr-1_8v; -// mmc-hs200-1_8v; -//}; - -&mmc { - //dma-noncoherent; - bus-width = <4>; - disable-wp; - cap-sd-highspeed; - cap-mmc-highspeed; - mmc-ddr-1_8v; - mmc-hs200-1_8v; - sd-uhs-sdr12; - sd-uhs-sdr25; - sd-uhs-sdr50; - sd-uhs-sdr104; - status = "okay"; -}; - - -&mmuart0 { - status = "okay"; -}; - -&mmuart1 { - status = "okay"; -}; - -//&mmuart2 { -// status = "okay"; -//}; - -//&mmuart3 //{ -// statu//s = "okay"; -//};// -// -//&mmuart4 { -// status = "okay"; -//}; - -//&pcie { -// status = "okay"; -//}; - -&qspi { - status = "okay"; - cs-gpios = <&gpio1 17 GPIO_ACTIVE_LOW>, <&gpio0 12 GPIO_ACTIVE_LOW>; - num-cs = <2>; - - - mcp3464: mcp3464@0 { - compatible = "microchip,mcp3464r"; - reg = <0>; /* CE0 */ - spi-cpol; - spi-cpha; - spi-max-frequency = <15000000>; - status = "okay"; - microchip,hw-device-address = <1>; - }; - - mmc-slot@1 { - compatible = "mmc-spi-slot"; - reg = <1>; - gpios = <&gpio2 31 1>; - voltage-ranges = <3300 3300>; - spi-max-frequency = <15000000>; - disable-wp; - }; -}; - -&refclk { - clock-frequency = <125000000>; -}; - -&refclk_ccc { - clock-frequency = <50000000>; -}; - -&rtc { - status = "okay"; -}; - -&spi0 { - status = "okay"; -}; - -&spi1 { - status = "okay"; -}; - -&syscontroller { - status = "okay"; -}; - -&usb { - //dma-noncoherent; - status = "okay"; - dr_mode = "otg"; -}; diff --git a/patches/linux/linux-6.4.y/Makefile b/patches/linux/linux-6.4.y/Makefile deleted file mode 100644 index 65af281..0000000 --- a/patches/linux/linux-6.4.y/Makefile +++ /dev/null @@ -1,8 +0,0 @@ -# SPDX-License-Identifier: GPL-2.0 -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-icicle-kit.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-m100pfsevp.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-polarberry.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-sev-kit.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-tysom-m.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-beaglev-fire.dtb -obj-$(CONFIG_BUILTIN_DTB) += $(addsuffix .o, $(dtb-y)) diff --git a/patches/linux/linux-6.4.y/defconfig b/patches/linux/linux-6.4.y/defconfig deleted file mode 100644 index 7c7c4df..0000000 --- a/patches/linux/linux-6.4.y/defconfig +++ /dev/null @@ -1,5537 +0,0 @@ -# -# Automatically generated file; DO NOT EDIT. -# Linux/riscv 6.4.10 Kernel Configuration -# -CONFIG_CC_VERSION_TEXT="riscv64-linux-gcc (GCC) 11.4.0" -CONFIG_CC_IS_GCC=y -CONFIG_GCC_VERSION=110400 -CONFIG_CLANG_VERSION=0 -CONFIG_AS_IS_GNU=y -CONFIG_AS_VERSION=24000 -CONFIG_LD_IS_BFD=y -CONFIG_LD_VERSION=24000 -CONFIG_LLD_VERSION=0 -CONFIG_CC_HAS_ASM_GOTO_OUTPUT=y -CONFIG_CC_HAS_ASM_GOTO_TIED_OUTPUT=y -CONFIG_CC_HAS_ASM_INLINE=y -CONFIG_CC_HAS_NO_PROFILE_FN_ATTR=y -CONFIG_PAHOLE_VERSION=0 -CONFIG_IRQ_WORK=y -CONFIG_BUILDTIME_TABLE_SORT=y -CONFIG_THREAD_INFO_IN_TASK=y - -# -# General setup -# -CONFIG_INIT_ENV_ARG_LIMIT=32 -# CONFIG_COMPILE_TEST is not set -# CONFIG_WERROR is not set -CONFIG_LOCALVERSION="" -CONFIG_LOCALVERSION_AUTO=y -CONFIG_BUILD_SALT="" -CONFIG_DEFAULT_INIT="" -CONFIG_DEFAULT_HOSTNAME="(none)" -CONFIG_SYSVIPC=y -CONFIG_SYSVIPC_SYSCTL=y -CONFIG_SYSVIPC_COMPAT=y -CONFIG_POSIX_MQUEUE=y -CONFIG_POSIX_MQUEUE_SYSCTL=y -# CONFIG_WATCH_QUEUE is not set -CONFIG_CROSS_MEMORY_ATTACH=y -# CONFIG_USELIB is not set -CONFIG_AUDIT=y -CONFIG_HAVE_ARCH_AUDITSYSCALL=y -CONFIG_AUDITSYSCALL=y - -# -# IRQ subsystem -# -CONFIG_GENERIC_IRQ_SHOW=y -CONFIG_GENERIC_IRQ_SHOW_LEVEL=y -CONFIG_GENERIC_IRQ_EFFECTIVE_AFF_MASK=y -CONFIG_GENERIC_IRQ_MIGRATION=y -CONFIG_HARDIRQS_SW_RESEND=y -CONFIG_GENERIC_IRQ_CHIP=y -CONFIG_IRQ_DOMAIN=y -CONFIG_IRQ_DOMAIN_HIERARCHY=y -CONFIG_GENERIC_IRQ_IPI=y -CONFIG_GENERIC_IRQ_IPI_MUX=y -CONFIG_GENERIC_MSI_IRQ=y -CONFIG_IRQ_FORCED_THREADING=y -CONFIG_SPARSE_IRQ=y -# CONFIG_GENERIC_IRQ_DEBUGFS is not set -# end of IRQ subsystem - -CONFIG_GENERIC_IRQ_MULTI_HANDLER=y -CONFIG_GENERIC_TIME_VSYSCALL=y -CONFIG_GENERIC_CLOCKEVENTS=y -CONFIG_ARCH_HAS_TICK_BROADCAST=y -CONFIG_GENERIC_CLOCKEVENTS_BROADCAST=y -CONFIG_HAVE_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_CONTEXT_TRACKING=y -CONFIG_CONTEXT_TRACKING_IDLE=y - -# -# Timers subsystem -# -CONFIG_TICK_ONESHOT=y -CONFIG_NO_HZ_COMMON=y -# CONFIG_HZ_PERIODIC is not set -CONFIG_NO_HZ_IDLE=y -# CONFIG_NO_HZ_FULL is not set -# CONFIG_NO_HZ is not set -CONFIG_HIGH_RES_TIMERS=y -# end of Timers subsystem - -CONFIG_BPF=y -CONFIG_HAVE_EBPF_JIT=y - -# -# BPF subsystem -# -CONFIG_BPF_SYSCALL=y -# CONFIG_BPF_JIT is not set -CONFIG_BPF_UNPRIV_DEFAULT_OFF=y -# CONFIG_BPF_PRELOAD is not set -# end of BPF subsystem - -CONFIG_PREEMPT_NONE_BUILD=y -CONFIG_PREEMPT_NONE=y -# CONFIG_PREEMPT_VOLUNTARY is not set -# CONFIG_PREEMPT is not set -CONFIG_PREEMPT_COUNT=y - -# -# CPU/Task time and stats accounting -# -CONFIG_TICK_CPU_ACCOUNTING=y -# CONFIG_VIRT_CPU_ACCOUNTING_GEN is not set -# CONFIG_IRQ_TIME_ACCOUNTING is not set -# CONFIG_BSD_PROCESS_ACCT is not set -# CONFIG_TASKSTATS is not set -# CONFIG_PSI is not set -# end of CPU/Task time and stats accounting - -CONFIG_CPU_ISOLATION=y - -# -# RCU Subsystem -# -CONFIG_TREE_RCU=y -# CONFIG_RCU_EXPERT is not set -CONFIG_TREE_SRCU=y -CONFIG_TASKS_RCU_GENERIC=y -CONFIG_TASKS_TRACE_RCU=y -CONFIG_RCU_STALL_COMMON=y -CONFIG_RCU_NEED_SEGCBLIST=y -# end of RCU Subsystem - -CONFIG_IKCONFIG=y -CONFIG_IKCONFIG_PROC=y -# CONFIG_IKHEADERS is not set -CONFIG_LOG_BUF_SHIFT=17 -CONFIG_LOG_CPU_MAX_BUF_SHIFT=12 -# CONFIG_PRINTK_INDEX is not set -CONFIG_GENERIC_SCHED_CLOCK=y - -# -# Scheduler features -# -# end of Scheduler features - -CONFIG_CC_HAS_INT128=y -CONFIG_CC_IMPLICIT_FALLTHROUGH="-Wimplicit-fallthrough=5" -CONFIG_GCC11_NO_ARRAY_BOUNDS=y -CONFIG_CC_NO_ARRAY_BOUNDS=y -CONFIG_ARCH_SUPPORTS_INT128=y -CONFIG_CGROUPS=y -CONFIG_PAGE_COUNTER=y -# CONFIG_CGROUP_FAVOR_DYNMODS is not set -CONFIG_MEMCG=y -CONFIG_MEMCG_KMEM=y -# CONFIG_BLK_CGROUP is not set -CONFIG_CGROUP_SCHED=y -CONFIG_FAIR_GROUP_SCHED=y -CONFIG_CFS_BANDWIDTH=y -CONFIG_RT_GROUP_SCHED=y -CONFIG_SCHED_MM_CID=y -CONFIG_CGROUP_PIDS=y -# CONFIG_CGROUP_RDMA is not set -CONFIG_CGROUP_FREEZER=y -CONFIG_CGROUP_HUGETLB=y -CONFIG_CPUSETS=y -CONFIG_PROC_PID_CPUSET=y -CONFIG_CGROUP_DEVICE=y -CONFIG_CGROUP_CPUACCT=y -CONFIG_CGROUP_PERF=y -CONFIG_CGROUP_BPF=y -# CONFIG_CGROUP_MISC is not set -# CONFIG_CGROUP_DEBUG is not set -CONFIG_SOCK_CGROUP_DATA=y -CONFIG_NAMESPACES=y -CONFIG_UTS_NS=y -CONFIG_TIME_NS=y -CONFIG_IPC_NS=y -CONFIG_USER_NS=y -CONFIG_PID_NS=y -CONFIG_NET_NS=y -CONFIG_CHECKPOINT_RESTORE=y -# CONFIG_SCHED_AUTOGROUP is not set -# CONFIG_RELAY is not set -CONFIG_BLK_DEV_INITRD=y -CONFIG_INITRAMFS_SOURCE="" -CONFIG_RD_GZIP=y -CONFIG_RD_BZIP2=y -CONFIG_RD_LZMA=y -CONFIG_RD_XZ=y -CONFIG_RD_LZO=y -CONFIG_RD_LZ4=y -CONFIG_RD_ZSTD=y -# CONFIG_BOOT_CONFIG is not set -CONFIG_INITRAMFS_PRESERVE_MTIME=y -CONFIG_CC_OPTIMIZE_FOR_PERFORMANCE=y -# CONFIG_CC_OPTIMIZE_FOR_SIZE is not set -CONFIG_LD_ORPHAN_WARN=y -CONFIG_LD_ORPHAN_WARN_LEVEL="warn" -CONFIG_SYSCTL=y -CONFIG_SYSCTL_EXCEPTION_TRACE=y -CONFIG_EXPERT=y -CONFIG_MULTIUSER=y -# CONFIG_SGETMASK_SYSCALL is not set -# CONFIG_SYSFS_SYSCALL is not set -CONFIG_FHANDLE=y -CONFIG_POSIX_TIMERS=y -CONFIG_PRINTK=y -CONFIG_BUG=y -CONFIG_ELF_CORE=y -CONFIG_BASE_FULL=y -CONFIG_FUTEX=y -CONFIG_FUTEX_PI=y -CONFIG_EPOLL=y -CONFIG_SIGNALFD=y -CONFIG_TIMERFD=y -CONFIG_EVENTFD=y -CONFIG_SHMEM=y -CONFIG_AIO=y -CONFIG_IO_URING=y -CONFIG_ADVISE_SYSCALLS=y -CONFIG_MEMBARRIER=y -CONFIG_KALLSYMS=y -# CONFIG_KALLSYMS_SELFTEST is not set -# CONFIG_KALLSYMS_ALL is not set -CONFIG_KALLSYMS_BASE_RELATIVE=y -CONFIG_KCMP=y -CONFIG_RSEQ=y -# CONFIG_DEBUG_RSEQ is not set -# CONFIG_EMBEDDED is not set -CONFIG_HAVE_PERF_EVENTS=y -# CONFIG_PC104 is not set - -# -# Kernel Performance Events And Counters -# -CONFIG_PERF_EVENTS=y -# CONFIG_DEBUG_PERF_USE_VMALLOC is not set -# end of Kernel Performance Events And Counters - -CONFIG_PROFILING=y -# end of General setup - -CONFIG_64BIT=y -CONFIG_RISCV=y -CONFIG_GCC_SUPPORTS_DYNAMIC_FTRACE=y -CONFIG_ARCH_MMAP_RND_BITS_MIN=18 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MIN=8 -CONFIG_ARCH_MMAP_RND_BITS_MAX=24 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MAX=17 -CONFIG_RISCV_SBI=y -CONFIG_MMU=y -CONFIG_PAGE_OFFSET=0xff60000000000000 -CONFIG_ARCH_FLATMEM_ENABLE=y -CONFIG_ARCH_SPARSEMEM_ENABLE=y -CONFIG_ARCH_SELECT_MEMORY_MODEL=y -CONFIG_ARCH_SUPPORTS_UPROBES=y -CONFIG_STACKTRACE_SUPPORT=y -CONFIG_GENERIC_BUG=y -CONFIG_GENERIC_BUG_RELATIVE_POINTERS=y -CONFIG_GENERIC_CALIBRATE_DELAY=y -CONFIG_GENERIC_CSUM=y -CONFIG_GENERIC_HWEIGHT=y -CONFIG_FIX_EARLYCON_MEM=y -CONFIG_PGTABLE_LEVELS=5 -CONFIG_LOCKDEP_SUPPORT=y -CONFIG_RISCV_DMA_NONCOHERENT=y -CONFIG_AS_HAS_INSN=y - -# -# SoC selection -# -CONFIG_ARCH_MICROCHIP_POLARFIRE=y -CONFIG_SOC_MICROCHIP_POLARFIRE=y -CONFIG_ARCH_RENESAS=y -CONFIG_ARCH_SIFIVE=y -CONFIG_SOC_SIFIVE=y -CONFIG_ARCH_STARFIVE=y -CONFIG_SOC_STARFIVE=y -CONFIG_ARCH_SUNXI=y -CONFIG_ARCH_VIRT=y -CONFIG_SOC_VIRT=y -# end of SoC selection - -# -# CPU errata selection -# -CONFIG_ERRATA_SIFIVE=y -CONFIG_ERRATA_SIFIVE_CIP_453=y -CONFIG_ERRATA_SIFIVE_CIP_1200=y -CONFIG_ERRATA_THEAD=y -CONFIG_ERRATA_THEAD_PBMT=y -CONFIG_ERRATA_THEAD_CMO=y -CONFIG_ERRATA_THEAD_PMU=y -# end of CPU errata selection - -# -# Platform type -# -# CONFIG_NONPORTABLE is not set -CONFIG_ARCH_RV64I=y -# CONFIG_CMODEL_MEDLOW is not set -CONFIG_CMODEL_MEDANY=y -CONFIG_MODULE_SECTIONS=y -CONFIG_SMP=y -# CONFIG_SCHED_MC is not set -CONFIG_NR_CPUS=64 -CONFIG_HOTPLUG_CPU=y -CONFIG_TUNE_GENERIC=y -# CONFIG_NUMA is not set -CONFIG_RISCV_ALTERNATIVE=y -CONFIG_RISCV_ALTERNATIVE_EARLY=y -CONFIG_RISCV_ISA_C=y -CONFIG_RISCV_ISA_SVNAPOT=y -CONFIG_RISCV_ISA_SVPBMT=y -CONFIG_TOOLCHAIN_HAS_ZBB=y -CONFIG_RISCV_ISA_ZBB=y -CONFIG_RISCV_ISA_ZICBOM=y -CONFIG_RISCV_ISA_ZICBOZ=y -CONFIG_TOOLCHAIN_HAS_ZIHINTPAUSE=y -CONFIG_TOOLCHAIN_NEEDS_EXPLICIT_ZICSR_ZIFENCEI=y -CONFIG_FPU=y -# end of Platform type - -# -# Kernel features -# -# CONFIG_HZ_100 is not set -CONFIG_HZ_250=y -# CONFIG_HZ_300 is not set -# CONFIG_HZ_1000 is not set -CONFIG_HZ=250 -CONFIG_SCHED_HRTICK=y -# CONFIG_RISCV_SBI_V01 is not set -# CONFIG_RISCV_BOOT_SPINWAIT is not set -# CONFIG_KEXEC is not set -# CONFIG_KEXEC_FILE is not set -# CONFIG_CRASH_DUMP is not set -CONFIG_COMPAT=y -# CONFIG_RELOCATABLE is not set -# end of Kernel features - -# -# Boot options -# -CONFIG_CMDLINE="" -CONFIG_EFI_STUB=y -CONFIG_EFI=y -CONFIG_CC_HAVE_STACKPROTECTOR_TLS=y -CONFIG_STACKPROTECTOR_PER_TASK=y -# end of Boot options - -CONFIG_PORTABLE=y - -# -# Power management options -# -CONFIG_PM=y -# CONFIG_PM_DEBUG is not set -CONFIG_PM_CLK=y -CONFIG_PM_GENERIC_DOMAINS=y -# CONFIG_WQ_POWER_EFFICIENT_DEFAULT is not set -CONFIG_PM_GENERIC_DOMAINS_OF=y -CONFIG_CPU_PM=y -# end of Power management options - -# -# CPU Power Management -# - -# -# CPU Idle -# -CONFIG_CPU_IDLE=y -CONFIG_CPU_IDLE_MULTIPLE_DRIVERS=y -# CONFIG_CPU_IDLE_GOV_LADDER is not set -CONFIG_CPU_IDLE_GOV_MENU=y -# CONFIG_CPU_IDLE_GOV_TEO is not set -CONFIG_DT_IDLE_STATES=y -CONFIG_DT_IDLE_GENPD=y - -# -# RISC-V CPU Idle Drivers -# -CONFIG_RISCV_SBI_CPUIDLE=y -# end of RISC-V CPU Idle Drivers -# end of CPU Idle - -# -# CPU Frequency scaling -# -# CONFIG_CPU_FREQ is not set -# end of CPU Frequency scaling -# end of CPU Power Management - -CONFIG_HAVE_KVM_EVENTFD=y -CONFIG_KVM_MMIO=y -CONFIG_KVM_GENERIC_DIRTYLOG_READ_PROTECT=y -CONFIG_HAVE_KVM_VCPU_ASYNC_IOCTL=y -CONFIG_KVM_XFER_TO_GUEST_WORK=y -CONFIG_KVM_GENERIC_HARDWARE_ENABLING=y -CONFIG_VIRTUALIZATION=y -CONFIG_KVM=m - -# -# General architecture-dependent options -# -CONFIG_GENERIC_ENTRY=y -# CONFIG_KPROBES is not set -CONFIG_JUMP_LABEL=y -# CONFIG_STATIC_KEYS_SELFTEST is not set -CONFIG_HAVE_64BIT_ALIGNED_ACCESS=y -CONFIG_HAVE_KPROBES=y -CONFIG_HAVE_KRETPROBES=y -CONFIG_HAVE_KPROBES_ON_FTRACE=y -CONFIG_HAVE_FUNCTION_ERROR_INJECTION=y -CONFIG_TRACE_IRQFLAGS_SUPPORT=y -CONFIG_HAVE_ARCH_TRACEHOOK=y -CONFIG_HAVE_DMA_CONTIGUOUS=y -CONFIG_GENERIC_SMP_IDLE_THREAD=y -CONFIG_GENERIC_IDLE_POLL_SETUP=y -CONFIG_ARCH_HAS_FORTIFY_SOURCE=y -CONFIG_ARCH_HAS_SET_MEMORY=y -CONFIG_ARCH_HAS_SET_DIRECT_MAP=y -CONFIG_HAVE_ARCH_THREAD_STRUCT_WHITELIST=y -CONFIG_HAVE_ASM_MODVERSIONS=y -CONFIG_HAVE_REGS_AND_STACK_ACCESS_API=y -CONFIG_HAVE_RSEQ=y -CONFIG_HAVE_FUNCTION_ARG_ACCESS_API=y -CONFIG_HAVE_PERF_REGS=y -CONFIG_HAVE_PERF_USER_STACK_DUMP=y -CONFIG_HAVE_ARCH_JUMP_LABEL=y -CONFIG_HAVE_ARCH_JUMP_LABEL_RELATIVE=y -CONFIG_MMU_LAZY_TLB_REFCOUNT=y -CONFIG_HAVE_ARCH_SECCOMP=y -CONFIG_HAVE_ARCH_SECCOMP_FILTER=y -CONFIG_SECCOMP=y -CONFIG_SECCOMP_FILTER=y -# CONFIG_SECCOMP_CACHE_DEBUG is not set -CONFIG_HAVE_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR_STRONG=y -CONFIG_LTO_NONE=y -CONFIG_HAVE_CONTEXT_TRACKING_USER=y -CONFIG_HAVE_VIRT_CPU_ACCOUNTING_GEN=y -CONFIG_HAVE_IRQ_TIME_ACCOUNTING=y -CONFIG_HAVE_MOVE_PUD=y -CONFIG_HAVE_MOVE_PMD=y -CONFIG_HAVE_ARCH_TRANSPARENT_HUGEPAGE=y -CONFIG_HAVE_ARCH_HUGE_VMAP=y -CONFIG_HAVE_ARCH_HUGE_VMALLOC=y -CONFIG_ARCH_WANT_HUGE_PMD_SHARE=y -CONFIG_HAVE_MOD_ARCH_SPECIFIC=y -CONFIG_MODULES_USE_ELF_RELA=y -CONFIG_ARCH_HAS_ELF_RANDOMIZE=y -CONFIG_HAVE_ARCH_MMAP_RND_BITS=y -CONFIG_ARCH_MMAP_RND_BITS=18 -CONFIG_HAVE_ARCH_MMAP_RND_COMPAT_BITS=y -CONFIG_ARCH_MMAP_RND_COMPAT_BITS=8 -CONFIG_PAGE_SIZE_LESS_THAN_64KB=y -CONFIG_PAGE_SIZE_LESS_THAN_256KB=y -CONFIG_ARCH_WANT_DEFAULT_TOPDOWN_MMAP_LAYOUT=y -CONFIG_CLONE_BACKWARDS=y -CONFIG_COMPAT_32BIT_TIME=y -CONFIG_HAVE_ARCH_VMAP_STACK=y -CONFIG_VMAP_STACK=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX_DEFAULT=y -CONFIG_ARCH_HAS_STRICT_KERNEL_RWX=y -CONFIG_STRICT_KERNEL_RWX=y -CONFIG_ARCH_HAS_STRICT_MODULE_RWX=y -CONFIG_STRICT_MODULE_RWX=y -CONFIG_ARCH_USE_MEMREMAP_PROT=y -# CONFIG_LOCK_EVENT_COUNTS is not set -CONFIG_ARCH_HAS_VDSO_DATA=y -CONFIG_ARCH_WANT_LD_ORPHAN_WARN=y -CONFIG_ARCH_SUPPORTS_DEBUG_PAGEALLOC=y -CONFIG_ARCH_SUPPORTS_PAGE_TABLE_CHECK=y - -# -# GCOV-based kernel profiling -# -# CONFIG_GCOV_KERNEL is not set -CONFIG_ARCH_HAS_GCOV_PROFILE_ALL=y -# end of GCOV-based kernel profiling - -CONFIG_HAVE_GCC_PLUGINS=y -CONFIG_GCC_PLUGINS=y -# CONFIG_GCC_PLUGIN_LATENT_ENTROPY is not set -CONFIG_FUNCTION_ALIGNMENT=0 -# end of General architecture-dependent options - -CONFIG_RT_MUTEXES=y -CONFIG_BASE_SMALL=0 -CONFIG_MODULES=y -# CONFIG_MODULE_DEBUG is not set -# CONFIG_MODULE_FORCE_LOAD is not set -CONFIG_MODULE_UNLOAD=y -# CONFIG_MODULE_FORCE_UNLOAD is not set -# CONFIG_MODULE_UNLOAD_TAINT_TRACKING is not set -# CONFIG_MODVERSIONS is not set -# CONFIG_MODULE_SRCVERSION_ALL is not set -# CONFIG_MODULE_SIG is not set -CONFIG_MODULE_COMPRESS_NONE=y -# CONFIG_MODULE_COMPRESS_GZIP is not set -# CONFIG_MODULE_COMPRESS_XZ is not set -# CONFIG_MODULE_COMPRESS_ZSTD is not set -# CONFIG_MODULE_ALLOW_MISSING_NAMESPACE_IMPORTS is not set -CONFIG_MODPROBE_PATH="/sbin/modprobe" -# CONFIG_TRIM_UNUSED_KSYMS is not set -CONFIG_MODULES_TREE_LOOKUP=y -CONFIG_BLOCK=y -CONFIG_BLOCK_LEGACY_AUTOLOAD=y -CONFIG_BLK_CGROUP_PUNT_BIO=y -CONFIG_BLK_DEV_BSG_COMMON=y -CONFIG_BLK_ICQ=y -# CONFIG_BLK_DEV_BSGLIB is not set -# CONFIG_BLK_DEV_INTEGRITY is not set -# CONFIG_BLK_DEV_ZONED is not set -# CONFIG_BLK_WBT is not set -CONFIG_BLK_DEBUG_FS=y -# CONFIG_BLK_SED_OPAL is not set -# CONFIG_BLK_INLINE_ENCRYPTION is not set - -# -# Partition Types -# -# CONFIG_PARTITION_ADVANCED is not set -CONFIG_MSDOS_PARTITION=y -CONFIG_EFI_PARTITION=y -# end of Partition Types - -CONFIG_BLK_MQ_PCI=y -CONFIG_BLK_MQ_VIRTIO=y -CONFIG_BLK_PM=y -CONFIG_BLOCK_HOLDER_DEPRECATED=y -CONFIG_BLK_MQ_STACKING=y - -# -# IO Schedulers -# -CONFIG_MQ_IOSCHED_DEADLINE=y -CONFIG_MQ_IOSCHED_KYBER=y -CONFIG_IOSCHED_BFQ=y -# end of IO Schedulers - -CONFIG_PREEMPT_NOTIFIERS=y -CONFIG_ASN1=y -CONFIG_UNINLINE_SPIN_UNLOCK=y -CONFIG_ARCH_SUPPORTS_ATOMIC_RMW=y -CONFIG_MUTEX_SPIN_ON_OWNER=y -CONFIG_RWSEM_SPIN_ON_OWNER=y -CONFIG_LOCK_SPIN_ON_OWNER=y -CONFIG_ARCH_USE_QUEUED_RWLOCKS=y -CONFIG_QUEUED_RWLOCKS=y -CONFIG_ARCH_HAS_MMIOWB=y -CONFIG_MMIOWB=y -CONFIG_ARCH_HAS_NON_OVERLAPPING_ADDRESS_SPACE=y -CONFIG_FREEZER=y - -# -# Executable file formats -# -CONFIG_BINFMT_ELF=y -CONFIG_COMPAT_BINFMT_ELF=y -CONFIG_ELFCORE=y -CONFIG_CORE_DUMP_DEFAULT_ELF_HEADERS=y -CONFIG_BINFMT_SCRIPT=y -CONFIG_ARCH_HAS_BINFMT_FLAT=y -# CONFIG_BINFMT_FLAT is not set -# CONFIG_BINFMT_MISC is not set -CONFIG_COREDUMP=y -# end of Executable file formats - -# -# Memory Management options -# -CONFIG_SWAP=y -# CONFIG_ZSWAP is not set - -# -# SLAB allocator options -# -# CONFIG_SLAB is not set -CONFIG_SLUB=y -# CONFIG_SLUB_TINY is not set -CONFIG_SLAB_MERGE_DEFAULT=y -# CONFIG_SLAB_FREELIST_RANDOM is not set -# CONFIG_SLAB_FREELIST_HARDENED is not set -# CONFIG_SLUB_STATS is not set -CONFIG_SLUB_CPU_PARTIAL=y -# end of SLAB allocator options - -# CONFIG_SHUFFLE_PAGE_ALLOCATOR is not set -CONFIG_COMPAT_BRK=y -CONFIG_SELECT_MEMORY_MODEL=y -# CONFIG_FLATMEM_MANUAL is not set -CONFIG_SPARSEMEM_MANUAL=y -CONFIG_SPARSEMEM=y -CONFIG_SPARSEMEM_EXTREME=y -CONFIG_SPARSEMEM_VMEMMAP_ENABLE=y -CONFIG_SPARSEMEM_VMEMMAP=y -CONFIG_ARCH_WANT_OPTIMIZE_VMEMMAP=y -CONFIG_SPLIT_PTLOCK_CPUS=4 -CONFIG_ARCH_ENABLE_SPLIT_PMD_PTLOCK=y -CONFIG_MEMORY_BALLOON=y -CONFIG_BALLOON_COMPACTION=y -CONFIG_COMPACTION=y -CONFIG_COMPACT_UNEVICTABLE_DEFAULT=1 -CONFIG_PAGE_REPORTING=y -CONFIG_MIGRATION=y -CONFIG_ARCH_ENABLE_HUGEPAGE_MIGRATION=y -CONFIG_PHYS_ADDR_T_64BIT=y -CONFIG_MMU_NOTIFIER=y -# CONFIG_KSM is not set -CONFIG_DEFAULT_MMAP_MIN_ADDR=4096 -CONFIG_ARCH_WANTS_THP_SWAP=y -# CONFIG_TRANSPARENT_HUGEPAGE is not set -# CONFIG_CMA is not set -CONFIG_GENERIC_EARLY_IOREMAP=y -# CONFIG_DEFERRED_STRUCT_PAGE_INIT is not set -# CONFIG_IDLE_PAGE_TRACKING is not set -CONFIG_ARCH_HAS_CURRENT_STACK_POINTER=y -CONFIG_ZONE_DMA32=y -CONFIG_VM_EVENT_COUNTERS=y -# CONFIG_PERCPU_STATS is not set -# CONFIG_GUP_TEST is not set -# CONFIG_DMAPOOL_TEST is not set -CONFIG_ARCH_HAS_PTE_SPECIAL=y -CONFIG_SECRETMEM=y -# CONFIG_ANON_VMA_NAME is not set -# CONFIG_USERFAULTFD is not set -# CONFIG_LRU_GEN is not set -CONFIG_LOCK_MM_AND_FIND_VMA=y - -# -# Data Access Monitoring -# -# CONFIG_DAMON is not set -# end of Data Access Monitoring -# end of Memory Management options - -CONFIG_NET=y -CONFIG_NET_INGRESS=y -CONFIG_NET_EGRESS=y -CONFIG_SKB_EXTENSIONS=y - -# -# Networking options -# -CONFIG_PACKET=y -# CONFIG_PACKET_DIAG is not set -CONFIG_UNIX=y -CONFIG_UNIX_SCM=y -CONFIG_AF_UNIX_OOB=y -# CONFIG_UNIX_DIAG is not set -# CONFIG_TLS is not set -CONFIG_XFRM=y -CONFIG_XFRM_ALGO=m -CONFIG_XFRM_USER=m -# CONFIG_XFRM_INTERFACE is not set -# CONFIG_XFRM_SUB_POLICY is not set -# CONFIG_XFRM_MIGRATE is not set -# CONFIG_XFRM_STATISTICS is not set -CONFIG_XFRM_ESP=m -# CONFIG_NET_KEY is not set -# CONFIG_XDP_SOCKETS is not set -CONFIG_NET_HANDSHAKE=y -CONFIG_INET=y -CONFIG_IP_MULTICAST=y -CONFIG_IP_ADVANCED_ROUTER=y -# CONFIG_IP_FIB_TRIE_STATS is not set -# CONFIG_IP_MULTIPLE_TABLES is not set -# CONFIG_IP_ROUTE_MULTIPATH is not set -# CONFIG_IP_ROUTE_VERBOSE is not set -CONFIG_IP_PNP=y -CONFIG_IP_PNP_DHCP=y -CONFIG_IP_PNP_BOOTP=y -CONFIG_IP_PNP_RARP=y -# CONFIG_NET_IPIP is not set -# CONFIG_NET_IPGRE_DEMUX is not set -CONFIG_NET_IP_TUNNEL=y -# CONFIG_IP_MROUTE is not set -# CONFIG_SYN_COOKIES is not set -# CONFIG_NET_IPVTI is not set -CONFIG_NET_UDP_TUNNEL=m -# CONFIG_NET_FOU is not set -# CONFIG_NET_FOU_IP_TUNNELS is not set -# CONFIG_INET_AH is not set -CONFIG_INET_ESP=m -# CONFIG_INET_ESP_OFFLOAD is not set -# CONFIG_INET_ESPINTCP is not set -# CONFIG_INET_IPCOMP is not set -CONFIG_INET_TABLE_PERTURB_ORDER=16 -CONFIG_INET_TUNNEL=y -CONFIG_INET_DIAG=y -CONFIG_INET_TCP_DIAG=y -# CONFIG_INET_UDP_DIAG is not set -# CONFIG_INET_RAW_DIAG is not set -# CONFIG_INET_DIAG_DESTROY is not set -# CONFIG_TCP_CONG_ADVANCED is not set -CONFIG_TCP_CONG_CUBIC=y -CONFIG_DEFAULT_TCP_CONG="cubic" -# CONFIG_TCP_MD5SIG is not set -CONFIG_IPV6=y -# CONFIG_IPV6_ROUTER_PREF is not set -# CONFIG_IPV6_OPTIMISTIC_DAD is not set -# CONFIG_INET6_AH is not set -# CONFIG_INET6_ESP is not set -# CONFIG_INET6_IPCOMP is not set -# CONFIG_IPV6_MIP6 is not set -# CONFIG_IPV6_ILA is not set -# CONFIG_IPV6_VTI is not set -CONFIG_IPV6_SIT=y -# CONFIG_IPV6_SIT_6RD is not set -CONFIG_IPV6_NDISC_NODETYPE=y -# CONFIG_IPV6_TUNNEL is not set -# CONFIG_IPV6_MULTIPLE_TABLES is not set -# CONFIG_IPV6_MROUTE is not set -# CONFIG_IPV6_SEG6_LWTUNNEL is not set -# CONFIG_IPV6_SEG6_HMAC is not set -# CONFIG_IPV6_RPL_LWTUNNEL is not set -# CONFIG_IPV6_IOAM6_LWTUNNEL is not set -# CONFIG_NETLABEL is not set -# CONFIG_MPTCP is not set -CONFIG_NETWORK_SECMARK=y -# CONFIG_NETWORK_PHY_TIMESTAMPING is not set -CONFIG_NETFILTER=y -CONFIG_NETFILTER_ADVANCED=y -CONFIG_BRIDGE_NETFILTER=m - -# -# Core Netfilter Configuration -# -CONFIG_NETFILTER_INGRESS=y -CONFIG_NETFILTER_EGRESS=y -CONFIG_NETFILTER_FAMILY_BRIDGE=y -CONFIG_NETFILTER_BPF_LINK=y -# CONFIG_NETFILTER_NETLINK_ACCT is not set -# CONFIG_NETFILTER_NETLINK_QUEUE is not set -# CONFIG_NETFILTER_NETLINK_LOG is not set -# CONFIG_NETFILTER_NETLINK_OSF is not set -CONFIG_NF_CONNTRACK=m -CONFIG_NF_LOG_SYSLOG=m -# CONFIG_NF_CONNTRACK_MARK is not set -# CONFIG_NF_CONNTRACK_SECMARK is not set -# CONFIG_NF_CONNTRACK_ZONES is not set -# CONFIG_NF_CONNTRACK_PROCFS is not set -# CONFIG_NF_CONNTRACK_EVENTS is not set -# CONFIG_NF_CONNTRACK_TIMEOUT is not set -# CONFIG_NF_CONNTRACK_TIMESTAMP is not set -# CONFIG_NF_CONNTRACK_LABELS is not set -CONFIG_NF_CT_PROTO_DCCP=y -CONFIG_NF_CT_PROTO_SCTP=y -CONFIG_NF_CT_PROTO_UDPLITE=y -# CONFIG_NF_CONNTRACK_AMANDA is not set -CONFIG_NF_CONNTRACK_FTP=m -# CONFIG_NF_CONNTRACK_H323 is not set -# CONFIG_NF_CONNTRACK_IRC is not set -# CONFIG_NF_CONNTRACK_NETBIOS_NS is not set -# CONFIG_NF_CONNTRACK_SNMP is not set -# CONFIG_NF_CONNTRACK_PPTP is not set -# CONFIG_NF_CONNTRACK_SANE is not set -# CONFIG_NF_CONNTRACK_SIP is not set -CONFIG_NF_CONNTRACK_TFTP=m -# CONFIG_NF_CT_NETLINK is not set -CONFIG_NF_NAT=m -CONFIG_NF_NAT_FTP=m -CONFIG_NF_NAT_TFTP=m -CONFIG_NF_NAT_REDIRECT=y -CONFIG_NF_NAT_MASQUERADE=y -# CONFIG_NF_TABLES is not set -CONFIG_NETFILTER_XTABLES=y -# CONFIG_NETFILTER_XTABLES_COMPAT is not set - -# -# Xtables combined modules -# -CONFIG_NETFILTER_XT_MARK=m -# CONFIG_NETFILTER_XT_CONNMARK is not set - -# -# Xtables targets -# -# CONFIG_NETFILTER_XT_TARGET_AUDIT is not set -# CONFIG_NETFILTER_XT_TARGET_CHECKSUM is not set -# CONFIG_NETFILTER_XT_TARGET_CLASSIFY is not set -# CONFIG_NETFILTER_XT_TARGET_CONNMARK is not set -# CONFIG_NETFILTER_XT_TARGET_DSCP is not set -# CONFIG_NETFILTER_XT_TARGET_HL is not set -# CONFIG_NETFILTER_XT_TARGET_HMARK is not set -# CONFIG_NETFILTER_XT_TARGET_IDLETIMER is not set -# CONFIG_NETFILTER_XT_TARGET_LOG is not set -# CONFIG_NETFILTER_XT_TARGET_MARK is not set -CONFIG_NETFILTER_XT_NAT=m -# CONFIG_NETFILTER_XT_TARGET_NETMAP is not set -# CONFIG_NETFILTER_XT_TARGET_NFLOG is not set -# CONFIG_NETFILTER_XT_TARGET_NFQUEUE is not set -# CONFIG_NETFILTER_XT_TARGET_RATEEST is not set -CONFIG_NETFILTER_XT_TARGET_REDIRECT=m -CONFIG_NETFILTER_XT_TARGET_MASQUERADE=m -# CONFIG_NETFILTER_XT_TARGET_TEE is not set -# CONFIG_NETFILTER_XT_TARGET_TPROXY is not set -# CONFIG_NETFILTER_XT_TARGET_SECMARK is not set -# CONFIG_NETFILTER_XT_TARGET_TCPMSS is not set -# CONFIG_NETFILTER_XT_TARGET_TCPOPTSTRIP is not set - -# -# Xtables matches -# -CONFIG_NETFILTER_XT_MATCH_ADDRTYPE=m -# CONFIG_NETFILTER_XT_MATCH_BPF is not set -# CONFIG_NETFILTER_XT_MATCH_CGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_CLUSTER is not set -# CONFIG_NETFILTER_XT_MATCH_COMMENT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNBYTES is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLABEL is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNMARK is not set -CONFIG_NETFILTER_XT_MATCH_CONNTRACK=m -# CONFIG_NETFILTER_XT_MATCH_CPU is not set -# CONFIG_NETFILTER_XT_MATCH_DCCP is not set -# CONFIG_NETFILTER_XT_MATCH_DEVGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_DSCP is not set -# CONFIG_NETFILTER_XT_MATCH_ECN is not set -# CONFIG_NETFILTER_XT_MATCH_ESP is not set -# CONFIG_NETFILTER_XT_MATCH_HASHLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_HELPER is not set -# CONFIG_NETFILTER_XT_MATCH_HL is not set -# CONFIG_NETFILTER_XT_MATCH_IPCOMP is not set -# CONFIG_NETFILTER_XT_MATCH_IPRANGE is not set -CONFIG_NETFILTER_XT_MATCH_IPVS=m -# CONFIG_NETFILTER_XT_MATCH_L2TP is not set -# CONFIG_NETFILTER_XT_MATCH_LENGTH is not set -# CONFIG_NETFILTER_XT_MATCH_LIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_MAC is not set -# CONFIG_NETFILTER_XT_MATCH_MARK is not set -# CONFIG_NETFILTER_XT_MATCH_MULTIPORT is not set -# CONFIG_NETFILTER_XT_MATCH_NFACCT is not set -# CONFIG_NETFILTER_XT_MATCH_OSF is not set -# CONFIG_NETFILTER_XT_MATCH_OWNER is not set -# CONFIG_NETFILTER_XT_MATCH_POLICY is not set -# CONFIG_NETFILTER_XT_MATCH_PHYSDEV is not set -# CONFIG_NETFILTER_XT_MATCH_PKTTYPE is not set -# CONFIG_NETFILTER_XT_MATCH_QUOTA is not set -# CONFIG_NETFILTER_XT_MATCH_RATEEST is not set -# CONFIG_NETFILTER_XT_MATCH_REALM is not set -# CONFIG_NETFILTER_XT_MATCH_RECENT is not set -# CONFIG_NETFILTER_XT_MATCH_SCTP is not set -# CONFIG_NETFILTER_XT_MATCH_SOCKET is not set -# CONFIG_NETFILTER_XT_MATCH_STATE is not set -# CONFIG_NETFILTER_XT_MATCH_STATISTIC is not set -# CONFIG_NETFILTER_XT_MATCH_STRING is not set -# CONFIG_NETFILTER_XT_MATCH_TCPMSS is not set -# CONFIG_NETFILTER_XT_MATCH_TIME is not set -# CONFIG_NETFILTER_XT_MATCH_U32 is not set -# end of Core Netfilter Configuration - -# CONFIG_IP_SET is not set -CONFIG_IP_VS=m -# CONFIG_IP_VS_IPV6 is not set -# CONFIG_IP_VS_DEBUG is not set -CONFIG_IP_VS_TAB_BITS=12 - -# -# IPVS transport protocol load balancing support -# -CONFIG_IP_VS_PROTO_TCP=y -CONFIG_IP_VS_PROTO_UDP=y -# CONFIG_IP_VS_PROTO_ESP is not set -# CONFIG_IP_VS_PROTO_AH is not set -# CONFIG_IP_VS_PROTO_SCTP is not set - -# -# IPVS scheduler -# -CONFIG_IP_VS_RR=m -# CONFIG_IP_VS_WRR is not set -# CONFIG_IP_VS_LC is not set -# CONFIG_IP_VS_WLC is not set -# CONFIG_IP_VS_FO is not set -# CONFIG_IP_VS_OVF is not set -# CONFIG_IP_VS_LBLC is not set -# CONFIG_IP_VS_LBLCR is not set -# CONFIG_IP_VS_DH is not set -# CONFIG_IP_VS_SH is not set -# CONFIG_IP_VS_MH is not set -# CONFIG_IP_VS_SED is not set -# CONFIG_IP_VS_NQ is not set -# CONFIG_IP_VS_TWOS is not set - -# -# IPVS SH scheduler -# -CONFIG_IP_VS_SH_TAB_BITS=8 - -# -# IPVS MH scheduler -# -CONFIG_IP_VS_MH_TAB_INDEX=12 - -# -# IPVS application helper -# -# CONFIG_IP_VS_FTP is not set -CONFIG_IP_VS_NFCT=y - -# -# IP: Netfilter Configuration -# -CONFIG_NF_DEFRAG_IPV4=m -# CONFIG_NF_SOCKET_IPV4 is not set -# CONFIG_NF_TPROXY_IPV4 is not set -# CONFIG_NF_DUP_IPV4 is not set -CONFIG_NF_LOG_ARP=m -CONFIG_NF_LOG_IPV4=m -CONFIG_NF_REJECT_IPV4=m -CONFIG_IP_NF_IPTABLES=y -# CONFIG_IP_NF_MATCH_AH is not set -# CONFIG_IP_NF_MATCH_ECN is not set -# CONFIG_IP_NF_MATCH_RPFILTER is not set -# CONFIG_IP_NF_MATCH_TTL is not set -CONFIG_IP_NF_FILTER=m -CONFIG_IP_NF_TARGET_REJECT=m -# CONFIG_IP_NF_TARGET_SYNPROXY is not set -CONFIG_IP_NF_NAT=m -CONFIG_IP_NF_TARGET_MASQUERADE=m -# CONFIG_IP_NF_TARGET_NETMAP is not set -CONFIG_IP_NF_TARGET_REDIRECT=m -CONFIG_IP_NF_MANGLE=m -# CONFIG_IP_NF_TARGET_ECN is not set -# CONFIG_IP_NF_TARGET_TTL is not set -# CONFIG_IP_NF_RAW is not set -# CONFIG_IP_NF_SECURITY is not set -# CONFIG_IP_NF_ARPTABLES is not set -# end of IP: Netfilter Configuration - -# -# IPv6: Netfilter Configuration -# -# CONFIG_NF_SOCKET_IPV6 is not set -# CONFIG_NF_TPROXY_IPV6 is not set -# CONFIG_NF_DUP_IPV6 is not set -CONFIG_NF_REJECT_IPV6=m -CONFIG_NF_LOG_IPV6=m -CONFIG_IP6_NF_IPTABLES=m -# CONFIG_IP6_NF_MATCH_AH is not set -# CONFIG_IP6_NF_MATCH_EUI64 is not set -# CONFIG_IP6_NF_MATCH_FRAG is not set -# CONFIG_IP6_NF_MATCH_OPTS is not set -# CONFIG_IP6_NF_MATCH_HL is not set -CONFIG_IP6_NF_MATCH_IPV6HEADER=m -# CONFIG_IP6_NF_MATCH_MH is not set -# CONFIG_IP6_NF_MATCH_RPFILTER is not set -# CONFIG_IP6_NF_MATCH_RT is not set -# CONFIG_IP6_NF_MATCH_SRH is not set -# CONFIG_IP6_NF_TARGET_HL is not set -CONFIG_IP6_NF_FILTER=m -CONFIG_IP6_NF_TARGET_REJECT=m -# CONFIG_IP6_NF_TARGET_SYNPROXY is not set -CONFIG_IP6_NF_MANGLE=m -# CONFIG_IP6_NF_RAW is not set -# CONFIG_IP6_NF_SECURITY is not set -# CONFIG_IP6_NF_NAT is not set -# end of IPv6: Netfilter Configuration - -CONFIG_NF_DEFRAG_IPV6=m -# CONFIG_NF_CONNTRACK_BRIDGE is not set -# CONFIG_BRIDGE_NF_EBTABLES is not set -# CONFIG_BPFILTER is not set -# CONFIG_IP_DCCP is not set -# CONFIG_IP_SCTP is not set -# CONFIG_RDS is not set -# CONFIG_TIPC is not set -# CONFIG_ATM is not set -# CONFIG_L2TP is not set -CONFIG_STP=m -CONFIG_BRIDGE=m -CONFIG_BRIDGE_IGMP_SNOOPING=y -CONFIG_BRIDGE_VLAN_FILTERING=y -# CONFIG_BRIDGE_MRP is not set -# CONFIG_BRIDGE_CFM is not set -# CONFIG_NET_DSA is not set -CONFIG_VLAN_8021Q=m -# CONFIG_VLAN_8021Q_GVRP is not set -# CONFIG_VLAN_8021Q_MVRP is not set -CONFIG_LLC=m -# CONFIG_LLC2 is not set -# CONFIG_ATALK is not set -# CONFIG_X25 is not set -# CONFIG_LAPB is not set -# CONFIG_PHONET is not set -# CONFIG_6LOWPAN is not set -# CONFIG_IEEE802154 is not set -CONFIG_NET_SCHED=y - -# -# Queueing/Scheduling -# -# CONFIG_NET_SCH_HTB is not set -# CONFIG_NET_SCH_HFSC is not set -# CONFIG_NET_SCH_PRIO is not set -# CONFIG_NET_SCH_MULTIQ is not set -# CONFIG_NET_SCH_RED is not set -# CONFIG_NET_SCH_SFB is not set -# CONFIG_NET_SCH_SFQ is not set -# CONFIG_NET_SCH_TEQL is not set -# CONFIG_NET_SCH_TBF is not set -# CONFIG_NET_SCH_CBS is not set -# CONFIG_NET_SCH_ETF is not set -# CONFIG_NET_SCH_TAPRIO is not set -# CONFIG_NET_SCH_GRED is not set -# CONFIG_NET_SCH_NETEM is not set -# CONFIG_NET_SCH_DRR is not set -# CONFIG_NET_SCH_MQPRIO is not set -# CONFIG_NET_SCH_SKBPRIO is not set -# CONFIG_NET_SCH_CHOKE is not set -# CONFIG_NET_SCH_QFQ is not set -# CONFIG_NET_SCH_CODEL is not set -# CONFIG_NET_SCH_FQ_CODEL is not set -# CONFIG_NET_SCH_CAKE is not set -# CONFIG_NET_SCH_FQ is not set -# CONFIG_NET_SCH_HHF is not set -# CONFIG_NET_SCH_PIE is not set -# CONFIG_NET_SCH_PLUG is not set -# CONFIG_NET_SCH_ETS is not set -# CONFIG_NET_SCH_DEFAULT is not set - -# -# Classification -# -CONFIG_NET_CLS=y -# CONFIG_NET_CLS_BASIC is not set -# CONFIG_NET_CLS_ROUTE4 is not set -# CONFIG_NET_CLS_FW is not set -# CONFIG_NET_CLS_U32 is not set -# CONFIG_NET_CLS_FLOW is not set -CONFIG_NET_CLS_CGROUP=m -# CONFIG_NET_CLS_BPF is not set -# CONFIG_NET_CLS_FLOWER is not set -# CONFIG_NET_CLS_MATCHALL is not set -# CONFIG_NET_EMATCH is not set -# CONFIG_NET_CLS_ACT is not set -CONFIG_NET_SCH_FIFO=y -# CONFIG_DCB is not set -CONFIG_DNS_RESOLVER=y -# CONFIG_BATMAN_ADV is not set -# CONFIG_OPENVSWITCH is not set -# CONFIG_VSOCKETS is not set -CONFIG_NETLINK_DIAG=y -# CONFIG_MPLS is not set -# CONFIG_NET_NSH is not set -# CONFIG_HSR is not set -# CONFIG_NET_SWITCHDEV is not set -CONFIG_NET_L3_MASTER_DEV=y -# CONFIG_QRTR is not set -# CONFIG_NET_NCSI is not set -CONFIG_PCPU_DEV_REFCNT=y -CONFIG_MAX_SKB_FRAGS=17 -CONFIG_RPS=y -CONFIG_RFS_ACCEL=y -CONFIG_SOCK_RX_QUEUE_MAPPING=y -CONFIG_XPS=y -CONFIG_CGROUP_NET_PRIO=y -CONFIG_CGROUP_NET_CLASSID=y -CONFIG_NET_RX_BUSY_POLL=y -CONFIG_BQL=y -# CONFIG_BPF_STREAM_PARSER is not set -CONFIG_NET_FLOW_LIMIT=y - -# -# Network testing -# -# CONFIG_NET_PKTGEN is not set -# end of Network testing -# end of Networking options - -# CONFIG_HAMRADIO is not set -# CONFIG_CAN is not set -# CONFIG_BT is not set -# CONFIG_AF_RXRPC is not set -# CONFIG_AF_KCM is not set -# CONFIG_MCTP is not set -CONFIG_WIRELESS=y -# CONFIG_CFG80211 is not set - -# -# CFG80211 needs to be enabled for MAC80211 -# -CONFIG_MAC80211_STA_HASH_MAX_SIZE=0 -# CONFIG_RFKILL is not set -CONFIG_NET_9P=y -CONFIG_NET_9P_FD=y -CONFIG_NET_9P_VIRTIO=y -# CONFIG_NET_9P_DEBUG is not set -# CONFIG_CAIF is not set -# CONFIG_CEPH_LIB is not set -# CONFIG_NFC is not set -# CONFIG_PSAMPLE is not set -# CONFIG_NET_IFE is not set -# CONFIG_LWTUNNEL is not set -CONFIG_DST_CACHE=y -CONFIG_GRO_CELLS=y -CONFIG_NET_SELFTESTS=y -CONFIG_NET_SOCK_MSG=y -CONFIG_PAGE_POOL=y -CONFIG_PAGE_POOL_STATS=y -CONFIG_FAILOVER=y -CONFIG_ETHTOOL_NETLINK=y - -# -# Device Drivers -# -CONFIG_HAVE_PCI=y -CONFIG_PCI=y -CONFIG_PCI_DOMAINS=y -CONFIG_PCI_DOMAINS_GENERIC=y -CONFIG_PCIEPORTBUS=y -# CONFIG_PCIEAER is not set -CONFIG_PCIEASPM=y -CONFIG_PCIEASPM_DEFAULT=y -# CONFIG_PCIEASPM_POWERSAVE is not set -# CONFIG_PCIEASPM_POWER_SUPERSAVE is not set -# CONFIG_PCIEASPM_PERFORMANCE is not set -CONFIG_PCIE_PME=y -# CONFIG_PCIE_PTM is not set -CONFIG_PCI_MSI=y -CONFIG_PCI_QUIRKS=y -# CONFIG_PCI_DEBUG is not set -# CONFIG_PCI_STUB is not set -CONFIG_PCI_ECAM=y -# CONFIG_PCI_IOV is not set -# CONFIG_PCI_PRI is not set -# CONFIG_PCI_PASID is not set -# CONFIG_PCIE_BUS_TUNE_OFF is not set -CONFIG_PCIE_BUS_DEFAULT=y -# CONFIG_PCIE_BUS_SAFE is not set -# CONFIG_PCIE_BUS_PERFORMANCE is not set -# CONFIG_PCIE_BUS_PEER2PEER is not set -CONFIG_VGA_ARB=y -CONFIG_VGA_ARB_MAX_GPUS=16 -# CONFIG_HOTPLUG_PCI is not set - -# -# PCI controller drivers -# -# CONFIG_PCI_FTPCI100 is not set -CONFIG_PCI_HOST_COMMON=y -CONFIG_PCI_HOST_GENERIC=y -CONFIG_PCIE_MICROCHIP_HOST=y -# CONFIG_PCIE_RCAR_HOST is not set -CONFIG_PCIE_XILINX=y - -# -# Cadence-based PCIe controllers -# -# CONFIG_PCIE_CADENCE_PLAT_HOST is not set -# CONFIG_PCI_J721E_HOST is not set -# end of Cadence-based PCIe controllers - -# -# DesignWare-based PCIe controllers -# -CONFIG_PCIE_DW=y -CONFIG_PCIE_DW_HOST=y -# CONFIG_PCI_MESON is not set -# CONFIG_PCIE_DW_PLAT_HOST is not set -CONFIG_PCIE_FU740=y -# end of DesignWare-based PCIe controllers - -# -# Mobiveil-based PCIe controllers -# -# end of Mobiveil-based PCIe controllers -# end of PCI controller drivers - -# -# PCI Endpoint -# -# CONFIG_PCI_ENDPOINT is not set -# end of PCI Endpoint - -# -# PCI switch controller drivers -# -# CONFIG_PCI_SW_SWITCHTEC is not set -# end of PCI switch controller drivers - -# CONFIG_CXL_BUS is not set -# CONFIG_PCCARD is not set -# CONFIG_RAPIDIO is not set - -# -# Generic Driver Options -# -CONFIG_AUXILIARY_BUS=y -# CONFIG_UEVENT_HELPER is not set -CONFIG_DEVTMPFS=y -CONFIG_DEVTMPFS_MOUNT=y -# CONFIG_DEVTMPFS_SAFE is not set -CONFIG_STANDALONE=y -CONFIG_PREVENT_FIRMWARE_BUILD=y - -# -# Firmware loader -# -CONFIG_FW_LOADER=y -CONFIG_EXTRA_FIRMWARE="" -# CONFIG_FW_LOADER_USER_HELPER is not set -# CONFIG_FW_LOADER_COMPRESS is not set -# CONFIG_FW_UPLOAD is not set -# end of Firmware loader - -CONFIG_WANT_DEV_COREDUMP=y -CONFIG_ALLOW_DEV_COREDUMP=y -CONFIG_DEV_COREDUMP=y -# CONFIG_DEBUG_DRIVER is not set -# CONFIG_DEBUG_DEVRES is not set -# CONFIG_DEBUG_TEST_DRIVER_REMOVE is not set -# CONFIG_TEST_ASYNC_DRIVER_PROBE is not set -CONFIG_SOC_BUS=y -CONFIG_REGMAP=y -CONFIG_REGMAP_I2C=y -CONFIG_REGMAP_MMIO=y -CONFIG_DMA_SHARED_BUFFER=y -# CONFIG_DMA_FENCE_TRACE is not set -CONFIG_GENERIC_ARCH_TOPOLOGY=y -# CONFIG_FW_DEVLINK_SYNC_STATE_TIMEOUT is not set -# end of Generic Driver Options - -# -# Bus devices -# -# CONFIG_MOXTET is not set -# CONFIG_SUN50I_DE2_BUS is not set -# CONFIG_SUNXI_RSB is not set -# CONFIG_MHI_BUS is not set -# CONFIG_MHI_BUS_EP is not set -# end of Bus devices - -# CONFIG_CONNECTOR is not set - -# -# Firmware Drivers -# - -# -# ARM System Control and Management Interface Protocol -# -# end of ARM System Control and Management Interface Protocol - -# CONFIG_FIRMWARE_MEMMAP is not set -# CONFIG_SYSFB_SIMPLEFB is not set -# CONFIG_GOOGLE_FIRMWARE is not set - -# -# EFI (Extensible Firmware Interface) Support -# -CONFIG_EFI_ESRT=y -CONFIG_EFI_PARAMS_FROM_FDT=y -CONFIG_EFI_RUNTIME_WRAPPERS=y -CONFIG_EFI_GENERIC_STUB=y -# CONFIG_EFI_ZBOOT is not set -# CONFIG_EFI_BOOTLOADER_CONTROL is not set -# CONFIG_EFI_CAPSULE_LOADER is not set -# CONFIG_EFI_TEST is not set -# CONFIG_RESET_ATTACK_MITIGATION is not set -# CONFIG_EFI_DISABLE_PCI_DMA is not set -CONFIG_EFI_EARLYCON=y -# CONFIG_EFI_DISABLE_RUNTIME is not set -# CONFIG_EFI_COCO_SECRET is not set -# end of EFI (Extensible Firmware Interface) Support - -# -# Tegra firmware driver -# -# end of Tegra firmware driver -# end of Firmware Drivers - -# CONFIG_GNSS is not set -# CONFIG_MTD is not set -CONFIG_DTC=y -CONFIG_OF=y -# CONFIG_OF_UNITTEST is not set -CONFIG_OF_FLATTREE=y -CONFIG_OF_EARLY_FLATTREE=y -CONFIG_OF_KOBJ=y -CONFIG_OF_DYNAMIC=y -CONFIG_OF_ADDRESS=y -CONFIG_OF_IRQ=y -CONFIG_OF_RESERVED_MEM=y -CONFIG_OF_RESOLVE=y -CONFIG_OF_OVERLAY=y -# CONFIG_PARPORT is not set -CONFIG_BLK_DEV=y -# CONFIG_BLK_DEV_NULL_BLK is not set -CONFIG_CDROM=y -# CONFIG_BLK_DEV_PCIESSD_MTIP32XX is not set -CONFIG_BLK_DEV_LOOP=y -CONFIG_BLK_DEV_LOOP_MIN_COUNT=8 -# CONFIG_BLK_DEV_DRBD is not set -# CONFIG_BLK_DEV_NBD is not set -# CONFIG_BLK_DEV_RAM is not set -# CONFIG_CDROM_PKTCDVD is not set -# CONFIG_ATA_OVER_ETH is not set -CONFIG_VIRTIO_BLK=y -# CONFIG_BLK_DEV_RBD is not set -# CONFIG_BLK_DEV_UBLK is not set - -# -# NVME Support -# -CONFIG_NVME_CORE=m -CONFIG_BLK_DEV_NVME=m -# CONFIG_NVME_MULTIPATH is not set -# CONFIG_NVME_VERBOSE_ERRORS is not set -# CONFIG_NVME_HWMON is not set -# CONFIG_NVME_FC is not set -# CONFIG_NVME_TCP is not set -# CONFIG_NVME_AUTH is not set -# CONFIG_NVME_TARGET is not set -# end of NVME Support - -# -# Misc devices -# -# CONFIG_AD525X_DPOT is not set -# CONFIG_DUMMY_IRQ is not set -# CONFIG_PHANTOM is not set -# CONFIG_TIFM_CORE is not set -# CONFIG_ICS932S401 is not set -# CONFIG_ENCLOSURE_SERVICES is not set -# CONFIG_HP_ILO is not set -# CONFIG_APDS9802ALS is not set -# CONFIG_ISL29003 is not set -# CONFIG_ISL29020 is not set -# CONFIG_SENSORS_TSL2550 is not set -# CONFIG_SENSORS_BH1770 is not set -# CONFIG_SENSORS_APDS990X is not set -# CONFIG_HMC6352 is not set -# CONFIG_DS1682 is not set -# CONFIG_LATTICE_ECP3_CONFIG is not set -# CONFIG_SRAM is not set -# CONFIG_DW_XDATA_PCIE is not set -# CONFIG_PCI_ENDPOINT_TEST is not set -# CONFIG_XILINX_SDFEC is not set -# CONFIG_OPEN_DICE is not set -# CONFIG_VCPU_STALL_DETECTOR is not set -# CONFIG_C2PORT is not set - -# -# EEPROM support -# -CONFIG_EEPROM_AT24=y -# CONFIG_EEPROM_AT25 is not set -# CONFIG_EEPROM_LEGACY is not set -# CONFIG_EEPROM_MAX6875 is not set -# CONFIG_EEPROM_93CX6 is not set -# CONFIG_EEPROM_93XX46 is not set -# CONFIG_EEPROM_IDT_89HPESX is not set -# CONFIG_EEPROM_EE1004 is not set -# end of EEPROM support - -# CONFIG_CB710_CORE is not set - -# -# Texas Instruments shared transport line discipline -# -# CONFIG_TI_ST is not set -# end of Texas Instruments shared transport line discipline - -# CONFIG_SENSORS_LIS3_SPI is not set -# CONFIG_SENSORS_LIS3_I2C is not set -# CONFIG_ALTERA_STAPL is not set -# CONFIG_GENWQE is not set -# CONFIG_ECHO is not set -# CONFIG_BCM_VK is not set -# CONFIG_MISC_ALCOR_PCI is not set -# CONFIG_MISC_RTSX_PCI is not set -# CONFIG_MISC_RTSX_USB is not set -# CONFIG_UACCE is not set -# CONFIG_PVPANIC is not set -# CONFIG_GP_PCI1XXXX is not set -# end of Misc devices - -# -# SCSI device support -# -CONFIG_SCSI_MOD=y -# CONFIG_RAID_ATTRS is not set -CONFIG_SCSI_COMMON=y -CONFIG_SCSI=y -CONFIG_SCSI_DMA=y -CONFIG_SCSI_PROC_FS=y - -# -# SCSI support type (disk, tape, CD-ROM) -# -CONFIG_BLK_DEV_SD=y -# CONFIG_CHR_DEV_ST is not set -CONFIG_BLK_DEV_SR=y -# CONFIG_CHR_DEV_SG is not set -CONFIG_BLK_DEV_BSG=y -# CONFIG_CHR_DEV_SCH is not set -# CONFIG_SCSI_CONSTANTS is not set -# CONFIG_SCSI_LOGGING is not set -# CONFIG_SCSI_SCAN_ASYNC is not set - -# -# SCSI Transports -# -# CONFIG_SCSI_SPI_ATTRS is not set -# CONFIG_SCSI_FC_ATTRS is not set -# CONFIG_SCSI_ISCSI_ATTRS is not set -# CONFIG_SCSI_SAS_ATTRS is not set -# CONFIG_SCSI_SAS_LIBSAS is not set -# CONFIG_SCSI_SRP_ATTRS is not set -# end of SCSI Transports - -CONFIG_SCSI_LOWLEVEL=y -# CONFIG_ISCSI_TCP is not set -# CONFIG_ISCSI_BOOT_SYSFS is not set -# CONFIG_SCSI_CXGB3_ISCSI is not set -# CONFIG_SCSI_CXGB4_ISCSI is not set -# CONFIG_SCSI_BNX2_ISCSI is not set -# CONFIG_BE2ISCSI is not set -# CONFIG_BLK_DEV_3W_XXXX_RAID is not set -# CONFIG_SCSI_HPSA is not set -# CONFIG_SCSI_3W_9XXX is not set -# CONFIG_SCSI_3W_SAS is not set -# CONFIG_SCSI_ACARD is not set -# CONFIG_SCSI_AACRAID is not set -# CONFIG_SCSI_AIC7XXX is not set -# CONFIG_SCSI_AIC79XX is not set -# CONFIG_SCSI_AIC94XX is not set -# CONFIG_SCSI_MVSAS is not set -# CONFIG_SCSI_MVUMI is not set -# CONFIG_SCSI_ADVANSYS is not set -# CONFIG_SCSI_ARCMSR is not set -# CONFIG_SCSI_ESAS2R is not set -# CONFIG_MEGARAID_NEWGEN is not set -# CONFIG_MEGARAID_LEGACY is not set -# CONFIG_MEGARAID_SAS is not set -# CONFIG_SCSI_MPT3SAS is not set -# CONFIG_SCSI_MPT2SAS is not set -# CONFIG_SCSI_MPI3MR is not set -# CONFIG_SCSI_SMARTPQI is not set -# CONFIG_SCSI_HPTIOP is not set -# CONFIG_SCSI_BUSLOGIC is not set -# CONFIG_SCSI_MYRB is not set -# CONFIG_SCSI_MYRS is not set -# CONFIG_SCSI_SNIC is not set -# CONFIG_SCSI_DMX3191D is not set -# CONFIG_SCSI_FDOMAIN_PCI is not set -# CONFIG_SCSI_IPS is not set -# CONFIG_SCSI_INITIO is not set -# CONFIG_SCSI_INIA100 is not set -# CONFIG_SCSI_STEX is not set -# CONFIG_SCSI_SYM53C8XX_2 is not set -# CONFIG_SCSI_IPR is not set -# CONFIG_SCSI_QLOGIC_1280 is not set -# CONFIG_SCSI_QLA_ISCSI is not set -# CONFIG_SCSI_DC395x is not set -# CONFIG_SCSI_AM53C974 is not set -# CONFIG_SCSI_WD719X is not set -# CONFIG_SCSI_DEBUG is not set -# CONFIG_SCSI_PMCRAID is not set -# CONFIG_SCSI_PM8001 is not set -CONFIG_SCSI_VIRTIO=y -# CONFIG_SCSI_DH is not set -# end of SCSI device support - -CONFIG_ATA=y -CONFIG_SATA_HOST=y -CONFIG_ATA_VERBOSE_ERROR=y -CONFIG_ATA_FORCE=y -CONFIG_SATA_PMP=y - -# -# Controllers with non-SFF native interface -# -CONFIG_SATA_AHCI=y -CONFIG_SATA_MOBILE_LPM_POLICY=0 -CONFIG_SATA_AHCI_PLATFORM=y -# CONFIG_AHCI_DWC is not set -# CONFIG_AHCI_CEVA is not set -# CONFIG_AHCI_SUNXI is not set -# CONFIG_SATA_INIC162X is not set -# CONFIG_SATA_ACARD_AHCI is not set -# CONFIG_SATA_SIL24 is not set -CONFIG_ATA_SFF=y - -# -# SFF controllers with custom DMA interface -# -# CONFIG_PDC_ADMA is not set -# CONFIG_SATA_QSTOR is not set -# CONFIG_SATA_SX4 is not set -CONFIG_ATA_BMDMA=y - -# -# SATA SFF controllers with BMDMA -# -# CONFIG_ATA_PIIX is not set -# CONFIG_SATA_DWC is not set -# CONFIG_SATA_MV is not set -# CONFIG_SATA_NV is not set -# CONFIG_SATA_PROMISE is not set -# CONFIG_SATA_RCAR is not set -# CONFIG_SATA_SIL is not set -# CONFIG_SATA_SIS is not set -# CONFIG_SATA_SVW is not set -# CONFIG_SATA_ULI is not set -# CONFIG_SATA_VIA is not set -# CONFIG_SATA_VITESSE is not set - -# -# PATA SFF controllers with BMDMA -# -# CONFIG_PATA_ALI is not set -# CONFIG_PATA_AMD is not set -# CONFIG_PATA_ARTOP is not set -# CONFIG_PATA_ATIIXP is not set -# CONFIG_PATA_ATP867X is not set -# CONFIG_PATA_CMD64X is not set -# CONFIG_PATA_CYPRESS is not set -# CONFIG_PATA_EFAR is not set -# CONFIG_PATA_HPT366 is not set -# CONFIG_PATA_HPT37X is not set -# CONFIG_PATA_HPT3X2N is not set -# CONFIG_PATA_HPT3X3 is not set -# CONFIG_PATA_IT8213 is not set -# CONFIG_PATA_IT821X is not set -# CONFIG_PATA_JMICRON is not set -# CONFIG_PATA_MARVELL is not set -# CONFIG_PATA_NETCELL is not set -# CONFIG_PATA_NINJA32 is not set -# CONFIG_PATA_NS87415 is not set -# CONFIG_PATA_OLDPIIX is not set -# CONFIG_PATA_OPTIDMA is not set -# CONFIG_PATA_PDC2027X is not set -# CONFIG_PATA_PDC_OLD is not set -# CONFIG_PATA_RADISYS is not set -# CONFIG_PATA_RDC is not set -# CONFIG_PATA_SCH is not set -# CONFIG_PATA_SERVERWORKS is not set -# CONFIG_PATA_SIL680 is not set -# CONFIG_PATA_SIS is not set -# CONFIG_PATA_TOSHIBA is not set -# CONFIG_PATA_TRIFLEX is not set -# CONFIG_PATA_VIA is not set -# CONFIG_PATA_WINBOND is not set - -# -# PIO-only SFF controllers -# -# CONFIG_PATA_CMD640_PCI is not set -# CONFIG_PATA_MPIIX is not set -# CONFIG_PATA_NS87410 is not set -# CONFIG_PATA_OPTI is not set -# CONFIG_PATA_OF_PLATFORM is not set -# CONFIG_PATA_RZ1000 is not set - -# -# Generic fallback / legacy drivers -# -# CONFIG_ATA_GENERIC is not set -# CONFIG_PATA_LEGACY is not set -CONFIG_MD=y -# CONFIG_BLK_DEV_MD is not set -# CONFIG_BCACHE is not set -CONFIG_BLK_DEV_DM_BUILTIN=y -CONFIG_BLK_DEV_DM=y -# CONFIG_DM_DEBUG is not set -CONFIG_DM_BUFIO=m -# CONFIG_DM_DEBUG_BLOCK_MANAGER_LOCKING is not set -CONFIG_DM_BIO_PRISON=m -CONFIG_DM_PERSISTENT_DATA=m -# CONFIG_DM_UNSTRIPED is not set -# CONFIG_DM_CRYPT is not set -# CONFIG_DM_SNAPSHOT is not set -CONFIG_DM_THIN_PROVISIONING=m -# CONFIG_DM_CACHE is not set -# CONFIG_DM_WRITECACHE is not set -# CONFIG_DM_EBS is not set -# CONFIG_DM_ERA is not set -# CONFIG_DM_CLONE is not set -# CONFIG_DM_MIRROR is not set -# CONFIG_DM_RAID is not set -# CONFIG_DM_ZERO is not set -# CONFIG_DM_MULTIPATH is not set -# CONFIG_DM_DELAY is not set -# CONFIG_DM_DUST is not set -# CONFIG_DM_INIT is not set -# CONFIG_DM_UEVENT is not set -# CONFIG_DM_FLAKEY is not set -# CONFIG_DM_VERITY is not set -# CONFIG_DM_SWITCH is not set -# CONFIG_DM_LOG_WRITES is not set -# CONFIG_DM_INTEGRITY is not set -# CONFIG_DM_AUDIT is not set -# CONFIG_TARGET_CORE is not set -# CONFIG_FUSION is not set - -# -# IEEE 1394 (FireWire) support -# -# CONFIG_FIREWIRE is not set -# CONFIG_FIREWIRE_NOSY is not set -# end of IEEE 1394 (FireWire) support - -CONFIG_NETDEVICES=y -CONFIG_MII=m -CONFIG_NET_CORE=y -# CONFIG_BONDING is not set -CONFIG_DUMMY=m -# CONFIG_WIREGUARD is not set -# CONFIG_EQUALIZER is not set -# CONFIG_NET_FC is not set -# CONFIG_NET_TEAM is not set -CONFIG_MACVLAN=m -# CONFIG_MACVTAP is not set -CONFIG_IPVLAN_L3S=y -CONFIG_IPVLAN=m -# CONFIG_IPVTAP is not set -CONFIG_VXLAN=m -# CONFIG_GENEVE is not set -# CONFIG_BAREUDP is not set -# CONFIG_GTP is not set -# CONFIG_AMT is not set -# CONFIG_MACSEC is not set -# CONFIG_NETCONSOLE is not set -# CONFIG_TUN is not set -# CONFIG_TUN_VNET_CROSS_LE is not set -CONFIG_VETH=m -CONFIG_VIRTIO_NET=y -# CONFIG_NLMON is not set -# CONFIG_ARCNET is not set -CONFIG_ETHERNET=y -CONFIG_NET_VENDOR_3COM=y -# CONFIG_VORTEX is not set -# CONFIG_TYPHOON is not set -CONFIG_NET_VENDOR_ADAPTEC=y -# CONFIG_ADAPTEC_STARFIRE is not set -CONFIG_NET_VENDOR_AGERE=y -# CONFIG_ET131X is not set -CONFIG_NET_VENDOR_ALACRITECH=y -# CONFIG_SLICOSS is not set -CONFIG_NET_VENDOR_ALLWINNER=y -# CONFIG_SUN4I_EMAC is not set -CONFIG_NET_VENDOR_ALTEON=y -# CONFIG_ACENIC is not set -# CONFIG_ALTERA_TSE is not set -CONFIG_NET_VENDOR_AMAZON=y -# CONFIG_ENA_ETHERNET is not set -CONFIG_NET_VENDOR_AMD=y -# CONFIG_AMD8111_ETH is not set -# CONFIG_PCNET32 is not set -# CONFIG_PDS_CORE is not set -CONFIG_NET_VENDOR_AQUANTIA=y -# CONFIG_AQTION is not set -CONFIG_NET_VENDOR_ARC=y -CONFIG_NET_VENDOR_ASIX=y -# CONFIG_SPI_AX88796C is not set -CONFIG_NET_VENDOR_ATHEROS=y -# CONFIG_ATL2 is not set -# CONFIG_ATL1 is not set -# CONFIG_ATL1E is not set -# CONFIG_ATL1C is not set -# CONFIG_ALX is not set -CONFIG_NET_VENDOR_BROADCOM=y -# CONFIG_B44 is not set -# CONFIG_BCMGENET is not set -# CONFIG_BNX2 is not set -# CONFIG_CNIC is not set -# CONFIG_TIGON3 is not set -# CONFIG_BNX2X is not set -# CONFIG_SYSTEMPORT is not set -# CONFIG_BNXT is not set -CONFIG_NET_VENDOR_CADENCE=y -CONFIG_MACB=y -# CONFIG_MACB_PCI is not set -CONFIG_NET_VENDOR_CAVIUM=y -# CONFIG_THUNDER_NIC_PF is not set -# CONFIG_THUNDER_NIC_VF is not set -# CONFIG_THUNDER_NIC_BGX is not set -# CONFIG_THUNDER_NIC_RGX is not set -# CONFIG_LIQUIDIO is not set -# CONFIG_LIQUIDIO_VF is not set -CONFIG_NET_VENDOR_CHELSIO=y -# CONFIG_CHELSIO_T1 is not set -# CONFIG_CHELSIO_T3 is not set -# CONFIG_CHELSIO_T4 is not set -# CONFIG_CHELSIO_T4VF is not set -CONFIG_NET_VENDOR_CISCO=y -# CONFIG_ENIC is not set -CONFIG_NET_VENDOR_CORTINA=y -# CONFIG_GEMINI_ETHERNET is not set -CONFIG_NET_VENDOR_DAVICOM=y -# CONFIG_DM9051 is not set -# CONFIG_DNET is not set -CONFIG_NET_VENDOR_DEC=y -# CONFIG_NET_TULIP is not set -CONFIG_NET_VENDOR_DLINK=y -# CONFIG_DL2K is not set -# CONFIG_SUNDANCE is not set -CONFIG_NET_VENDOR_EMULEX=y -# CONFIG_BE2NET is not set -CONFIG_NET_VENDOR_ENGLEDER=y -# CONFIG_TSNEP is not set -CONFIG_NET_VENDOR_EZCHIP=y -# CONFIG_EZCHIP_NPS_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_FUNGIBLE=y -# CONFIG_FUN_ETH is not set -CONFIG_NET_VENDOR_GOOGLE=y -CONFIG_NET_VENDOR_HUAWEI=y -CONFIG_NET_VENDOR_I825XX=y -CONFIG_NET_VENDOR_INTEL=y -# CONFIG_E100 is not set -# CONFIG_E1000 is not set -CONFIG_E1000E=y -# CONFIG_IGB is not set -# CONFIG_IGBVF is not set -# CONFIG_IXGBE is not set -# CONFIG_IXGBEVF is not set -# CONFIG_I40E is not set -# CONFIG_I40EVF is not set -# CONFIG_ICE is not set -# CONFIG_FM10K is not set -# CONFIG_IGC is not set -# CONFIG_JME is not set -CONFIG_NET_VENDOR_ADI=y -CONFIG_NET_VENDOR_LITEX=y -# CONFIG_LITEX_LITEETH is not set -CONFIG_NET_VENDOR_MARVELL=y -# CONFIG_MVMDIO is not set -# CONFIG_SKGE is not set -# CONFIG_SKY2 is not set -# CONFIG_OCTEON_EP is not set -CONFIG_NET_VENDOR_MELLANOX=y -# CONFIG_MLX4_EN is not set -# CONFIG_MLX5_CORE is not set -# CONFIG_MLXSW_CORE is not set -# CONFIG_MLXFW is not set -CONFIG_NET_VENDOR_MICREL=y -# CONFIG_KS8842 is not set -# CONFIG_KS8851 is not set -# CONFIG_KS8851_MLL is not set -# CONFIG_KSZ884X_PCI is not set -CONFIG_NET_VENDOR_MICROCHIP=y -# CONFIG_ENC28J60 is not set -# CONFIG_ENCX24J600 is not set -# CONFIG_LAN743X is not set -# CONFIG_VCAP is not set -CONFIG_NET_VENDOR_MICROSEMI=y -CONFIG_NET_VENDOR_MICROSOFT=y -CONFIG_NET_VENDOR_MYRI=y -# CONFIG_MYRI10GE is not set -# CONFIG_FEALNX is not set -CONFIG_NET_VENDOR_NI=y -# CONFIG_NI_XGE_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_NATSEMI=y -# CONFIG_NATSEMI is not set -# CONFIG_NS83820 is not set -CONFIG_NET_VENDOR_NETERION=y -# CONFIG_S2IO is not set -CONFIG_NET_VENDOR_NETRONOME=y -# CONFIG_NFP is not set -CONFIG_NET_VENDOR_8390=y -# CONFIG_NE2K_PCI is not set -CONFIG_NET_VENDOR_NVIDIA=y -# CONFIG_FORCEDETH is not set -CONFIG_NET_VENDOR_OKI=y -# CONFIG_ETHOC is not set -CONFIG_NET_VENDOR_PACKET_ENGINES=y -# CONFIG_HAMACHI is not set -# CONFIG_YELLOWFIN is not set -CONFIG_NET_VENDOR_PENSANDO=y -# CONFIG_IONIC is not set -CONFIG_NET_VENDOR_QLOGIC=y -# CONFIG_QLA3XXX is not set -# CONFIG_QLCNIC is not set -# CONFIG_NETXEN_NIC is not set -# CONFIG_QED is not set -CONFIG_NET_VENDOR_BROCADE=y -# CONFIG_BNA is not set -CONFIG_NET_VENDOR_QUALCOMM=y -# CONFIG_QCA7000_SPI is not set -# CONFIG_QCOM_EMAC is not set -# CONFIG_RMNET is not set -CONFIG_NET_VENDOR_RDC=y -# CONFIG_R6040 is not set -CONFIG_NET_VENDOR_REALTEK=y -# CONFIG_8139CP is not set -# CONFIG_8139TOO is not set -CONFIG_R8169=y -CONFIG_NET_VENDOR_RENESAS=y -# CONFIG_SH_ETH is not set -# CONFIG_RAVB is not set -# CONFIG_RENESAS_ETHER_SWITCH is not set -CONFIG_NET_VENDOR_ROCKER=y -CONFIG_NET_VENDOR_SAMSUNG=y -# CONFIG_SXGBE_ETH is not set -CONFIG_NET_VENDOR_SEEQ=y -CONFIG_NET_VENDOR_SILAN=y -# CONFIG_SC92031 is not set -CONFIG_NET_VENDOR_SIS=y -# CONFIG_SIS900 is not set -# CONFIG_SIS190 is not set -CONFIG_NET_VENDOR_SOLARFLARE=y -# CONFIG_SFC is not set -# CONFIG_SFC_FALCON is not set -CONFIG_NET_VENDOR_SMSC=y -# CONFIG_EPIC100 is not set -# CONFIG_SMSC911X is not set -# CONFIG_SMSC9420 is not set -CONFIG_NET_VENDOR_SOCIONEXT=y -CONFIG_NET_VENDOR_STMICRO=y -CONFIG_STMMAC_ETH=m -# CONFIG_STMMAC_SELFTESTS is not set -CONFIG_STMMAC_PLATFORM=m -# CONFIG_DWMAC_DWC_QOS_ETH is not set -CONFIG_DWMAC_GENERIC=m -CONFIG_DWMAC_STARFIVE=m -CONFIG_DWMAC_SUNXI=m -CONFIG_DWMAC_SUN8I=m -# CONFIG_DWMAC_INTEL_PLAT is not set -# CONFIG_DWMAC_LOONGSON is not set -# CONFIG_STMMAC_PCI is not set -CONFIG_NET_VENDOR_SUN=y -# CONFIG_HAPPYMEAL is not set -# CONFIG_SUNGEM is not set -# CONFIG_CASSINI is not set -# CONFIG_NIU is not set -CONFIG_NET_VENDOR_SYNOPSYS=y -# CONFIG_DWC_XLGMAC is not set -CONFIG_NET_VENDOR_TEHUTI=y -# CONFIG_TEHUTI is not set -CONFIG_NET_VENDOR_TI=y -# CONFIG_TI_CPSW_PHY_SEL is not set -# CONFIG_TLAN is not set -CONFIG_NET_VENDOR_VERTEXCOM=y -# CONFIG_MSE102X is not set -CONFIG_NET_VENDOR_VIA=y -# CONFIG_VIA_RHINE is not set -# CONFIG_VIA_VELOCITY is not set -CONFIG_NET_VENDOR_WANGXUN=y -# CONFIG_NGBE is not set -# CONFIG_TXGBE is not set -CONFIG_NET_VENDOR_WIZNET=y -# CONFIG_WIZNET_W5100 is not set -# CONFIG_WIZNET_W5300 is not set -CONFIG_NET_VENDOR_XILINX=y -# CONFIG_XILINX_EMACLITE is not set -# CONFIG_XILINX_AXI_EMAC is not set -# CONFIG_XILINX_LL_TEMAC is not set -# CONFIG_FDDI is not set -# CONFIG_HIPPI is not set -CONFIG_PHYLINK=y -CONFIG_PHYLIB=y -CONFIG_SWPHY=y -CONFIG_FIXED_PHY=y -# CONFIG_SFP is not set - -# -# MII PHY device drivers -# -# CONFIG_AMD_PHY is not set -# CONFIG_ADIN_PHY is not set -# CONFIG_ADIN1100_PHY is not set -# CONFIG_AQUANTIA_PHY is not set -# CONFIG_AX88796B_PHY is not set -# CONFIG_BROADCOM_PHY is not set -# CONFIG_BCM54140_PHY is not set -# CONFIG_BCM7XXX_PHY is not set -# CONFIG_BCM84881_PHY is not set -# CONFIG_BCM87XX_PHY is not set -# CONFIG_CICADA_PHY is not set -# CONFIG_CORTINA_PHY is not set -# CONFIG_DAVICOM_PHY is not set -# CONFIG_ICPLUS_PHY is not set -# CONFIG_LXT_PHY is not set -# CONFIG_INTEL_XWAY_PHY is not set -# CONFIG_LSI_ET1011C_PHY is not set -# CONFIG_MARVELL_PHY is not set -# CONFIG_MARVELL_10G_PHY is not set -# CONFIG_MARVELL_88X2222_PHY is not set -# CONFIG_MAXLINEAR_GPHY is not set -# CONFIG_MEDIATEK_GE_PHY is not set -# CONFIG_MICREL_PHY is not set -# CONFIG_MICROCHIP_T1S_PHY is not set -# CONFIG_MICROCHIP_PHY is not set -# CONFIG_MICROCHIP_T1_PHY is not set -CONFIG_MICROSEMI_PHY=y -# CONFIG_MOTORCOMM_PHY is not set -# CONFIG_NATIONAL_PHY is not set -# CONFIG_NXP_CBTX_PHY is not set -# CONFIG_NXP_C45_TJA11XX_PHY is not set -# CONFIG_NXP_TJA11XX_PHY is not set -# CONFIG_NCN26000_PHY is not set -# CONFIG_AT803X_PHY is not set -# CONFIG_QSEMI_PHY is not set -CONFIG_REALTEK_PHY=y -# CONFIG_RENESAS_PHY is not set -# CONFIG_ROCKCHIP_PHY is not set -# CONFIG_SMSC_PHY is not set -# CONFIG_STE10XP is not set -# CONFIG_TERANETICS_PHY is not set -# CONFIG_DP83822_PHY is not set -# CONFIG_DP83TC811_PHY is not set -# CONFIG_DP83848_PHY is not set -# CONFIG_DP83867_PHY is not set -# CONFIG_DP83869_PHY is not set -# CONFIG_DP83TD510_PHY is not set -# CONFIG_VITESSE_PHY is not set -# CONFIG_XILINX_GMII2RGMII is not set -# CONFIG_MICREL_KS8995MA is not set -# CONFIG_PSE_CONTROLLER is not set -CONFIG_MDIO_DEVICE=y -CONFIG_MDIO_BUS=y -CONFIG_FWNODE_MDIO=y -CONFIG_OF_MDIO=y -CONFIG_MDIO_DEVRES=y -# CONFIG_MDIO_SUN4I is not set -# CONFIG_MDIO_BITBANG is not set -# CONFIG_MDIO_BCM_UNIMAC is not set -# CONFIG_MDIO_HISI_FEMAC is not set -# CONFIG_MDIO_MVUSB is not set -# CONFIG_MDIO_MSCC_MIIM is not set -# CONFIG_MDIO_OCTEON is not set -# CONFIG_MDIO_IPQ4019 is not set -# CONFIG_MDIO_IPQ8064 is not set -# CONFIG_MDIO_THUNDER is not set - -# -# MDIO Multiplexers -# -CONFIG_MDIO_BUS_MUX=m -# CONFIG_MDIO_BUS_MUX_GPIO is not set -# CONFIG_MDIO_BUS_MUX_MULTIPLEXER is not set -# CONFIG_MDIO_BUS_MUX_MMIOREG is not set - -# -# PCS device drivers -# -CONFIG_PCS_XPCS=m -# end of PCS device drivers - -# CONFIG_PPP is not set -# CONFIG_SLIP is not set -CONFIG_USB_NET_DRIVERS=y -# CONFIG_USB_CATC is not set -# CONFIG_USB_KAWETH is not set -# CONFIG_USB_PEGASUS is not set -# CONFIG_USB_RTL8150 is not set -# CONFIG_USB_RTL8152 is not set -# CONFIG_USB_LAN78XX is not set -# CONFIG_USB_USBNET is not set -# CONFIG_USB_IPHETH is not set -CONFIG_WLAN=y -CONFIG_WLAN_VENDOR_ADMTEK=y -CONFIG_WLAN_VENDOR_ATH=y -# CONFIG_ATH_DEBUG is not set -# CONFIG_ATH5K_PCI is not set -CONFIG_WLAN_VENDOR_ATMEL=y -CONFIG_WLAN_VENDOR_BROADCOM=y -CONFIG_WLAN_VENDOR_CISCO=y -CONFIG_WLAN_VENDOR_INTEL=y -CONFIG_WLAN_VENDOR_INTERSIL=y -# CONFIG_HOSTAP is not set -CONFIG_WLAN_VENDOR_MARVELL=y -CONFIG_WLAN_VENDOR_MEDIATEK=y -CONFIG_WLAN_VENDOR_MICROCHIP=y -CONFIG_WLAN_VENDOR_PURELIFI=y -CONFIG_WLAN_VENDOR_RALINK=y -CONFIG_WLAN_VENDOR_REALTEK=y -CONFIG_WLAN_VENDOR_RSI=y -CONFIG_WLAN_VENDOR_SILABS=y -CONFIG_WLAN_VENDOR_ST=y -CONFIG_WLAN_VENDOR_TI=y -CONFIG_WLAN_VENDOR_ZYDAS=y -CONFIG_WLAN_VENDOR_QUANTENNA=y -# CONFIG_WAN is not set - -# -# Wireless WAN -# -# CONFIG_WWAN is not set -# end of Wireless WAN - -# CONFIG_VMXNET3 is not set -# CONFIG_NETDEVSIM is not set -CONFIG_NET_FAILOVER=y -# CONFIG_ISDN is not set - -# -# Input device support -# -CONFIG_INPUT=y -# CONFIG_INPUT_FF_MEMLESS is not set -# CONFIG_INPUT_SPARSEKMAP is not set -# CONFIG_INPUT_MATRIXKMAP is not set -CONFIG_INPUT_VIVALDIFMAP=y - -# -# Userland interfaces -# -CONFIG_INPUT_MOUSEDEV=y -# CONFIG_INPUT_MOUSEDEV_PSAUX is not set -CONFIG_INPUT_MOUSEDEV_SCREEN_X=1024 -CONFIG_INPUT_MOUSEDEV_SCREEN_Y=768 -# CONFIG_INPUT_JOYDEV is not set -# CONFIG_INPUT_EVDEV is not set -# CONFIG_INPUT_EVBUG is not set - -# -# Input Device Drivers -# -CONFIG_INPUT_KEYBOARD=y -# CONFIG_KEYBOARD_ADC is not set -# CONFIG_KEYBOARD_ADP5588 is not set -# CONFIG_KEYBOARD_ADP5589 is not set -CONFIG_KEYBOARD_ATKBD=y -# CONFIG_KEYBOARD_QT1050 is not set -# CONFIG_KEYBOARD_QT1070 is not set -# CONFIG_KEYBOARD_QT2160 is not set -# CONFIG_KEYBOARD_DLINK_DIR685 is not set -# CONFIG_KEYBOARD_LKKBD is not set -# CONFIG_KEYBOARD_GPIO is not set -# CONFIG_KEYBOARD_GPIO_POLLED is not set -# CONFIG_KEYBOARD_TCA6416 is not set -# CONFIG_KEYBOARD_TCA8418 is not set -# CONFIG_KEYBOARD_MATRIX is not set -# CONFIG_KEYBOARD_LM8333 is not set -# CONFIG_KEYBOARD_MAX7359 is not set -# CONFIG_KEYBOARD_MCS is not set -# CONFIG_KEYBOARD_MPR121 is not set -# CONFIG_KEYBOARD_NEWTON is not set -# CONFIG_KEYBOARD_OPENCORES is not set -# CONFIG_KEYBOARD_PINEPHONE is not set -# CONFIG_KEYBOARD_SAMSUNG is not set -# CONFIG_KEYBOARD_GOLDFISH_EVENTS is not set -# CONFIG_KEYBOARD_STOWAWAY is not set -# CONFIG_KEYBOARD_SUNKBD is not set -CONFIG_KEYBOARD_SUN4I_LRADC=m -# CONFIG_KEYBOARD_OMAP4 is not set -# CONFIG_KEYBOARD_XTKBD is not set -# CONFIG_KEYBOARD_CAP11XX is not set -# CONFIG_KEYBOARD_BCM is not set -# CONFIG_KEYBOARD_CYPRESS_SF is not set -CONFIG_INPUT_MOUSE=y -CONFIG_MOUSE_PS2=y -CONFIG_MOUSE_PS2_ALPS=y -CONFIG_MOUSE_PS2_BYD=y -CONFIG_MOUSE_PS2_LOGIPS2PP=y -CONFIG_MOUSE_PS2_SYNAPTICS=y -CONFIG_MOUSE_PS2_SYNAPTICS_SMBUS=y -CONFIG_MOUSE_PS2_CYPRESS=y -CONFIG_MOUSE_PS2_TRACKPOINT=y -# CONFIG_MOUSE_PS2_ELANTECH is not set -# CONFIG_MOUSE_PS2_SENTELIC is not set -# CONFIG_MOUSE_PS2_TOUCHKIT is not set -CONFIG_MOUSE_PS2_FOCALTECH=y -CONFIG_MOUSE_PS2_SMBUS=y -# CONFIG_MOUSE_SERIAL is not set -# CONFIG_MOUSE_APPLETOUCH is not set -# CONFIG_MOUSE_BCM5974 is not set -# CONFIG_MOUSE_CYAPA is not set -# CONFIG_MOUSE_ELAN_I2C is not set -# CONFIG_MOUSE_VSXXXAA is not set -# CONFIG_MOUSE_GPIO is not set -# CONFIG_MOUSE_SYNAPTICS_I2C is not set -# CONFIG_MOUSE_SYNAPTICS_USB is not set -# CONFIG_INPUT_JOYSTICK is not set -# CONFIG_INPUT_TABLET is not set -# CONFIG_INPUT_TOUCHSCREEN is not set -# CONFIG_INPUT_MISC is not set -# CONFIG_RMI4_CORE is not set - -# -# Hardware I/O ports -# -CONFIG_SERIO=y -CONFIG_SERIO_SERPORT=y -# CONFIG_SERIO_PCIPS2 is not set -CONFIG_SERIO_LIBPS2=y -# CONFIG_SERIO_RAW is not set -# CONFIG_SERIO_ALTERA_PS2 is not set -# CONFIG_SERIO_PS2MULT is not set -# CONFIG_SERIO_ARC_PS2 is not set -# CONFIG_SERIO_APBPS2 is not set -# CONFIG_SERIO_SUN4I_PS2 is not set -# CONFIG_SERIO_GPIO_PS2 is not set -# CONFIG_USERIO is not set -# CONFIG_GAMEPORT is not set -# end of Hardware I/O ports -# end of Input device support - -# -# Character devices -# -CONFIG_TTY=y -CONFIG_VT=y -CONFIG_CONSOLE_TRANSLATIONS=y -CONFIG_VT_CONSOLE=y -CONFIG_HW_CONSOLE=y -CONFIG_VT_HW_CONSOLE_BINDING=y -CONFIG_UNIX98_PTYS=y -CONFIG_LEGACY_PTYS=y -CONFIG_LEGACY_PTY_COUNT=256 -CONFIG_LEGACY_TIOCSTI=y -CONFIG_LDISC_AUTOLOAD=y - -# -# Serial drivers -# -CONFIG_SERIAL_EARLYCON=y -CONFIG_SERIAL_8250=y -CONFIG_SERIAL_8250_DEPRECATED_OPTIONS=y -CONFIG_SERIAL_8250_16550A_VARIANTS=y -# CONFIG_SERIAL_8250_FINTEK is not set -CONFIG_SERIAL_8250_CONSOLE=y -CONFIG_SERIAL_8250_DMA=y -CONFIG_SERIAL_8250_PCILIB=y -CONFIG_SERIAL_8250_PCI=y -CONFIG_SERIAL_8250_EXAR=y -CONFIG_SERIAL_8250_NR_UARTS=4 -CONFIG_SERIAL_8250_RUNTIME_UARTS=4 -# CONFIG_SERIAL_8250_EXTENDED is not set -# CONFIG_SERIAL_8250_PCI1XXXX is not set -CONFIG_SERIAL_8250_DWLIB=y -CONFIG_SERIAL_8250_DW=y -# CONFIG_SERIAL_8250_EM is not set -# CONFIG_SERIAL_8250_RT288X is not set -CONFIG_SERIAL_8250_PERICOM=y -CONFIG_SERIAL_OF_PLATFORM=y - -# -# Non-8250 serial port support -# -# CONFIG_SERIAL_EARLYCON_SEMIHOST is not set -# CONFIG_SERIAL_MAX3100 is not set -# CONFIG_SERIAL_MAX310X is not set -# CONFIG_SERIAL_UARTLITE is not set -CONFIG_SERIAL_SH_SCI=y -CONFIG_SERIAL_SH_SCI_NR_UARTS=18 -CONFIG_SERIAL_SH_SCI_CONSOLE=y -CONFIG_SERIAL_SH_SCI_EARLYCON=y -CONFIG_SERIAL_SH_SCI_DMA=y -CONFIG_SERIAL_CORE=y -CONFIG_SERIAL_CORE_CONSOLE=y -# CONFIG_SERIAL_JSM is not set -CONFIG_SERIAL_SIFIVE=y -CONFIG_SERIAL_SIFIVE_CONSOLE=y -# CONFIG_SERIAL_SCCNXP is not set -# CONFIG_SERIAL_SC16IS7XX is not set -# CONFIG_SERIAL_ALTERA_JTAGUART is not set -# CONFIG_SERIAL_ALTERA_UART is not set -# CONFIG_SERIAL_XILINX_PS_UART is not set -# CONFIG_SERIAL_ARC is not set -# CONFIG_SERIAL_RP2 is not set -# CONFIG_SERIAL_FSL_LPUART is not set -# CONFIG_SERIAL_FSL_LINFLEXUART is not set -# CONFIG_SERIAL_CONEXANT_DIGICOLOR is not set -# CONFIG_SERIAL_SPRD is not set -# end of Serial drivers - -CONFIG_SERIAL_MCTRL_GPIO=y -# CONFIG_SERIAL_NONSTANDARD is not set -# CONFIG_GOLDFISH_TTY is not set -# CONFIG_N_GSM is not set -# CONFIG_NOZOMI is not set -# CONFIG_NULL_TTY is not set -CONFIG_HVC_DRIVER=y -# CONFIG_RPMSG_TTY is not set -# CONFIG_SERIAL_DEV_BUS is not set -# CONFIG_TTY_PRINTK is not set -CONFIG_VIRTIO_CONSOLE=y -# CONFIG_IPMI_HANDLER is not set -CONFIG_HW_RANDOM=y -# CONFIG_HW_RANDOM_TIMERIOMEM is not set -# CONFIG_HW_RANDOM_BA431 is not set -CONFIG_HW_RANDOM_VIRTIO=y -CONFIG_HW_RANDOM_POLARFIRE_SOC=y -# CONFIG_HW_RANDOM_CCTRNG is not set -# CONFIG_HW_RANDOM_XIPHERA is not set -# CONFIG_HW_RANDOM_JH7110 is not set -# CONFIG_APPLICOM is not set -CONFIG_DEVMEM=y -CONFIG_DEVPORT=y -# CONFIG_TCG_TPM is not set -# CONFIG_XILLYBUS is not set -# CONFIG_XILLYUSB is not set -# end of Character devices - -# -# I2C support -# -CONFIG_I2C=y -CONFIG_I2C_BOARDINFO=y -CONFIG_I2C_COMPAT=y -# CONFIG_I2C_CHARDEV is not set -CONFIG_I2C_MUX=m - -# -# Multiplexer I2C Chip support -# -# CONFIG_I2C_ARB_GPIO_CHALLENGE is not set -# CONFIG_I2C_MUX_GPIO is not set -# CONFIG_I2C_MUX_GPMUX is not set -# CONFIG_I2C_MUX_LTC4306 is not set -# CONFIG_I2C_MUX_PCA9541 is not set -# CONFIG_I2C_MUX_PCA954x is not set -# CONFIG_I2C_MUX_PINCTRL is not set -# CONFIG_I2C_MUX_REG is not set -# CONFIG_I2C_DEMUX_PINCTRL is not set -# CONFIG_I2C_MUX_MLXCPLD is not set -# end of Multiplexer I2C Chip support - -CONFIG_I2C_HELPER_AUTO=y - -# -# I2C Hardware Bus support -# - -# -# PC SMBus host controller drivers -# -# CONFIG_I2C_ALI1535 is not set -# CONFIG_I2C_ALI1563 is not set -# CONFIG_I2C_ALI15X3 is not set -# CONFIG_I2C_AMD756 is not set -# CONFIG_I2C_AMD8111 is not set -# CONFIG_I2C_I801 is not set -# CONFIG_I2C_ISCH is not set -# CONFIG_I2C_PIIX4 is not set -# CONFIG_I2C_NFORCE2 is not set -# CONFIG_I2C_NVIDIA_GPU is not set -# CONFIG_I2C_SIS5595 is not set -# CONFIG_I2C_SIS630 is not set -# CONFIG_I2C_SIS96X is not set -# CONFIG_I2C_VIA is not set -# CONFIG_I2C_VIAPRO is not set - -# -# I2C system bus drivers (mostly embedded / system-on-chip) -# -# CONFIG_I2C_CBUS_GPIO is not set -# CONFIG_I2C_DESIGNWARE_PLATFORM is not set -# CONFIG_I2C_DESIGNWARE_PCI is not set -# CONFIG_I2C_EMEV2 is not set -# CONFIG_I2C_GPIO is not set -CONFIG_I2C_MICROCHIP_CORE=y -CONFIG_I2C_MV64XXX=m -# CONFIG_I2C_OCORES is not set -# CONFIG_I2C_PCA_PLATFORM is not set -# CONFIG_I2C_RIIC is not set -# CONFIG_I2C_RK3X is not set -# CONFIG_I2C_RZV2M is not set -# CONFIG_I2C_SH_MOBILE is not set -# CONFIG_I2C_SIMTEC is not set -# CONFIG_I2C_XILINX is not set -# CONFIG_I2C_RCAR is not set - -# -# External I2C/SMBus adapter drivers -# -# CONFIG_I2C_DIOLAN_U2C is not set -# CONFIG_I2C_CP2615 is not set -# CONFIG_I2C_PCI1XXXX is not set -# CONFIG_I2C_ROBOTFUZZ_OSIF is not set -# CONFIG_I2C_TAOS_EVM is not set -# CONFIG_I2C_TINY_USB is not set - -# -# Other I2C/SMBus bus drivers -# -# CONFIG_I2C_VIRTIO is not set -# end of I2C Hardware Bus support - -# CONFIG_I2C_STUB is not set -# CONFIG_I2C_SLAVE is not set -# CONFIG_I2C_DEBUG_CORE is not set -# CONFIG_I2C_DEBUG_ALGO is not set -# CONFIG_I2C_DEBUG_BUS is not set -# end of I2C support - -# CONFIG_I3C is not set -CONFIG_SPI=y -# CONFIG_SPI_DEBUG is not set -CONFIG_SPI_MASTER=y -# CONFIG_SPI_MEM is not set - -# -# SPI Master Controller Drivers -# -# CONFIG_SPI_ALTERA is not set -# CONFIG_SPI_AXI_SPI_ENGINE is not set -# CONFIG_SPI_BITBANG is not set -# CONFIG_SPI_CADENCE is not set -# CONFIG_SPI_CADENCE_QUADSPI is not set -# CONFIG_SPI_DESIGNWARE is not set -# CONFIG_SPI_GPIO is not set -# CONFIG_SPI_FSL_SPI is not set -CONFIG_SPI_MICROCHIP_CORE=y -CONFIG_SPI_MICROCHIP_CORE_QSPI=y -# CONFIG_SPI_OC_TINY is not set -# CONFIG_SPI_PCI1XXXX is not set -# CONFIG_SPI_PXA2XX is not set -# CONFIG_SPI_RSPI is not set -# CONFIG_SPI_SC18IS602 is not set -# CONFIG_SPI_SH_MSIOF is not set -# CONFIG_SPI_SH_HSPI is not set -CONFIG_SPI_SIFIVE=y -# CONFIG_SPI_SUN4I is not set -CONFIG_SPI_SUN6I=y -# CONFIG_SPI_MXIC is not set -# CONFIG_SPI_XCOMM is not set -# CONFIG_SPI_XILINX is not set -# CONFIG_SPI_ZYNQMP_GQSPI is not set -# CONFIG_SPI_AMD is not set - -# -# SPI Multiplexer support -# -# CONFIG_SPI_MUX is not set - -# -# SPI Protocol Masters -# -CONFIG_SPI_SPIDEV=m -# CONFIG_SPI_LOOPBACK_TEST is not set -# CONFIG_SPI_TLE62X0 is not set -# CONFIG_SPI_SLAVE is not set -CONFIG_SPI_DYNAMIC=y -# CONFIG_SPMI is not set -# CONFIG_HSI is not set -# CONFIG_PPS is not set - -# -# PTP clock support -# -# CONFIG_PTP_1588_CLOCK is not set -CONFIG_PTP_1588_CLOCK_OPTIONAL=y - -# -# Enable PHYLIB and NETWORK_PHY_TIMESTAMPING to see the additional clocks. -# -# end of PTP clock support - -CONFIG_PINCTRL=y -CONFIG_GENERIC_PINCTRL_GROUPS=y -CONFIG_PINMUX=y -CONFIG_GENERIC_PINMUX_FUNCTIONS=y -CONFIG_PINCONF=y -CONFIG_GENERIC_PINCONF=y -# CONFIG_DEBUG_PINCTRL is not set -# CONFIG_PINCTRL_CY8C95X0 is not set -# CONFIG_PINCTRL_MCP23S08 is not set -# CONFIG_PINCTRL_MICROCHIP_SGPIO is not set -# CONFIG_PINCTRL_OCELOT is not set -# CONFIG_PINCTRL_SINGLE is not set -# CONFIG_PINCTRL_STMFX is not set -# CONFIG_PINCTRL_SX150X is not set - -# -# Renesas pinctrl drivers -# -CONFIG_PINCTRL_RENESAS=y -CONFIG_PINCTRL_RZG2L=y -# end of Renesas pinctrl drivers - -CONFIG_PINCTRL_STARFIVE_JH7100=y -CONFIG_PINCTRL_STARFIVE_JH7110=y -CONFIG_PINCTRL_STARFIVE_JH7110_SYS=y -CONFIG_PINCTRL_STARFIVE_JH7110_AON=y -CONFIG_PINCTRL_SUNXI=y -# CONFIG_PINCTRL_SUN4I_A10 is not set -# CONFIG_PINCTRL_SUN5I is not set -# CONFIG_PINCTRL_SUN6I_A31 is not set -# CONFIG_PINCTRL_SUN6I_A31_R is not set -# CONFIG_PINCTRL_SUN8I_A23 is not set -# CONFIG_PINCTRL_SUN8I_A33 is not set -# CONFIG_PINCTRL_SUN8I_A83T is not set -# CONFIG_PINCTRL_SUN8I_A83T_R is not set -# CONFIG_PINCTRL_SUN8I_A23_R is not set -# CONFIG_PINCTRL_SUN8I_H3 is not set -# CONFIG_PINCTRL_SUN8I_H3_R is not set -# CONFIG_PINCTRL_SUN8I_V3S is not set -# CONFIG_PINCTRL_SUN9I_A80 is not set -# CONFIG_PINCTRL_SUN9I_A80_R is not set -CONFIG_PINCTRL_SUN20I_D1=y -# CONFIG_PINCTRL_SUN50I_A64 is not set -# CONFIG_PINCTRL_SUN50I_A64_R is not set -# CONFIG_PINCTRL_SUN50I_A100 is not set -# CONFIG_PINCTRL_SUN50I_A100_R is not set -# CONFIG_PINCTRL_SUN50I_H5 is not set -# CONFIG_PINCTRL_SUN50I_H6 is not set -# CONFIG_PINCTRL_SUN50I_H6_R is not set -# CONFIG_PINCTRL_SUN50I_H616 is not set -# CONFIG_PINCTRL_SUN50I_H616_R is not set -CONFIG_GPIOLIB=y -CONFIG_GPIOLIB_FASTPATH_LIMIT=512 -CONFIG_OF_GPIO=y -CONFIG_GPIOLIB_IRQCHIP=y -# CONFIG_DEBUG_GPIO is not set -CONFIG_GPIO_SYSFS=y -CONFIG_GPIO_CDEV=y -CONFIG_GPIO_CDEV_V1=y -CONFIG_GPIO_GENERIC=y - -# -# Memory mapped GPIO drivers -# -# CONFIG_GPIO_74XX_MMIO is not set -# CONFIG_GPIO_ALTERA is not set -# CONFIG_GPIO_CADENCE is not set -# CONFIG_GPIO_DWAPB is not set -# CONFIG_GPIO_EXAR is not set -# CONFIG_GPIO_FTGPIO010 is not set -# CONFIG_GPIO_GENERIC_PLATFORM is not set -# CONFIG_GPIO_GRGPIO is not set -# CONFIG_GPIO_HLWD is not set -# CONFIG_GPIO_LOGICVC is not set -# CONFIG_GPIO_MB86S7X is not set -# CONFIG_GPIO_RCAR is not set -CONFIG_GPIO_SIFIVE=y -# CONFIG_GPIO_SYSCON is not set -# CONFIG_GPIO_XILINX is not set -# CONFIG_GPIO_AMD_FCH is not set -# end of Memory mapped GPIO drivers - -# -# I2C GPIO expanders -# -# CONFIG_GPIO_ADNP is not set -# CONFIG_GPIO_FXL6408 is not set -# CONFIG_GPIO_GW_PLD is not set -# CONFIG_GPIO_MAX7300 is not set -# CONFIG_GPIO_MAX732X is not set -# CONFIG_GPIO_PCA953X is not set -# CONFIG_GPIO_PCA9570 is not set -# CONFIG_GPIO_PCF857X is not set -# CONFIG_GPIO_TPIC2810 is not set -# end of I2C GPIO expanders - -# -# MFD GPIO expanders -# -# end of MFD GPIO expanders - -# -# PCI GPIO expanders -# -# CONFIG_GPIO_BT8XX is not set -# CONFIG_GPIO_PCI_IDIO_16 is not set -# CONFIG_GPIO_PCIE_IDIO_24 is not set -# CONFIG_GPIO_RDC321X is not set -# end of PCI GPIO expanders - -# -# SPI GPIO expanders -# -# CONFIG_GPIO_74X164 is not set -# CONFIG_GPIO_MAX3191X is not set -# CONFIG_GPIO_MAX7301 is not set -# CONFIG_GPIO_MC33880 is not set -# CONFIG_GPIO_PISOSR is not set -# CONFIG_GPIO_XRA1403 is not set -# end of SPI GPIO expanders - -# -# USB GPIO expanders -# -# end of USB GPIO expanders - -# -# Virtual GPIO drivers -# -# CONFIG_GPIO_AGGREGATOR is not set -# CONFIG_GPIO_LATCH is not set -# CONFIG_GPIO_MOCKUP is not set -# CONFIG_GPIO_VIRTIO is not set -# CONFIG_GPIO_SIM is not set -# end of Virtual GPIO drivers - -# CONFIG_W1 is not set -CONFIG_POWER_RESET=y -# CONFIG_POWER_RESET_GPIO is not set -# CONFIG_POWER_RESET_GPIO_RESTART is not set -# CONFIG_POWER_RESET_LTC2952 is not set -# CONFIG_POWER_RESET_REGULATOR is not set -# CONFIG_POWER_RESET_RESTART is not set -CONFIG_POWER_RESET_SYSCON=y -CONFIG_POWER_RESET_SYSCON_POWEROFF=y -# CONFIG_SYSCON_REBOOT_MODE is not set -# CONFIG_NVMEM_REBOOT_MODE is not set -CONFIG_POWER_SUPPLY=y -# CONFIG_POWER_SUPPLY_DEBUG is not set -CONFIG_POWER_SUPPLY_HWMON=y -# CONFIG_GENERIC_ADC_BATTERY is not set -# CONFIG_IP5XXX_POWER is not set -# CONFIG_TEST_POWER is not set -# CONFIG_CHARGER_ADP5061 is not set -# CONFIG_BATTERY_CW2015 is not set -# CONFIG_BATTERY_DS2780 is not set -# CONFIG_BATTERY_DS2781 is not set -# CONFIG_BATTERY_DS2782 is not set -# CONFIG_BATTERY_SAMSUNG_SDI is not set -# CONFIG_BATTERY_SBS is not set -# CONFIG_CHARGER_SBS is not set -# CONFIG_MANAGER_SBS is not set -# CONFIG_BATTERY_BQ27XXX is not set -# CONFIG_BATTERY_MAX17040 is not set -# CONFIG_BATTERY_MAX17042 is not set -# CONFIG_CHARGER_ISP1704 is not set -# CONFIG_CHARGER_MAX8903 is not set -# CONFIG_CHARGER_LP8727 is not set -# CONFIG_CHARGER_GPIO is not set -# CONFIG_CHARGER_MANAGER is not set -# CONFIG_CHARGER_LT3651 is not set -# CONFIG_CHARGER_LTC4162L is not set -# CONFIG_CHARGER_DETECTOR_MAX14656 is not set -# CONFIG_CHARGER_MAX77976 is not set -# CONFIG_CHARGER_BQ2415X is not set -# CONFIG_CHARGER_BQ24190 is not set -# CONFIG_CHARGER_BQ24257 is not set -# CONFIG_CHARGER_BQ24735 is not set -# CONFIG_CHARGER_BQ2515X is not set -# CONFIG_CHARGER_BQ25890 is not set -# CONFIG_CHARGER_BQ25980 is not set -# CONFIG_CHARGER_BQ256XX is not set -# CONFIG_CHARGER_SMB347 is not set -# CONFIG_BATTERY_GAUGE_LTC2941 is not set -# CONFIG_BATTERY_GOLDFISH is not set -# CONFIG_BATTERY_RT5033 is not set -# CONFIG_CHARGER_RT9455 is not set -# CONFIG_CHARGER_RT9467 is not set -# CONFIG_CHARGER_RT9471 is not set -# CONFIG_CHARGER_UCS1002 is not set -# CONFIG_CHARGER_BD99954 is not set -# CONFIG_BATTERY_UG3105 is not set -CONFIG_HWMON=y -# CONFIG_HWMON_DEBUG_CHIP is not set - -# -# Native drivers -# -# CONFIG_SENSORS_AD7314 is not set -# CONFIG_SENSORS_AD7414 is not set -# CONFIG_SENSORS_AD7418 is not set -# CONFIG_SENSORS_ADM1021 is not set -# CONFIG_SENSORS_ADM1025 is not set -# CONFIG_SENSORS_ADM1026 is not set -# CONFIG_SENSORS_ADM1029 is not set -# CONFIG_SENSORS_ADM1031 is not set -# CONFIG_SENSORS_ADM1177 is not set -# CONFIG_SENSORS_ADM9240 is not set -# CONFIG_SENSORS_ADT7310 is not set -# CONFIG_SENSORS_ADT7410 is not set -# CONFIG_SENSORS_ADT7411 is not set -# CONFIG_SENSORS_ADT7462 is not set -# CONFIG_SENSORS_ADT7470 is not set -# CONFIG_SENSORS_ADT7475 is not set -# CONFIG_SENSORS_AHT10 is not set -# CONFIG_SENSORS_AQUACOMPUTER_D5NEXT is not set -# CONFIG_SENSORS_AS370 is not set -# CONFIG_SENSORS_ASC7621 is not set -# CONFIG_SENSORS_AXI_FAN_CONTROL is not set -# CONFIG_SENSORS_ATXP1 is not set -# CONFIG_SENSORS_CORSAIR_CPRO is not set -# CONFIG_SENSORS_CORSAIR_PSU is not set -# CONFIG_SENSORS_DRIVETEMP is not set -# CONFIG_SENSORS_DS620 is not set -# CONFIG_SENSORS_DS1621 is not set -# CONFIG_SENSORS_I5K_AMB is not set -# CONFIG_SENSORS_F71805F is not set -# CONFIG_SENSORS_F71882FG is not set -# CONFIG_SENSORS_F75375S is not set -# CONFIG_SENSORS_FTSTEUTATES is not set -# CONFIG_SENSORS_GL518SM is not set -# CONFIG_SENSORS_GL520SM is not set -# CONFIG_SENSORS_G760A is not set -# CONFIG_SENSORS_G762 is not set -# CONFIG_SENSORS_GPIO_FAN is not set -# CONFIG_SENSORS_HIH6130 is not set -# CONFIG_SENSORS_IIO_HWMON is not set -# CONFIG_SENSORS_IT87 is not set -# CONFIG_SENSORS_JC42 is not set -# CONFIG_SENSORS_POWR1220 is not set -# CONFIG_SENSORS_LINEAGE is not set -# CONFIG_SENSORS_LTC2945 is not set -# CONFIG_SENSORS_LTC2947_I2C is not set -# CONFIG_SENSORS_LTC2947_SPI is not set -# CONFIG_SENSORS_LTC2990 is not set -# CONFIG_SENSORS_LTC2992 is not set -# CONFIG_SENSORS_LTC4151 is not set -# CONFIG_SENSORS_LTC4215 is not set -# CONFIG_SENSORS_LTC4222 is not set -# CONFIG_SENSORS_LTC4245 is not set -# CONFIG_SENSORS_LTC4260 is not set -# CONFIG_SENSORS_LTC4261 is not set -# CONFIG_SENSORS_MAX1111 is not set -# CONFIG_SENSORS_MAX127 is not set -# CONFIG_SENSORS_MAX16065 is not set -# CONFIG_SENSORS_MAX1619 is not set -# CONFIG_SENSORS_MAX1668 is not set -# CONFIG_SENSORS_MAX197 is not set -# CONFIG_SENSORS_MAX31722 is not set -# CONFIG_SENSORS_MAX31730 is not set -# CONFIG_SENSORS_MAX31760 is not set -# CONFIG_SENSORS_MAX6620 is not set -# CONFIG_SENSORS_MAX6621 is not set -# CONFIG_SENSORS_MAX6639 is not set -# CONFIG_SENSORS_MAX6642 is not set -# CONFIG_SENSORS_MAX6650 is not set -# CONFIG_SENSORS_MAX6697 is not set -# CONFIG_SENSORS_MAX31790 is not set -# CONFIG_SENSORS_MC34VR500 is not set -# CONFIG_SENSORS_MCP3021 is not set -# CONFIG_SENSORS_TC654 is not set -# CONFIG_SENSORS_TPS23861 is not set -# CONFIG_SENSORS_MR75203 is not set -# CONFIG_SENSORS_ADCXX is not set -# CONFIG_SENSORS_LM63 is not set -# CONFIG_SENSORS_LM70 is not set -# CONFIG_SENSORS_LM73 is not set -# CONFIG_SENSORS_LM75 is not set -# CONFIG_SENSORS_LM77 is not set -# CONFIG_SENSORS_LM78 is not set -# CONFIG_SENSORS_LM80 is not set -# CONFIG_SENSORS_LM83 is not set -# CONFIG_SENSORS_LM85 is not set -# CONFIG_SENSORS_LM87 is not set -# CONFIG_SENSORS_LM90 is not set -# CONFIG_SENSORS_LM92 is not set -# CONFIG_SENSORS_LM93 is not set -# CONFIG_SENSORS_LM95234 is not set -# CONFIG_SENSORS_LM95241 is not set -# CONFIG_SENSORS_LM95245 is not set -# CONFIG_SENSORS_PC87360 is not set -# CONFIG_SENSORS_PC87427 is not set -# CONFIG_SENSORS_NTC_THERMISTOR is not set -# CONFIG_SENSORS_NCT6683 is not set -# CONFIG_SENSORS_NCT6775_I2C is not set -# CONFIG_SENSORS_NCT7802 is not set -# CONFIG_SENSORS_NCT7904 is not set -# CONFIG_SENSORS_NPCM7XX is not set -# CONFIG_SENSORS_NZXT_KRAKEN2 is not set -# CONFIG_SENSORS_NZXT_SMART2 is not set -# CONFIG_SENSORS_OCC_P8_I2C is not set -# CONFIG_SENSORS_PCF8591 is not set -# CONFIG_PMBUS is not set -# CONFIG_SENSORS_SBTSI is not set -# CONFIG_SENSORS_SBRMI is not set -# CONFIG_SENSORS_SHT15 is not set -# CONFIG_SENSORS_SHT21 is not set -# CONFIG_SENSORS_SHT3x is not set -# CONFIG_SENSORS_SHT4x is not set -# CONFIG_SENSORS_SHTC1 is not set -# CONFIG_SENSORS_SIS5595 is not set -# CONFIG_SENSORS_DME1737 is not set -# CONFIG_SENSORS_EMC1403 is not set -# CONFIG_SENSORS_EMC2103 is not set -# CONFIG_SENSORS_EMC2305 is not set -# CONFIG_SENSORS_EMC6W201 is not set -# CONFIG_SENSORS_SMSC47M1 is not set -# CONFIG_SENSORS_SMSC47M192 is not set -# CONFIG_SENSORS_SMSC47B397 is not set -# CONFIG_SENSORS_SCH5627 is not set -# CONFIG_SENSORS_SCH5636 is not set -# CONFIG_SENSORS_STTS751 is not set -# CONFIG_SENSORS_SFCTEMP is not set -# CONFIG_SENSORS_SMM665 is not set -# CONFIG_SENSORS_ADC128D818 is not set -# CONFIG_SENSORS_ADS7828 is not set -# CONFIG_SENSORS_ADS7871 is not set -# CONFIG_SENSORS_AMC6821 is not set -# CONFIG_SENSORS_INA209 is not set -# CONFIG_SENSORS_INA2XX is not set -# CONFIG_SENSORS_INA238 is not set -# CONFIG_SENSORS_INA3221 is not set -# CONFIG_SENSORS_TC74 is not set -# CONFIG_SENSORS_THMC50 is not set -# CONFIG_SENSORS_TMP102 is not set -# CONFIG_SENSORS_TMP103 is not set -# CONFIG_SENSORS_TMP108 is not set -# CONFIG_SENSORS_TMP401 is not set -# CONFIG_SENSORS_TMP421 is not set -# CONFIG_SENSORS_TMP464 is not set -# CONFIG_SENSORS_TMP513 is not set -# CONFIG_SENSORS_VIA686A is not set -# CONFIG_SENSORS_VT1211 is not set -# CONFIG_SENSORS_VT8231 is not set -# CONFIG_SENSORS_W83773G is not set -# CONFIG_SENSORS_W83781D is not set -# CONFIG_SENSORS_W83791D is not set -# CONFIG_SENSORS_W83792D is not set -# CONFIG_SENSORS_W83793 is not set -# CONFIG_SENSORS_W83795 is not set -# CONFIG_SENSORS_W83L785TS is not set -# CONFIG_SENSORS_W83L786NG is not set -# CONFIG_SENSORS_W83627HF is not set -# CONFIG_SENSORS_W83627EHF is not set -# CONFIG_THERMAL is not set -CONFIG_WATCHDOG=y -CONFIG_WATCHDOG_CORE=y -# CONFIG_WATCHDOG_NOWAYOUT is not set -CONFIG_WATCHDOG_HANDLE_BOOT_ENABLED=y -CONFIG_WATCHDOG_OPEN_TIMEOUT=0 -# CONFIG_WATCHDOG_SYSFS is not set -# CONFIG_WATCHDOG_HRTIMER_PRETIMEOUT is not set - -# -# Watchdog Pretimeout Governors -# -# CONFIG_WATCHDOG_PRETIMEOUT_GOV is not set - -# -# Watchdog Device Drivers -# -# CONFIG_SOFT_WATCHDOG is not set -# CONFIG_GPIO_WATCHDOG is not set -# CONFIG_XILINX_WATCHDOG is not set -# CONFIG_ZIIRAVE_WATCHDOG is not set -# CONFIG_CADENCE_WATCHDOG is not set -# CONFIG_DW_WATCHDOG is not set -CONFIG_SUNXI_WATCHDOG=y -# CONFIG_MAX63XX_WATCHDOG is not set -# CONFIG_RENESAS_WDT is not set -# CONFIG_RENESAS_RZAWDT is not set -# CONFIG_RENESAS_RZN1WDT is not set -# CONFIG_RENESAS_RZG2LWDT is not set -# CONFIG_ALIM7101_WDT is not set -# CONFIG_I6300ESB_WDT is not set -# CONFIG_MEN_A21_WDT is not set -CONFIG_STARFIVE_WATCHDOG=y - -# -# PCI-based Watchdog Cards -# -# CONFIG_PCIPCWATCHDOG is not set -# CONFIG_WDTPCI is not set - -# -# USB-based Watchdog Cards -# -# CONFIG_USBPCWATCHDOG is not set -CONFIG_SSB_POSSIBLE=y -# CONFIG_SSB is not set -CONFIG_BCMA_POSSIBLE=y -# CONFIG_BCMA is not set - -# -# Multifunction device drivers -# -# CONFIG_MFD_ACT8945A is not set -# CONFIG_MFD_SUN4I_GPADC is not set -# CONFIG_MFD_AS3711 is not set -# CONFIG_MFD_SMPRO is not set -# CONFIG_MFD_AS3722 is not set -# CONFIG_PMIC_ADP5520 is not set -# CONFIG_MFD_AAT2870_CORE is not set -# CONFIG_MFD_ATMEL_FLEXCOM is not set -# CONFIG_MFD_ATMEL_HLCDC is not set -# CONFIG_MFD_BCM590XX is not set -# CONFIG_MFD_BD9571MWV is not set -# CONFIG_MFD_AXP20X_I2C is not set -# CONFIG_MFD_MADERA is not set -# CONFIG_MFD_MAX597X is not set -# CONFIG_PMIC_DA903X is not set -# CONFIG_MFD_DA9052_SPI is not set -# CONFIG_MFD_DA9052_I2C is not set -# CONFIG_MFD_DA9055 is not set -# CONFIG_MFD_DA9062 is not set -# CONFIG_MFD_DA9063 is not set -# CONFIG_MFD_DA9150 is not set -# CONFIG_MFD_DLN2 is not set -# CONFIG_MFD_GATEWORKS_GSC is not set -# CONFIG_MFD_MC13XXX_SPI is not set -# CONFIG_MFD_MC13XXX_I2C is not set -# CONFIG_MFD_MP2629 is not set -# CONFIG_MFD_HI6421_PMIC is not set -# CONFIG_LPC_ICH is not set -# CONFIG_LPC_SCH is not set -# CONFIG_MFD_IQS62X is not set -# CONFIG_MFD_JANZ_CMODIO is not set -# CONFIG_MFD_KEMPLD is not set -# CONFIG_MFD_88PM800 is not set -# CONFIG_MFD_88PM805 is not set -# CONFIG_MFD_88PM860X is not set -# CONFIG_MFD_MAX14577 is not set -# CONFIG_MFD_MAX77620 is not set -# CONFIG_MFD_MAX77650 is not set -# CONFIG_MFD_MAX77686 is not set -# CONFIG_MFD_MAX77693 is not set -# CONFIG_MFD_MAX77714 is not set -# CONFIG_MFD_MAX77843 is not set -# CONFIG_MFD_MAX8907 is not set -# CONFIG_MFD_MAX8925 is not set -# CONFIG_MFD_MAX8997 is not set -# CONFIG_MFD_MAX8998 is not set -# CONFIG_MFD_MT6360 is not set -# CONFIG_MFD_MT6370 is not set -# CONFIG_MFD_MT6397 is not set -# CONFIG_MFD_MENF21BMC is not set -# CONFIG_MFD_OCELOT is not set -# CONFIG_EZX_PCAP is not set -# CONFIG_MFD_CPCAP is not set -# CONFIG_MFD_VIPERBOARD is not set -# CONFIG_MFD_NTXEC is not set -# CONFIG_MFD_RETU is not set -# CONFIG_MFD_PCF50633 is not set -# CONFIG_MFD_SY7636A is not set -# CONFIG_MFD_RDC321X is not set -# CONFIG_MFD_RT4831 is not set -# CONFIG_MFD_RT5033 is not set -# CONFIG_MFD_RT5120 is not set -# CONFIG_MFD_RC5T583 is not set -# CONFIG_MFD_RK808 is not set -# CONFIG_MFD_RN5T618 is not set -# CONFIG_MFD_SEC_CORE is not set -# CONFIG_MFD_SI476X_CORE is not set -# CONFIG_MFD_SM501 is not set -# CONFIG_MFD_SKY81452 is not set -# CONFIG_RZ_MTU3 is not set -# CONFIG_MFD_STMPE is not set -# CONFIG_MFD_SUN6I_PRCM is not set -CONFIG_MFD_SYSCON=y -# CONFIG_MFD_TI_AM335X_TSCADC is not set -# CONFIG_MFD_LP3943 is not set -# CONFIG_MFD_LP8788 is not set -# CONFIG_MFD_TI_LMU is not set -# CONFIG_MFD_PALMAS is not set -# CONFIG_TPS6105X is not set -# CONFIG_TPS65010 is not set -# CONFIG_TPS6507X is not set -# CONFIG_MFD_TPS65086 is not set -# CONFIG_MFD_TPS65090 is not set -# CONFIG_MFD_TPS65217 is not set -# CONFIG_MFD_TI_LP873X is not set -# CONFIG_MFD_TI_LP87565 is not set -# CONFIG_MFD_TPS65218 is not set -# CONFIG_MFD_TPS65219 is not set -# CONFIG_MFD_TPS6586X is not set -# CONFIG_MFD_TPS65910 is not set -# CONFIG_MFD_TPS65912_I2C is not set -# CONFIG_MFD_TPS65912_SPI is not set -# CONFIG_TWL4030_CORE is not set -# CONFIG_TWL6040_CORE is not set -# CONFIG_MFD_WL1273_CORE is not set -# CONFIG_MFD_LM3533 is not set -# CONFIG_MFD_TC3589X is not set -# CONFIG_MFD_TQMX86 is not set -# CONFIG_MFD_VX855 is not set -# CONFIG_MFD_LOCHNAGAR is not set -# CONFIG_MFD_ARIZONA_I2C is not set -# CONFIG_MFD_ARIZONA_SPI is not set -# CONFIG_MFD_WM8400 is not set -# CONFIG_MFD_WM831X_I2C is not set -# CONFIG_MFD_WM831X_SPI is not set -# CONFIG_MFD_WM8350_I2C is not set -# CONFIG_MFD_WM8994 is not set -# CONFIG_MFD_ROHM_BD718XX is not set -# CONFIG_MFD_ROHM_BD71828 is not set -# CONFIG_MFD_ROHM_BD957XMUF is not set -# CONFIG_MFD_STPMIC1 is not set -# CONFIG_MFD_STMFX is not set -# CONFIG_MFD_ATC260X_I2C is not set -# CONFIG_MFD_QCOM_PM8008 is not set -# CONFIG_MFD_INTEL_M10_BMC_SPI is not set -# CONFIG_MFD_RSMU_I2C is not set -# CONFIG_MFD_RSMU_SPI is not set -# end of Multifunction device drivers - -CONFIG_REGULATOR=y -# CONFIG_REGULATOR_DEBUG is not set -CONFIG_REGULATOR_FIXED_VOLTAGE=y -# CONFIG_REGULATOR_VIRTUAL_CONSUMER is not set -# CONFIG_REGULATOR_USERSPACE_CONSUMER is not set -# CONFIG_REGULATOR_88PG86X is not set -# CONFIG_REGULATOR_ACT8865 is not set -# CONFIG_REGULATOR_AD5398 is not set -# CONFIG_REGULATOR_DA9121 is not set -# CONFIG_REGULATOR_DA9210 is not set -# CONFIG_REGULATOR_DA9211 is not set -# CONFIG_REGULATOR_FAN53555 is not set -# CONFIG_REGULATOR_FAN53880 is not set -# CONFIG_REGULATOR_GPIO is not set -# CONFIG_REGULATOR_ISL9305 is not set -# CONFIG_REGULATOR_ISL6271A is not set -# CONFIG_REGULATOR_LP3971 is not set -# CONFIG_REGULATOR_LP3972 is not set -# CONFIG_REGULATOR_LP872X is not set -# CONFIG_REGULATOR_LP8755 is not set -# CONFIG_REGULATOR_LTC3589 is not set -# CONFIG_REGULATOR_LTC3676 is not set -# CONFIG_REGULATOR_MAX1586 is not set -# CONFIG_REGULATOR_MAX8649 is not set -# CONFIG_REGULATOR_MAX8660 is not set -# CONFIG_REGULATOR_MAX8893 is not set -# CONFIG_REGULATOR_MAX8952 is not set -# CONFIG_REGULATOR_MAX20086 is not set -# CONFIG_REGULATOR_MAX20411 is not set -# CONFIG_REGULATOR_MAX77826 is not set -# CONFIG_REGULATOR_MCP16502 is not set -# CONFIG_REGULATOR_MP5416 is not set -# CONFIG_REGULATOR_MP8859 is not set -# CONFIG_REGULATOR_MP886X is not set -# CONFIG_REGULATOR_MPQ7920 is not set -# CONFIG_REGULATOR_MT6311 is not set -# CONFIG_REGULATOR_PCA9450 is not set -# CONFIG_REGULATOR_PF8X00 is not set -# CONFIG_REGULATOR_PFUZE100 is not set -# CONFIG_REGULATOR_PV88060 is not set -# CONFIG_REGULATOR_PV88080 is not set -# CONFIG_REGULATOR_PV88090 is not set -# CONFIG_REGULATOR_RASPBERRYPI_TOUCHSCREEN_ATTINY is not set -# CONFIG_REGULATOR_RT4801 is not set -# CONFIG_REGULATOR_RT4803 is not set -# CONFIG_REGULATOR_RT5190A is not set -# CONFIG_REGULATOR_RT5739 is not set -# CONFIG_REGULATOR_RT5759 is not set -# CONFIG_REGULATOR_RT6160 is not set -# CONFIG_REGULATOR_RT6190 is not set -# CONFIG_REGULATOR_RT6245 is not set -# CONFIG_REGULATOR_RTQ2134 is not set -# CONFIG_REGULATOR_RTMV20 is not set -# CONFIG_REGULATOR_RTQ6752 is not set -# CONFIG_REGULATOR_SLG51000 is not set -# CONFIG_REGULATOR_SY8106A is not set -# CONFIG_REGULATOR_SY8824X is not set -# CONFIG_REGULATOR_SY8827N is not set -# CONFIG_REGULATOR_TPS51632 is not set -# CONFIG_REGULATOR_TPS62360 is not set -# CONFIG_REGULATOR_TPS6286X is not set -# CONFIG_REGULATOR_TPS65023 is not set -# CONFIG_REGULATOR_TPS6507X is not set -# CONFIG_REGULATOR_TPS65132 is not set -# CONFIG_REGULATOR_TPS6524X is not set -# CONFIG_REGULATOR_VCTRL is not set -# CONFIG_RC_CORE is not set - -# -# CEC support -# -# CONFIG_MEDIA_CEC_SUPPORT is not set -# end of CEC support - -CONFIG_MEDIA_SUPPORT=m -CONFIG_MEDIA_SUPPORT_FILTER=y -CONFIG_MEDIA_SUBDRV_AUTOSELECT=y - -# -# Media device types -# -CONFIG_MEDIA_CAMERA_SUPPORT=y -# CONFIG_MEDIA_ANALOG_TV_SUPPORT is not set -# CONFIG_MEDIA_DIGITAL_TV_SUPPORT is not set -# CONFIG_MEDIA_RADIO_SUPPORT is not set -# CONFIG_MEDIA_SDR_SUPPORT is not set -# CONFIG_MEDIA_PLATFORM_SUPPORT is not set -# CONFIG_MEDIA_TEST_SUPPORT is not set -# end of Media device types - -CONFIG_VIDEO_DEV=m -CONFIG_MEDIA_CONTROLLER=y - -# -# Video4Linux options -# -CONFIG_VIDEO_V4L2_I2C=y -CONFIG_VIDEO_V4L2_SUBDEV_API=y -# CONFIG_VIDEO_ADV_DEBUG is not set -# CONFIG_VIDEO_FIXED_MINOR_RANGES is not set -CONFIG_V4L2_FWNODE=m -CONFIG_V4L2_ASYNC=m -# end of Video4Linux options - -# -# Media controller options -# -# end of Media controller options - -# -# Media drivers -# - -# -# Drivers filtered as selected at 'Filter media drivers' -# - -# -# Media drivers -# -# CONFIG_MEDIA_USB_SUPPORT is not set -# CONFIG_MEDIA_PCI_SUPPORT is not set -CONFIG_UVC_COMMON=m -CONFIG_VIDEOBUF2_CORE=m -CONFIG_VIDEOBUF2_V4L2=m -CONFIG_VIDEOBUF2_MEMOPS=m -CONFIG_VIDEOBUF2_VMALLOC=m -CONFIG_VIDEOBUF2_DMA_SG=m -# end of Media drivers - -# -# Media ancillary drivers -# - -# -# Camera sensor devices -# -# CONFIG_VIDEO_AR0521 is not set -# CONFIG_VIDEO_HI556 is not set -# CONFIG_VIDEO_HI846 is not set -# CONFIG_VIDEO_HI847 is not set -# CONFIG_VIDEO_IMX208 is not set -# CONFIG_VIDEO_IMX214 is not set -CONFIG_VIDEO_IMX219=m -# CONFIG_VIDEO_IMX258 is not set -# CONFIG_VIDEO_IMX274 is not set -# CONFIG_VIDEO_IMX290 is not set -# CONFIG_VIDEO_IMX296 is not set -# CONFIG_VIDEO_IMX319 is not set -# CONFIG_VIDEO_IMX334 is not set -# CONFIG_VIDEO_IMX335 is not set -# CONFIG_VIDEO_IMX355 is not set -# CONFIG_VIDEO_IMX412 is not set -# CONFIG_VIDEO_IMX415 is not set -# CONFIG_VIDEO_MT9M001 is not set -# CONFIG_VIDEO_MT9M111 is not set -# CONFIG_VIDEO_MT9P031 is not set -# CONFIG_VIDEO_MT9T112 is not set -# CONFIG_VIDEO_MT9V011 is not set -# CONFIG_VIDEO_MT9V032 is not set -# CONFIG_VIDEO_MT9V111 is not set -# CONFIG_VIDEO_OG01A1B is not set -# CONFIG_VIDEO_OV02A10 is not set -# CONFIG_VIDEO_OV08D10 is not set -# CONFIG_VIDEO_OV08X40 is not set -# CONFIG_VIDEO_OV13858 is not set -# CONFIG_VIDEO_OV13B10 is not set -# CONFIG_VIDEO_OV2640 is not set -# CONFIG_VIDEO_OV2659 is not set -# CONFIG_VIDEO_OV2680 is not set -# CONFIG_VIDEO_OV2685 is not set -# CONFIG_VIDEO_OV4689 is not set -# CONFIG_VIDEO_OV5640 is not set -# CONFIG_VIDEO_OV5645 is not set -# CONFIG_VIDEO_OV5647 is not set -# CONFIG_VIDEO_OV5648 is not set -# CONFIG_VIDEO_OV5670 is not set -# CONFIG_VIDEO_OV5675 is not set -# CONFIG_VIDEO_OV5693 is not set -# CONFIG_VIDEO_OV5695 is not set -# CONFIG_VIDEO_OV6650 is not set -# CONFIG_VIDEO_OV7251 is not set -# CONFIG_VIDEO_OV7640 is not set -# CONFIG_VIDEO_OV7670 is not set -# CONFIG_VIDEO_OV772X is not set -# CONFIG_VIDEO_OV7740 is not set -# CONFIG_VIDEO_OV8856 is not set -# CONFIG_VIDEO_OV8858 is not set -# CONFIG_VIDEO_OV8865 is not set -# CONFIG_VIDEO_OV9282 is not set -# CONFIG_VIDEO_OV9640 is not set -# CONFIG_VIDEO_OV9650 is not set -# CONFIG_VIDEO_RDACM20 is not set -# CONFIG_VIDEO_RDACM21 is not set -# CONFIG_VIDEO_RJ54N1 is not set -# CONFIG_VIDEO_S5C73M3 is not set -# CONFIG_VIDEO_S5K5BAF is not set -# CONFIG_VIDEO_S5K6A3 is not set -# CONFIG_VIDEO_ST_VGXY61 is not set -# CONFIG_VIDEO_CCS is not set -# CONFIG_VIDEO_ET8EK8 is not set -# end of Camera sensor devices - -# -# Lens drivers -# -# CONFIG_VIDEO_AD5820 is not set -# CONFIG_VIDEO_AK7375 is not set -# CONFIG_VIDEO_DW9714 is not set -# CONFIG_VIDEO_DW9768 is not set -# CONFIG_VIDEO_DW9807_VCM is not set -# end of Lens drivers - -# -# Flash devices -# -# CONFIG_VIDEO_ADP1653 is not set -# CONFIG_VIDEO_LM3560 is not set -# CONFIG_VIDEO_LM3646 is not set -# end of Flash devices - -# -# Audio decoders, processors and mixers -# -# CONFIG_VIDEO_CS3308 is not set -# CONFIG_VIDEO_CS5345 is not set -# CONFIG_VIDEO_CS53L32A is not set -# CONFIG_VIDEO_MSP3400 is not set -# CONFIG_VIDEO_SONY_BTF_MPX is not set -# CONFIG_VIDEO_TDA7432 is not set -# CONFIG_VIDEO_TDA9840 is not set -# CONFIG_VIDEO_TEA6415C is not set -# CONFIG_VIDEO_TEA6420 is not set -# CONFIG_VIDEO_TLV320AIC23B is not set -# CONFIG_VIDEO_TVAUDIO is not set -# CONFIG_VIDEO_UDA1342 is not set -# CONFIG_VIDEO_VP27SMPX is not set -# CONFIG_VIDEO_WM8739 is not set -# CONFIG_VIDEO_WM8775 is not set -# end of Audio decoders, processors and mixers - -# -# RDS decoders -# -# CONFIG_VIDEO_SAA6588 is not set -# end of RDS decoders - -# -# Video decoders -# -# CONFIG_VIDEO_ADV7180 is not set -# CONFIG_VIDEO_ADV7183 is not set -# CONFIG_VIDEO_ADV748X is not set -# CONFIG_VIDEO_ADV7604 is not set -# CONFIG_VIDEO_ADV7842 is not set -# CONFIG_VIDEO_BT819 is not set -# CONFIG_VIDEO_BT856 is not set -# CONFIG_VIDEO_BT866 is not set -# CONFIG_VIDEO_ISL7998X is not set -# CONFIG_VIDEO_KS0127 is not set -# CONFIG_VIDEO_MAX9286 is not set -# CONFIG_VIDEO_ML86V7667 is not set -# CONFIG_VIDEO_SAA7110 is not set -# CONFIG_VIDEO_SAA711X is not set -# CONFIG_VIDEO_TC358743 is not set -# CONFIG_VIDEO_TC358746 is not set -# CONFIG_VIDEO_TVP514X is not set -# CONFIG_VIDEO_TVP5150 is not set -# CONFIG_VIDEO_TVP7002 is not set -# CONFIG_VIDEO_TW2804 is not set -# CONFIG_VIDEO_TW9903 is not set -# CONFIG_VIDEO_TW9906 is not set -# CONFIG_VIDEO_TW9910 is not set -# CONFIG_VIDEO_VPX3220 is not set - -# -# Video and audio decoders -# -# CONFIG_VIDEO_SAA717X is not set -# CONFIG_VIDEO_CX25840 is not set -# end of Video decoders - -# -# Video encoders -# -# CONFIG_VIDEO_ADV7170 is not set -# CONFIG_VIDEO_ADV7175 is not set -# CONFIG_VIDEO_ADV7343 is not set -# CONFIG_VIDEO_ADV7393 is not set -# CONFIG_VIDEO_ADV7511 is not set -# CONFIG_VIDEO_AK881X is not set -# CONFIG_VIDEO_SAA7127 is not set -# CONFIG_VIDEO_SAA7185 is not set -# CONFIG_VIDEO_THS8200 is not set -# end of Video encoders - -# -# Video improvement chips -# -# CONFIG_VIDEO_UPD64031A is not set -# CONFIG_VIDEO_UPD64083 is not set -# end of Video improvement chips - -# -# Audio/Video compression chips -# -# CONFIG_VIDEO_SAA6752HS is not set -# end of Audio/Video compression chips - -# -# SDR tuner chips -# -# end of SDR tuner chips - -# -# Miscellaneous helper chips -# -# CONFIG_VIDEO_I2C is not set -# CONFIG_VIDEO_M52790 is not set -# CONFIG_VIDEO_ST_MIPID02 is not set -# CONFIG_VIDEO_THS7303 is not set -# end of Miscellaneous helper chips - -# -# Media SPI Adapters -# -# CONFIG_VIDEO_GS1662 is not set -# end of Media SPI Adapters -# end of Media ancillary drivers - -# -# Graphics support -# -CONFIG_APERTURE_HELPERS=y -CONFIG_VIDEO_CMDLINE=y -# CONFIG_DRM is not set -# CONFIG_DRM_DEBUG_MODESET_LOCK is not set - -# -# ARM devices -# -# end of ARM devices - -# -# Frame buffer Devices -# -CONFIG_FB_NOTIFY=y -CONFIG_FB=y -# CONFIG_FIRMWARE_EDID is not set -# CONFIG_FB_FOREIGN_ENDIAN is not set -# CONFIG_FB_MODE_HELPERS is not set -# CONFIG_FB_TILEBLITTING is not set - -# -# Frame buffer hardware drivers -# -# CONFIG_FB_CIRRUS is not set -# CONFIG_FB_PM2 is not set -# CONFIG_FB_CYBER2000 is not set -# CONFIG_FB_ASILIANT is not set -# CONFIG_FB_IMSTT is not set -# CONFIG_FB_EFI is not set -# CONFIG_FB_OPENCORES is not set -# CONFIG_FB_S1D13XXX is not set -# CONFIG_FB_NVIDIA is not set -# CONFIG_FB_RIVA is not set -# CONFIG_FB_I740 is not set -# CONFIG_FB_MATROX is not set -# CONFIG_FB_RADEON is not set -# CONFIG_FB_ATY128 is not set -# CONFIG_FB_ATY is not set -# CONFIG_FB_S3 is not set -# CONFIG_FB_SAVAGE is not set -# CONFIG_FB_SIS is not set -# CONFIG_FB_NEOMAGIC is not set -# CONFIG_FB_KYRO is not set -# CONFIG_FB_3DFX is not set -# CONFIG_FB_VOODOO1 is not set -# CONFIG_FB_VT8623 is not set -# CONFIG_FB_TRIDENT is not set -# CONFIG_FB_ARK is not set -# CONFIG_FB_PM3 is not set -# CONFIG_FB_CARMINE is not set -# CONFIG_FB_SH_MOBILE_LCDC is not set -# CONFIG_FB_SMSCUFX is not set -# CONFIG_FB_UDL is not set -# CONFIG_FB_IBM_GXT4500 is not set -# CONFIG_FB_GOLDFISH is not set -# CONFIG_FB_VIRTUAL is not set -# CONFIG_FB_METRONOME is not set -# CONFIG_FB_MB862XX is not set -# CONFIG_FB_SIMPLE is not set -# CONFIG_FB_SSD1307 is not set -# CONFIG_FB_SM712 is not set -# end of Frame buffer Devices - -# -# Backlight & LCD device support -# -# CONFIG_LCD_CLASS_DEVICE is not set -CONFIG_BACKLIGHT_CLASS_DEVICE=m -# CONFIG_BACKLIGHT_KTD253 is not set -# CONFIG_BACKLIGHT_KTZ8866 is not set -# CONFIG_BACKLIGHT_QCOM_WLED is not set -# CONFIG_BACKLIGHT_ADP8860 is not set -# CONFIG_BACKLIGHT_ADP8870 is not set -# CONFIG_BACKLIGHT_LM3639 is not set -# CONFIG_BACKLIGHT_GPIO is not set -# CONFIG_BACKLIGHT_LV5207LP is not set -# CONFIG_BACKLIGHT_BD6107 is not set -# CONFIG_BACKLIGHT_ARCXCNN is not set -# end of Backlight & LCD device support - -# -# Console display driver support -# -CONFIG_VGA_CONSOLE=y -CONFIG_DUMMY_CONSOLE=y -CONFIG_DUMMY_CONSOLE_COLUMNS=80 -CONFIG_DUMMY_CONSOLE_ROWS=25 -CONFIG_FRAMEBUFFER_CONSOLE=y -# CONFIG_FRAMEBUFFER_CONSOLE_LEGACY_ACCELERATION is not set -CONFIG_FRAMEBUFFER_CONSOLE_DETECT_PRIMARY=y -# CONFIG_FRAMEBUFFER_CONSOLE_ROTATION is not set -# CONFIG_FRAMEBUFFER_CONSOLE_DEFERRED_TAKEOVER is not set -# end of Console display driver support - -# CONFIG_LOGO is not set -# end of Graphics support - -# CONFIG_SOUND is not set -CONFIG_HID_SUPPORT=y -CONFIG_HID=y -# CONFIG_HID_BATTERY_STRENGTH is not set -# CONFIG_HIDRAW is not set -# CONFIG_UHID is not set -CONFIG_HID_GENERIC=y - -# -# Special HID drivers -# -# CONFIG_HID_A4TECH is not set -# CONFIG_HID_ACCUTOUCH is not set -# CONFIG_HID_ACRUX is not set -# CONFIG_HID_APPLEIR is not set -# CONFIG_HID_AUREAL is not set -# CONFIG_HID_BELKIN is not set -# CONFIG_HID_BETOP_FF is not set -# CONFIG_HID_CHERRY is not set -# CONFIG_HID_CHICONY is not set -# CONFIG_HID_COUGAR is not set -# CONFIG_HID_MACALLY is not set -# CONFIG_HID_CMEDIA is not set -# CONFIG_HID_CREATIVE_SB0540 is not set -# CONFIG_HID_CYPRESS is not set -# CONFIG_HID_DRAGONRISE is not set -# CONFIG_HID_EMS_FF is not set -# CONFIG_HID_ELECOM is not set -# CONFIG_HID_ELO is not set -# CONFIG_HID_EVISION is not set -# CONFIG_HID_EZKEY is not set -# CONFIG_HID_GEMBIRD is not set -# CONFIG_HID_GFRM is not set -# CONFIG_HID_GLORIOUS is not set -# CONFIG_HID_HOLTEK is not set -# CONFIG_HID_VIVALDI is not set -# CONFIG_HID_KEYTOUCH is not set -# CONFIG_HID_KYE is not set -# CONFIG_HID_UCLOGIC is not set -# CONFIG_HID_WALTOP is not set -# CONFIG_HID_VIEWSONIC is not set -# CONFIG_HID_VRC2 is not set -# CONFIG_HID_XIAOMI is not set -# CONFIG_HID_GYRATION is not set -# CONFIG_HID_ICADE is not set -# CONFIG_HID_ITE is not set -# CONFIG_HID_JABRA is not set -# CONFIG_HID_TWINHAN is not set -# CONFIG_HID_KENSINGTON is not set -# CONFIG_HID_LCPOWER is not set -# CONFIG_HID_LENOVO is not set -# CONFIG_HID_LETSKETCH is not set -# CONFIG_HID_MAGICMOUSE is not set -# CONFIG_HID_MALTRON is not set -# CONFIG_HID_MAYFLASH is not set -# CONFIG_HID_MEGAWORLD_FF is not set -# CONFIG_HID_REDRAGON is not set -# CONFIG_HID_MICROSOFT is not set -# CONFIG_HID_MONTEREY is not set -# CONFIG_HID_MULTITOUCH is not set -# CONFIG_HID_NTI is not set -# CONFIG_HID_NTRIG is not set -# CONFIG_HID_ORTEK is not set -# CONFIG_HID_PANTHERLORD is not set -# CONFIG_HID_PENMOUNT is not set -# CONFIG_HID_PETALYNX is not set -# CONFIG_HID_PICOLCD is not set -# CONFIG_HID_PLANTRONICS is not set -# CONFIG_HID_PXRC is not set -# CONFIG_HID_RAZER is not set -# CONFIG_HID_PRIMAX is not set -# CONFIG_HID_RETRODE is not set -# CONFIG_HID_ROCCAT is not set -# CONFIG_HID_SAITEK is not set -# CONFIG_HID_SAMSUNG is not set -# CONFIG_HID_SEMITEK is not set -# CONFIG_HID_SIGMAMICRO is not set -# CONFIG_HID_SPEEDLINK is not set -# CONFIG_HID_STEAM is not set -# CONFIG_HID_STEELSERIES is not set -# CONFIG_HID_SUNPLUS is not set -# CONFIG_HID_RMI is not set -# CONFIG_HID_GREENASIA is not set -# CONFIG_HID_SMARTJOYPLUS is not set -# CONFIG_HID_TIVO is not set -# CONFIG_HID_TOPSEED is not set -# CONFIG_HID_TOPRE is not set -# CONFIG_HID_THRUSTMASTER is not set -# CONFIG_HID_UDRAW_PS3 is not set -# CONFIG_HID_WACOM is not set -# CONFIG_HID_XINMO is not set -# CONFIG_HID_ZEROPLUS is not set -# CONFIG_HID_ZYDACRON is not set -# CONFIG_HID_SENSOR_HUB is not set -# CONFIG_HID_ALPS is not set -# CONFIG_HID_MCP2221 is not set -# end of Special HID drivers - -# -# HID-BPF support -# -# end of HID-BPF support - -# -# USB HID support -# -CONFIG_USB_HID=y -# CONFIG_HID_PID is not set -# CONFIG_USB_HIDDEV is not set -# end of USB HID support - -CONFIG_I2C_HID=m -# CONFIG_I2C_HID_OF is not set -# CONFIG_I2C_HID_OF_ELAN is not set -# CONFIG_I2C_HID_OF_GOODIX is not set -CONFIG_USB_OHCI_LITTLE_ENDIAN=y -CONFIG_USB_SUPPORT=y -CONFIG_USB_COMMON=y -# CONFIG_USB_ULPI_BUS is not set -# CONFIG_USB_CONN_GPIO is not set -CONFIG_USB_ARCH_HAS_HCD=y -CONFIG_USB=y -CONFIG_USB_PCI=y -# CONFIG_USB_ANNOUNCE_NEW_DEVICES is not set - -# -# Miscellaneous USB options -# -CONFIG_USB_DEFAULT_PERSIST=y -# CONFIG_USB_FEW_INIT_RETRIES is not set -# CONFIG_USB_DYNAMIC_MINORS is not set -# CONFIG_USB_OTG is not set -# CONFIG_USB_OTG_PRODUCTLIST is not set -# CONFIG_USB_OTG_DISABLE_EXTERNAL_HUB is not set -CONFIG_USB_AUTOSUSPEND_DELAY=2 -# CONFIG_USB_MON is not set - -# -# USB Host Controller Drivers -# -# CONFIG_USB_C67X00_HCD is not set -CONFIG_USB_XHCI_HCD=y -# CONFIG_USB_XHCI_DBGCAP is not set -CONFIG_USB_XHCI_PCI=y -# CONFIG_USB_XHCI_PCI_RENESAS is not set -CONFIG_USB_XHCI_PLATFORM=y -CONFIG_USB_XHCI_RCAR=y -CONFIG_USB_EHCI_HCD=y -# CONFIG_USB_EHCI_ROOT_HUB_TT is not set -CONFIG_USB_EHCI_TT_NEWSCHED=y -CONFIG_USB_EHCI_PCI=y -# CONFIG_USB_EHCI_FSL is not set -CONFIG_USB_EHCI_HCD_PLATFORM=y -# CONFIG_USB_OXU210HP_HCD is not set -# CONFIG_USB_ISP116X_HCD is not set -# CONFIG_USB_MAX3421_HCD is not set -CONFIG_USB_OHCI_HCD=y -CONFIG_USB_OHCI_HCD_PCI=y -CONFIG_USB_OHCI_HCD_PLATFORM=y -# CONFIG_USB_UHCI_HCD is not set -# CONFIG_USB_SL811_HCD is not set -# CONFIG_USB_R8A66597_HCD is not set -# CONFIG_USB_HCD_TEST_MODE is not set -# CONFIG_USB_RENESAS_USBHS is not set - -# -# USB Device Class drivers -# -# CONFIG_USB_ACM is not set -# CONFIG_USB_PRINTER is not set -# CONFIG_USB_WDM is not set -# CONFIG_USB_TMC is not set - -# -# NOTE: USB_STORAGE depends on SCSI but BLK_DEV_SD may -# - -# -# also be needed; see USB_STORAGE Help for more info -# -CONFIG_USB_STORAGE=y -# CONFIG_USB_STORAGE_DEBUG is not set -# CONFIG_USB_STORAGE_REALTEK is not set -# CONFIG_USB_STORAGE_DATAFAB is not set -# CONFIG_USB_STORAGE_FREECOM is not set -# CONFIG_USB_STORAGE_ISD200 is not set -# CONFIG_USB_STORAGE_USBAT is not set -# CONFIG_USB_STORAGE_SDDR09 is not set -# CONFIG_USB_STORAGE_SDDR55 is not set -# CONFIG_USB_STORAGE_JUMPSHOT is not set -# CONFIG_USB_STORAGE_ALAUDA is not set -# CONFIG_USB_STORAGE_ONETOUCH is not set -# CONFIG_USB_STORAGE_KARMA is not set -# CONFIG_USB_STORAGE_CYPRESS_ATACB is not set -# CONFIG_USB_STORAGE_ENE_UB6250 is not set -CONFIG_USB_UAS=y - -# -# USB Imaging devices -# -# CONFIG_USB_MDC800 is not set -# CONFIG_USB_MICROTEK is not set -# CONFIG_USBIP_CORE is not set - -# -# USB dual-mode controller drivers -# -# CONFIG_USB_CDNS_SUPPORT is not set -CONFIG_USB_MUSB_HDRC=y -# CONFIG_USB_MUSB_HOST is not set -# CONFIG_USB_MUSB_GADGET is not set -CONFIG_USB_MUSB_DUAL_ROLE=y - -# -# Platform Glue Layer -# -CONFIG_USB_MUSB_SUNXI=m -CONFIG_USB_MUSB_POLARFIRE_SOC=y - -# -# MUSB DMA mode -# -# CONFIG_MUSB_PIO_ONLY is not set -# CONFIG_USB_INVENTRA_DMA is not set -# CONFIG_USB_DWC3 is not set -# CONFIG_USB_DWC2 is not set -# CONFIG_USB_CHIPIDEA is not set -# CONFIG_USB_ISP1760 is not set - -# -# USB port drivers -# -# CONFIG_USB_SERIAL is not set - -# -# USB Miscellaneous drivers -# -# CONFIG_USB_EMI62 is not set -# CONFIG_USB_EMI26 is not set -# CONFIG_USB_ADUTUX is not set -# CONFIG_USB_SEVSEG is not set -# CONFIG_USB_LEGOTOWER is not set -# CONFIG_USB_LCD is not set -# CONFIG_USB_CYPRESS_CY7C63 is not set -# CONFIG_USB_CYTHERM is not set -# CONFIG_USB_IDMOUSE is not set -# CONFIG_USB_APPLEDISPLAY is not set -# CONFIG_APPLE_MFI_FASTCHARGE is not set -# CONFIG_USB_SISUSBVGA is not set -# CONFIG_USB_LD is not set -# CONFIG_USB_TRANCEVIBRATOR is not set -# CONFIG_USB_IOWARRIOR is not set -# CONFIG_USB_TEST is not set -# CONFIG_USB_EHSET_TEST_FIXTURE is not set -# CONFIG_USB_ISIGHTFW is not set -# CONFIG_USB_YUREX is not set -# CONFIG_USB_EZUSB_FX2 is not set -# CONFIG_USB_HUB_USB251XB is not set -# CONFIG_USB_HSIC_USB3503 is not set -# CONFIG_USB_HSIC_USB4604 is not set -# CONFIG_USB_LINK_LAYER_TEST is not set -# CONFIG_USB_CHAOSKEY is not set -# CONFIG_USB_ONBOARD_HUB is not set - -# -# USB Physical Layer drivers -# -CONFIG_USB_PHY=y -CONFIG_NOP_USB_XCEIV=y -# CONFIG_USB_GPIO_VBUS is not set -# CONFIG_USB_ISP1301 is not set -# end of USB Physical Layer drivers - -CONFIG_USB_GADGET=y -# CONFIG_USB_GADGET_DEBUG is not set -# CONFIG_USB_GADGET_DEBUG_FILES is not set -# CONFIG_USB_GADGET_DEBUG_FS is not set -CONFIG_USB_GADGET_VBUS_DRAW=2 -CONFIG_USB_GADGET_STORAGE_NUM_BUFFERS=2 -# CONFIG_U_SERIAL_CONSOLE is not set - -# -# USB Peripheral Controller -# -# CONFIG_USB_GR_UDC is not set -# CONFIG_USB_R8A66597 is not set -# CONFIG_USB_RENESAS_USB3 is not set -# CONFIG_USB_RENESAS_USBF is not set -# CONFIG_USB_PXA27X is not set -# CONFIG_USB_MV_UDC is not set -# CONFIG_USB_MV_U3D is not set -# CONFIG_USB_SNP_UDC_PLAT is not set -# CONFIG_USB_M66592 is not set -# CONFIG_USB_BDC_UDC is not set -# CONFIG_USB_AMD5536UDC is not set -# CONFIG_USB_NET2272 is not set -# CONFIG_USB_NET2280 is not set -# CONFIG_USB_GOKU is not set -# CONFIG_USB_EG20T is not set -# CONFIG_USB_GADGET_XILINX is not set -# CONFIG_USB_MAX3420_UDC is not set -# CONFIG_USB_DUMMY_HCD is not set -# end of USB Peripheral Controller - -CONFIG_USB_LIBCOMPOSITE=y -CONFIG_USB_F_ACM=y -CONFIG_USB_F_SS_LB=y -CONFIG_USB_U_SERIAL=y -CONFIG_USB_U_ETHER=y -CONFIG_USB_F_SERIAL=y -CONFIG_USB_F_OBEX=y -CONFIG_USB_F_NCM=y -CONFIG_USB_F_ECM=y -CONFIG_USB_F_EEM=y -CONFIG_USB_F_SUBSET=y -CONFIG_USB_F_RNDIS=y -CONFIG_USB_F_MASS_STORAGE=y -CONFIG_USB_F_FS=y -CONFIG_USB_F_UVC=m -CONFIG_USB_F_HID=y -CONFIG_USB_F_PRINTER=y -CONFIG_USB_CONFIGFS=y -CONFIG_USB_CONFIGFS_SERIAL=y -CONFIG_USB_CONFIGFS_ACM=y -CONFIG_USB_CONFIGFS_OBEX=y -CONFIG_USB_CONFIGFS_NCM=y -CONFIG_USB_CONFIGFS_ECM=y -CONFIG_USB_CONFIGFS_ECM_SUBSET=y -CONFIG_USB_CONFIGFS_RNDIS=y -CONFIG_USB_CONFIGFS_EEM=y -CONFIG_USB_CONFIGFS_MASS_STORAGE=y -CONFIG_USB_CONFIGFS_F_LB_SS=y -CONFIG_USB_CONFIGFS_F_FS=y -CONFIG_USB_CONFIGFS_F_HID=y -CONFIG_USB_CONFIGFS_F_UVC=y -CONFIG_USB_CONFIGFS_F_PRINTER=y - -# -# USB Gadget precomposed configurations -# -# CONFIG_USB_ZERO is not set -# CONFIG_USB_ETH is not set -# CONFIG_USB_G_NCM is not set -# CONFIG_USB_GADGETFS is not set -# CONFIG_USB_FUNCTIONFS is not set -# CONFIG_USB_MASS_STORAGE is not set -# CONFIG_USB_G_SERIAL is not set -# CONFIG_USB_G_PRINTER is not set -# CONFIG_USB_CDC_COMPOSITE is not set -# CONFIG_USB_G_ACM_MS is not set -# CONFIG_USB_G_MULTI is not set -# CONFIG_USB_G_HID is not set -# CONFIG_USB_G_DBGP is not set -# CONFIG_USB_G_WEBCAM is not set -# CONFIG_USB_RAW_GADGET is not set -# end of USB Gadget precomposed configurations - -# CONFIG_TYPEC is not set -# CONFIG_USB_ROLE_SWITCH is not set -CONFIG_MMC=y -CONFIG_PWRSEQ_EMMC=y -CONFIG_PWRSEQ_SIMPLE=y -CONFIG_MMC_BLOCK=y -CONFIG_MMC_BLOCK_MINORS=8 -# CONFIG_SDIO_UART is not set -# CONFIG_MMC_TEST is not set - -# -# MMC/SD/SDIO Host Controller Drivers -# -# CONFIG_MMC_DEBUG is not set -CONFIG_MMC_SDHCI=y -CONFIG_MMC_SDHCI_IO_ACCESSORS=y -# CONFIG_MMC_SDHCI_PCI is not set -CONFIG_MMC_SDHCI_PLTFM=y -# CONFIG_MMC_SDHCI_OF_ARASAN is not set -# CONFIG_MMC_SDHCI_OF_AT91 is not set -# CONFIG_MMC_SDHCI_OF_DWCMSHC is not set -CONFIG_MMC_SDHCI_CADENCE=y -# CONFIG_MMC_SDHCI_F_SDH30 is not set -# CONFIG_MMC_SDHCI_MILBEAUT is not set -# CONFIG_MMC_TIFM_SD is not set -CONFIG_MMC_SPI=y -# CONFIG_MMC_SDHI is not set -# CONFIG_MMC_CB710 is not set -# CONFIG_MMC_VIA_SDMMC is not set -# CONFIG_MMC_DW is not set -# CONFIG_MMC_SH_MMCIF is not set -# CONFIG_MMC_VUB300 is not set -# CONFIG_MMC_USHC is not set -# CONFIG_MMC_USDHI6ROL0 is not set -CONFIG_MMC_SUNXI=y -# CONFIG_MMC_CQHCI is not set -# CONFIG_MMC_HSQ is not set -# CONFIG_MMC_TOSHIBA_PCI is not set -# CONFIG_MMC_MTK is not set -# CONFIG_MMC_SDHCI_XENON is not set -# CONFIG_MMC_SDHCI_OMAP is not set -# CONFIG_MMC_SDHCI_AM654 is not set -# CONFIG_SCSI_UFSHCD is not set -# CONFIG_MEMSTICK is not set -# CONFIG_NEW_LEDS is not set -# CONFIG_ACCESSIBILITY is not set -# CONFIG_INFINIBAND is not set -CONFIG_EDAC_SUPPORT=y -CONFIG_RTC_LIB=y -CONFIG_RTC_CLASS=y -CONFIG_RTC_HCTOSYS=y -CONFIG_RTC_HCTOSYS_DEVICE="rtc0" -CONFIG_RTC_SYSTOHC=y -CONFIG_RTC_SYSTOHC_DEVICE="rtc0" -# CONFIG_RTC_DEBUG is not set -CONFIG_RTC_NVMEM=y - -# -# RTC interfaces -# -CONFIG_RTC_INTF_SYSFS=y -CONFIG_RTC_INTF_PROC=y -CONFIG_RTC_INTF_DEV=y -# CONFIG_RTC_INTF_DEV_UIE_EMUL is not set -# CONFIG_RTC_DRV_TEST is not set - -# -# I2C RTC drivers -# -# CONFIG_RTC_DRV_ABB5ZES3 is not set -# CONFIG_RTC_DRV_ABEOZ9 is not set -# CONFIG_RTC_DRV_ABX80X is not set -# CONFIG_RTC_DRV_DS1307 is not set -# CONFIG_RTC_DRV_DS1374 is not set -# CONFIG_RTC_DRV_DS1672 is not set -# CONFIG_RTC_DRV_HYM8563 is not set -# CONFIG_RTC_DRV_MAX6900 is not set -# CONFIG_RTC_DRV_NCT3018Y is not set -# CONFIG_RTC_DRV_RS5C372 is not set -# CONFIG_RTC_DRV_ISL1208 is not set -# CONFIG_RTC_DRV_ISL12022 is not set -# CONFIG_RTC_DRV_ISL12026 is not set -# CONFIG_RTC_DRV_X1205 is not set -# CONFIG_RTC_DRV_PCF8523 is not set -# CONFIG_RTC_DRV_PCF85063 is not set -# CONFIG_RTC_DRV_PCF85363 is not set -# CONFIG_RTC_DRV_PCF8563 is not set -# CONFIG_RTC_DRV_PCF8583 is not set -# CONFIG_RTC_DRV_M41T80 is not set -# CONFIG_RTC_DRV_BQ32K is not set -# CONFIG_RTC_DRV_S35390A is not set -# CONFIG_RTC_DRV_FM3130 is not set -# CONFIG_RTC_DRV_RX8010 is not set -# CONFIG_RTC_DRV_RX8581 is not set -# CONFIG_RTC_DRV_RX8025 is not set -# CONFIG_RTC_DRV_EM3027 is not set -# CONFIG_RTC_DRV_RV3028 is not set -# CONFIG_RTC_DRV_RV3032 is not set -# CONFIG_RTC_DRV_RV8803 is not set -# CONFIG_RTC_DRV_SD3078 is not set - -# -# SPI RTC drivers -# -# CONFIG_RTC_DRV_M41T93 is not set -# CONFIG_RTC_DRV_M41T94 is not set -# CONFIG_RTC_DRV_DS1302 is not set -# CONFIG_RTC_DRV_DS1305 is not set -# CONFIG_RTC_DRV_DS1343 is not set -# CONFIG_RTC_DRV_DS1347 is not set -# CONFIG_RTC_DRV_DS1390 is not set -# CONFIG_RTC_DRV_MAX6916 is not set -# CONFIG_RTC_DRV_R9701 is not set -# CONFIG_RTC_DRV_RX4581 is not set -# CONFIG_RTC_DRV_RS5C348 is not set -# CONFIG_RTC_DRV_MAX6902 is not set -# CONFIG_RTC_DRV_PCF2123 is not set -# CONFIG_RTC_DRV_MCP795 is not set -CONFIG_RTC_I2C_AND_SPI=y - -# -# SPI and I2C RTC drivers -# -# CONFIG_RTC_DRV_DS3232 is not set -# CONFIG_RTC_DRV_PCF2127 is not set -# CONFIG_RTC_DRV_RV3029C2 is not set -# CONFIG_RTC_DRV_RX6110 is not set - -# -# Platform RTC drivers -# -# CONFIG_RTC_DRV_DS1286 is not set -# CONFIG_RTC_DRV_DS1511 is not set -# CONFIG_RTC_DRV_DS1553 is not set -# CONFIG_RTC_DRV_DS1685_FAMILY is not set -# CONFIG_RTC_DRV_DS1742 is not set -# CONFIG_RTC_DRV_DS2404 is not set -# CONFIG_RTC_DRV_EFI is not set -# CONFIG_RTC_DRV_STK17TA8 is not set -# CONFIG_RTC_DRV_M48T86 is not set -# CONFIG_RTC_DRV_M48T35 is not set -# CONFIG_RTC_DRV_M48T59 is not set -# CONFIG_RTC_DRV_MSM6242 is not set -# CONFIG_RTC_DRV_BQ4802 is not set -# CONFIG_RTC_DRV_RP5C01 is not set -# CONFIG_RTC_DRV_ZYNQMP is not set - -# -# on-CPU RTC drivers -# -# CONFIG_RTC_DRV_SH is not set -CONFIG_RTC_DRV_SUN6I=y -# CONFIG_RTC_DRV_CADENCE is not set -# CONFIG_RTC_DRV_FTRTC010 is not set -# CONFIG_RTC_DRV_R7301 is not set - -# -# HID Sensor RTC drivers -# -CONFIG_RTC_DRV_GOLDFISH=y -# CONFIG_RTC_DRV_POLARFIRE_SOC is not set -CONFIG_DMADEVICES=y -# CONFIG_DMADEVICES_DEBUG is not set - -# -# DMA Devices -# -CONFIG_DMA_ENGINE=y -CONFIG_DMA_VIRTUAL_CHANNELS=m -CONFIG_DMA_OF=y -# CONFIG_ALTERA_MSGDMA is not set -CONFIG_DMA_SUN6I=m -# CONFIG_DW_AXI_DMAC is not set -# CONFIG_FSL_EDMA is not set -# CONFIG_INTEL_IDMA64 is not set -# CONFIG_PLX_DMA is not set -# CONFIG_XILINX_XDMA is not set -# CONFIG_XILINX_ZYNQMP_DPDMA is not set -# CONFIG_QCOM_HIDMA_MGMT is not set -# CONFIG_QCOM_HIDMA is not set -# CONFIG_DW_DMAC is not set -# CONFIG_DW_DMAC_PCI is not set -# CONFIG_DW_EDMA is not set -# CONFIG_SF_PDMA is not set -# CONFIG_RCAR_DMAC is not set -# CONFIG_RENESAS_USB_DMAC is not set -# CONFIG_RZ_DMAC is not set - -# -# DMA Clients -# -# CONFIG_ASYNC_TX_DMA is not set -# CONFIG_DMATEST is not set - -# -# DMABUF options -# -CONFIG_SYNC_FILE=y -# CONFIG_SW_SYNC is not set -# CONFIG_UDMABUF is not set -# CONFIG_DMABUF_MOVE_NOTIFY is not set -# CONFIG_DMABUF_DEBUG is not set -# CONFIG_DMABUF_SELFTESTS is not set -# CONFIG_DMABUF_HEAPS is not set -# CONFIG_DMABUF_SYSFS_STATS is not set -# end of DMABUF options - -# CONFIG_AUXDISPLAY is not set -# CONFIG_UIO is not set -# CONFIG_VFIO is not set -# CONFIG_VIRT_DRIVERS is not set -CONFIG_VIRTIO_ANCHOR=y -CONFIG_VIRTIO=y -CONFIG_VIRTIO_PCI_LIB=y -CONFIG_VIRTIO_PCI_LIB_LEGACY=y -CONFIG_VIRTIO_MENU=y -CONFIG_VIRTIO_PCI=y -CONFIG_VIRTIO_PCI_LEGACY=y -# CONFIG_VIRTIO_PMEM is not set -CONFIG_VIRTIO_BALLOON=y -CONFIG_VIRTIO_INPUT=y -CONFIG_VIRTIO_MMIO=y -# CONFIG_VIRTIO_MMIO_CMDLINE_DEVICES is not set -# CONFIG_VDPA is not set -CONFIG_VHOST_MENU=y -# CONFIG_VHOST_NET is not set -# CONFIG_VHOST_CROSS_ENDIAN_LEGACY is not set - -# -# Microsoft Hyper-V guest support -# -# end of Microsoft Hyper-V guest support - -# CONFIG_GREYBUS is not set -# CONFIG_COMEDI is not set -# CONFIG_STAGING is not set -CONFIG_GOLDFISH=y -# CONFIG_GOLDFISH_PIPE is not set -CONFIG_HAVE_CLK=y -CONFIG_HAVE_CLK_PREPARE=y -CONFIG_COMMON_CLK=y -# CONFIG_LMK04832 is not set -# CONFIG_COMMON_CLK_MAX9485 is not set -# CONFIG_COMMON_CLK_SI5341 is not set -# CONFIG_COMMON_CLK_SI5351 is not set -# CONFIG_COMMON_CLK_SI514 is not set -# CONFIG_COMMON_CLK_SI544 is not set -# CONFIG_COMMON_CLK_SI570 is not set -# CONFIG_COMMON_CLK_CDCE706 is not set -# CONFIG_COMMON_CLK_CDCE925 is not set -# CONFIG_COMMON_CLK_CS2000_CP is not set -# CONFIG_COMMON_CLK_AXI_CLKGEN is not set -# CONFIG_COMMON_CLK_RS9_PCIE is not set -# CONFIG_COMMON_CLK_SI521XX is not set -# CONFIG_COMMON_CLK_VC5 is not set -# CONFIG_COMMON_CLK_VC7 is not set -# CONFIG_COMMON_CLK_FIXED_MMIO is not set -CONFIG_CLK_ANALOGBITS_WRPLL_CLN28HPC=y -CONFIG_MCHP_CLK_MPFS=y -CONFIG_CLK_RENESAS=y -CONFIG_CLK_R9A07G043=y -# CONFIG_CLK_RCAR_USB2_CLOCK_SEL is not set -CONFIG_CLK_RZG2L=y -CONFIG_CLK_SIFIVE=y -CONFIG_CLK_SIFIVE_PRCI=y -CONFIG_CLK_STARFIVE_JH71X0=y -CONFIG_CLK_STARFIVE_JH7100=y -CONFIG_CLK_STARFIVE_JH7100_AUDIO=m -CONFIG_CLK_STARFIVE_JH7110_SYS=y -CONFIG_CLK_STARFIVE_JH7110_AON=m -CONFIG_SUNXI_CCU=y -CONFIG_SUN20I_D1_CCU=y -CONFIG_SUN20I_D1_R_CCU=y -CONFIG_SUN6I_RTC_CCU=y -CONFIG_SUN8I_DE2_CCU=m -# CONFIG_XILINX_VCU is not set -# CONFIG_COMMON_CLK_XLNX_CLKWZRD is not set -# CONFIG_HWSPINLOCK is not set - -# -# Clock Source drivers -# -CONFIG_TIMER_OF=y -CONFIG_TIMER_PROBE=y -CONFIG_CLKSRC_MMIO=y -CONFIG_SUN4I_TIMER=y -# CONFIG_RENESAS_OSTM is not set -CONFIG_RISCV_TIMER=y -# end of Clock Source drivers - -CONFIG_MAILBOX=y -# CONFIG_PLATFORM_MHU is not set -# CONFIG_ALTERA_MBOX is not set -# CONFIG_MAILBOX_TEST is not set -CONFIG_POLARFIRE_SOC_MAILBOX=y -# CONFIG_SUN6I_MSGBOX is not set -CONFIG_IOMMU_API=y -CONFIG_IOMMU_SUPPORT=y - -# -# Generic IOMMU Pagetable Support -# -# end of Generic IOMMU Pagetable Support - -# CONFIG_IOMMU_DEBUGFS is not set -CONFIG_IOMMU_DEFAULT_DMA_STRICT=y -# CONFIG_IOMMU_DEFAULT_DMA_LAZY is not set -# CONFIG_IOMMU_DEFAULT_PASSTHROUGH is not set -CONFIG_OF_IOMMU=y -# CONFIG_IOMMUFD is not set -CONFIG_SUN50I_IOMMU=y - -# -# Remoteproc drivers -# -CONFIG_REMOTEPROC=y -CONFIG_REMOTEPROC_CDEV=y -# CONFIG_RCAR_REMOTEPROC is not set -# end of Remoteproc drivers - -# -# Rpmsg drivers -# -CONFIG_RPMSG=y -CONFIG_RPMSG_CHAR=y -CONFIG_RPMSG_CTRL=y -CONFIG_RPMSG_NS=y -# CONFIG_RPMSG_QCOM_GLINK_RPM is not set -CONFIG_RPMSG_VIRTIO=y -# end of Rpmsg drivers - -# CONFIG_SOUNDWIRE is not set - -# -# SOC (System On Chip) specific Drivers -# - -# -# Amlogic SoC drivers -# -# end of Amlogic SoC drivers - -# -# Broadcom SoC drivers -# -# end of Broadcom SoC drivers - -# -# NXP/Freescale QorIQ SoC drivers -# -# end of NXP/Freescale QorIQ SoC drivers - -# -# fujitsu SoC drivers -# -# end of fujitsu SoC drivers - -# -# i.MX SoC drivers -# -# end of i.MX SoC drivers - -# -# Enable LiteX SoC Builder specific drivers -# -# CONFIG_LITEX_SOC_CONTROLLER is not set -# end of Enable LiteX SoC Builder specific drivers - -CONFIG_POLARFIRE_SOC_SYS_CTRL=y -# CONFIG_WPCM450_SOC is not set - -# -# Qualcomm SoC drivers -# -# end of Qualcomm SoC drivers - -CONFIG_SOC_RENESAS=y -CONFIG_ARCH_RZG2L=y -CONFIG_ARCH_R9A07G043=y -# CONFIG_SIFIVE_CCACHE is not set -CONFIG_JH71XX_PMU=y -CONFIG_SUNXI_SRAM=y -# CONFIG_SUN20I_PPU is not set -# CONFIG_SOC_TI is not set - -# -# Xilinx SoC drivers -# -# end of Xilinx SoC drivers -# end of SOC (System On Chip) specific Drivers - -# CONFIG_PM_DEVFREQ is not set -CONFIG_EXTCON=y - -# -# Extcon Device Drivers -# -# CONFIG_EXTCON_ADC_JACK is not set -# CONFIG_EXTCON_FSA9480 is not set -# CONFIG_EXTCON_GPIO is not set -# CONFIG_EXTCON_MAX3355 is not set -# CONFIG_EXTCON_PTN5150 is not set -# CONFIG_EXTCON_RT8973A is not set -# CONFIG_EXTCON_SM5502 is not set -# CONFIG_EXTCON_USB_GPIO is not set -# CONFIG_MEMORY is not set -CONFIG_IIO=m -# CONFIG_IIO_BUFFER is not set -# CONFIG_IIO_CONFIGFS is not set -# CONFIG_IIO_TRIGGER is not set -# CONFIG_IIO_SW_DEVICE is not set -# CONFIG_IIO_SW_TRIGGER is not set -# CONFIG_IIO_TRIGGERED_EVENT is not set - -# -# Accelerometers -# -# CONFIG_ADIS16201 is not set -# CONFIG_ADIS16209 is not set -# CONFIG_ADXL313_I2C is not set -# CONFIG_ADXL313_SPI is not set -# CONFIG_ADXL345_I2C is not set -# CONFIG_ADXL345_SPI is not set -# CONFIG_ADXL355_I2C is not set -# CONFIG_ADXL355_SPI is not set -# CONFIG_ADXL367_SPI is not set -# CONFIG_ADXL367_I2C is not set -# CONFIG_ADXL372_SPI is not set -# CONFIG_ADXL372_I2C is not set -# CONFIG_BMA180 is not set -# CONFIG_BMA220 is not set -# CONFIG_BMA400 is not set -# CONFIG_BMC150_ACCEL is not set -# CONFIG_BMI088_ACCEL is not set -# CONFIG_DA280 is not set -# CONFIG_DA311 is not set -# CONFIG_DMARD06 is not set -# CONFIG_DMARD09 is not set -# CONFIG_DMARD10 is not set -# CONFIG_FXLS8962AF_I2C is not set -# CONFIG_FXLS8962AF_SPI is not set -# CONFIG_IIO_ST_ACCEL_3AXIS is not set -# CONFIG_IIO_KX022A_SPI is not set -# CONFIG_IIO_KX022A_I2C is not set -# CONFIG_KXSD9 is not set -# CONFIG_KXCJK1013 is not set -# CONFIG_MC3230 is not set -# CONFIG_MMA7455_I2C is not set -# CONFIG_MMA7455_SPI is not set -# CONFIG_MMA7660 is not set -# CONFIG_MMA8452 is not set -# CONFIG_MMA9551 is not set -# CONFIG_MMA9553 is not set -# CONFIG_MSA311 is not set -# CONFIG_MXC4005 is not set -# CONFIG_MXC6255 is not set -# CONFIG_SCA3000 is not set -# CONFIG_SCA3300 is not set -# CONFIG_STK8312 is not set -# CONFIG_STK8BA50 is not set -# end of Accelerometers - -# -# Analog to digital converters -# -# CONFIG_AD4130 is not set -# CONFIG_AD7091R5 is not set -# CONFIG_AD7124 is not set -# CONFIG_AD7192 is not set -# CONFIG_AD7266 is not set -# CONFIG_AD7280 is not set -# CONFIG_AD7291 is not set -# CONFIG_AD7292 is not set -# CONFIG_AD7298 is not set -# CONFIG_AD7476 is not set -# CONFIG_AD7606_IFACE_PARALLEL is not set -# CONFIG_AD7606_IFACE_SPI is not set -# CONFIG_AD7766 is not set -# CONFIG_AD7768_1 is not set -# CONFIG_AD7780 is not set -# CONFIG_AD7791 is not set -# CONFIG_AD7793 is not set -# CONFIG_AD7887 is not set -# CONFIG_AD7923 is not set -# CONFIG_AD7949 is not set -# CONFIG_AD799X is not set -# CONFIG_ADI_AXI_ADC is not set -# CONFIG_CC10001_ADC is not set -# CONFIG_ENVELOPE_DETECTOR is not set -# CONFIG_HI8435 is not set -# CONFIG_HX711 is not set -# CONFIG_INA2XX_ADC is not set -# CONFIG_LTC2471 is not set -# CONFIG_LTC2485 is not set -# CONFIG_LTC2496 is not set -# CONFIG_LTC2497 is not set -# CONFIG_MAX1027 is not set -# CONFIG_MAX11100 is not set -# CONFIG_MAX1118 is not set -# CONFIG_MAX11205 is not set -# CONFIG_MAX11410 is not set -# CONFIG_MAX1241 is not set -# CONFIG_MAX1363 is not set -# CONFIG_MAX9611 is not set -# CONFIG_MCP320X is not set -# CONFIG_MCP3422 is not set -# CONFIG_MCP3911 is not set -# CONFIG_NAU7802 is not set -# CONFIG_RICHTEK_RTQ6056 is not set -# CONFIG_RZG2L_ADC is not set -# CONFIG_SD_ADC_MODULATOR is not set -# CONFIG_TI_ADC081C is not set -# CONFIG_TI_ADC0832 is not set -# CONFIG_TI_ADC084S021 is not set -# CONFIG_TI_ADC12138 is not set -# CONFIG_TI_ADC108S102 is not set -# CONFIG_TI_ADC128S052 is not set -# CONFIG_TI_ADC161S626 is not set -# CONFIG_TI_ADS1015 is not set -# CONFIG_TI_ADS7924 is not set -# CONFIG_TI_ADS1100 is not set -# CONFIG_TI_ADS7950 is not set -# CONFIG_TI_ADS8344 is not set -# CONFIG_TI_ADS8688 is not set -# CONFIG_TI_ADS124S08 is not set -# CONFIG_TI_ADS131E08 is not set -# CONFIG_TI_LMP92064 is not set -# CONFIG_TI_TLC4541 is not set -# CONFIG_TI_TSC2046 is not set -# CONFIG_VF610_ADC is not set -# CONFIG_XILINX_XADC is not set -# end of Analog to digital converters - -# -# Analog to digital and digital to analog converters -# -# CONFIG_AD74115 is not set -# CONFIG_AD74413R is not set -# end of Analog to digital and digital to analog converters - -# -# Analog Front Ends -# -# CONFIG_IIO_RESCALE is not set -# end of Analog Front Ends - -# -# Amplifiers -# -# CONFIG_AD8366 is not set -# CONFIG_ADA4250 is not set -# CONFIG_HMC425 is not set -# end of Amplifiers - -# -# Capacitance to digital converters -# -# CONFIG_AD7150 is not set -# CONFIG_AD7746 is not set -# end of Capacitance to digital converters - -# -# Chemical Sensors -# -# CONFIG_ATLAS_PH_SENSOR is not set -# CONFIG_ATLAS_EZO_SENSOR is not set -# CONFIG_BME680 is not set -# CONFIG_CCS811 is not set -# CONFIG_IAQCORE is not set -# CONFIG_SCD30_CORE is not set -# CONFIG_SCD4X is not set -# CONFIG_SENSIRION_SGP30 is not set -# CONFIG_SENSIRION_SGP40 is not set -# CONFIG_SPS30_I2C is not set -# CONFIG_SENSEAIR_SUNRISE_CO2 is not set -# CONFIG_VZ89X is not set -# end of Chemical Sensors - -# -# Hid Sensor IIO Common -# -# end of Hid Sensor IIO Common - -# -# IIO SCMI Sensors -# -# end of IIO SCMI Sensors - -# -# SSP Sensor Common -# -# CONFIG_IIO_SSP_SENSORHUB is not set -# end of SSP Sensor Common - -# -# Digital to analog converters -# -# CONFIG_AD3552R is not set -# CONFIG_AD5064 is not set -# CONFIG_AD5360 is not set -# CONFIG_AD5380 is not set -# CONFIG_AD5421 is not set -# CONFIG_AD5446 is not set -# CONFIG_AD5449 is not set -# CONFIG_AD5592R is not set -# CONFIG_AD5593R is not set -# CONFIG_AD5504 is not set -# CONFIG_AD5624R_SPI is not set -# CONFIG_LTC2688 is not set -# CONFIG_AD5686_SPI is not set -# CONFIG_AD5696_I2C is not set -# CONFIG_AD5755 is not set -# CONFIG_AD5758 is not set -# CONFIG_AD5761 is not set -# CONFIG_AD5764 is not set -# CONFIG_AD5766 is not set -# CONFIG_AD5770R is not set -# CONFIG_AD5791 is not set -# CONFIG_AD7293 is not set -# CONFIG_AD7303 is not set -# CONFIG_AD8801 is not set -# CONFIG_DPOT_DAC is not set -# CONFIG_DS4424 is not set -# CONFIG_LTC1660 is not set -# CONFIG_LTC2632 is not set -# CONFIG_M62332 is not set -# CONFIG_MAX517 is not set -# CONFIG_MAX5522 is not set -# CONFIG_MAX5821 is not set -# CONFIG_MCP4725 is not set -# CONFIG_MCP4922 is not set -# CONFIG_TI_DAC082S085 is not set -# CONFIG_TI_DAC5571 is not set -# CONFIG_TI_DAC7311 is not set -# CONFIG_TI_DAC7612 is not set -# CONFIG_VF610_DAC is not set -# end of Digital to analog converters - -# -# IIO dummy driver -# -# end of IIO dummy driver - -# -# Filters -# -# CONFIG_ADMV8818 is not set -# end of Filters - -# -# Frequency Synthesizers DDS/PLL -# - -# -# Clock Generator/Distribution -# -# CONFIG_AD9523 is not set -# end of Clock Generator/Distribution - -# -# Phase-Locked Loop (PLL) frequency synthesizers -# -# CONFIG_ADF4350 is not set -# CONFIG_ADF4371 is not set -# CONFIG_ADF4377 is not set -# CONFIG_ADMV1013 is not set -# CONFIG_ADMV1014 is not set -# CONFIG_ADMV4420 is not set -# CONFIG_ADRF6780 is not set -# end of Phase-Locked Loop (PLL) frequency synthesizers -# end of Frequency Synthesizers DDS/PLL - -# -# Digital gyroscope sensors -# -# CONFIG_ADIS16080 is not set -# CONFIG_ADIS16130 is not set -# CONFIG_ADIS16136 is not set -# CONFIG_ADIS16260 is not set -# CONFIG_ADXRS290 is not set -# CONFIG_ADXRS450 is not set -# CONFIG_BMG160 is not set -# CONFIG_FXAS21002C is not set -# CONFIG_MPU3050_I2C is not set -# CONFIG_IIO_ST_GYRO_3AXIS is not set -# CONFIG_ITG3200 is not set -# end of Digital gyroscope sensors - -# -# Health Sensors -# - -# -# Heart Rate Monitors -# -# CONFIG_AFE4403 is not set -# CONFIG_AFE4404 is not set -# CONFIG_MAX30100 is not set -# CONFIG_MAX30102 is not set -# end of Heart Rate Monitors -# end of Health Sensors - -# -# Humidity sensors -# -# CONFIG_AM2315 is not set -# CONFIG_DHT11 is not set -# CONFIG_HDC100X is not set -# CONFIG_HDC2010 is not set -# CONFIG_HTS221 is not set -# CONFIG_HTU21 is not set -# CONFIG_SI7005 is not set -# CONFIG_SI7020 is not set -# end of Humidity sensors - -# -# Inertial measurement units -# -# CONFIG_ADIS16400 is not set -# CONFIG_ADIS16460 is not set -# CONFIG_ADIS16475 is not set -# CONFIG_ADIS16480 is not set -# CONFIG_BMI160_I2C is not set -# CONFIG_BMI160_SPI is not set -# CONFIG_BOSCH_BNO055_I2C is not set -# CONFIG_FXOS8700_I2C is not set -# CONFIG_FXOS8700_SPI is not set -# CONFIG_KMX61 is not set -# CONFIG_INV_ICM42600_I2C is not set -# CONFIG_INV_ICM42600_SPI is not set -# CONFIG_INV_MPU6050_I2C is not set -# CONFIG_INV_MPU6050_SPI is not set -# CONFIG_IIO_ST_LSM6DSX is not set -# CONFIG_IIO_ST_LSM9DS0 is not set -# end of Inertial measurement units - -# -# Light sensors -# -# CONFIG_ADJD_S311 is not set -# CONFIG_ADUX1020 is not set -# CONFIG_AL3010 is not set -# CONFIG_AL3320A is not set -# CONFIG_APDS9300 is not set -# CONFIG_APDS9960 is not set -# CONFIG_AS73211 is not set -# CONFIG_BH1750 is not set -# CONFIG_BH1780 is not set -# CONFIG_CM32181 is not set -# CONFIG_CM3232 is not set -# CONFIG_CM3323 is not set -# CONFIG_CM3605 is not set -# CONFIG_CM36651 is not set -# CONFIG_GP2AP002 is not set -# CONFIG_GP2AP020A00F is not set -# CONFIG_SENSORS_ISL29018 is not set -# CONFIG_SENSORS_ISL29028 is not set -# CONFIG_ISL29125 is not set -# CONFIG_JSA1212 is not set -# CONFIG_ROHM_BU27034 is not set -# CONFIG_RPR0521 is not set -# CONFIG_LTR501 is not set -# CONFIG_LTRF216A is not set -# CONFIG_LV0104CS is not set -# CONFIG_MAX44000 is not set -# CONFIG_MAX44009 is not set -# CONFIG_NOA1305 is not set -# CONFIG_OPT3001 is not set -# CONFIG_PA12203001 is not set -# CONFIG_SI1133 is not set -# CONFIG_SI1145 is not set -# CONFIG_STK3310 is not set -# CONFIG_ST_UVIS25 is not set -# CONFIG_TCS3414 is not set -# CONFIG_TCS3472 is not set -# CONFIG_SENSORS_TSL2563 is not set -# CONFIG_TSL2583 is not set -# CONFIG_TSL2591 is not set -# CONFIG_TSL2772 is not set -# CONFIG_TSL4531 is not set -# CONFIG_US5182D is not set -# CONFIG_VCNL4000 is not set -# CONFIG_VCNL4035 is not set -# CONFIG_VEML6030 is not set -# CONFIG_VEML6070 is not set -# CONFIG_VL6180 is not set -# CONFIG_ZOPT2201 is not set -# end of Light sensors - -# -# Magnetometer sensors -# -# CONFIG_AK8974 is not set -# CONFIG_AK8975 is not set -# CONFIG_AK09911 is not set -# CONFIG_BMC150_MAGN_I2C is not set -# CONFIG_BMC150_MAGN_SPI is not set -# CONFIG_MAG3110 is not set -# CONFIG_MMC35240 is not set -# CONFIG_IIO_ST_MAGN_3AXIS is not set -# CONFIG_SENSORS_HMC5843_I2C is not set -# CONFIG_SENSORS_HMC5843_SPI is not set -# CONFIG_SENSORS_RM3100_I2C is not set -# CONFIG_SENSORS_RM3100_SPI is not set -# CONFIG_TI_TMAG5273 is not set -# CONFIG_YAMAHA_YAS530 is not set -# end of Magnetometer sensors - -# -# Multiplexers -# -# CONFIG_IIO_MUX is not set -# end of Multiplexers - -# -# Inclinometer sensors -# -# end of Inclinometer sensors - -# -# Linear and angular position sensors -# -# end of Linear and angular position sensors - -# -# Digital potentiometers -# -# CONFIG_AD5110 is not set -# CONFIG_AD5272 is not set -# CONFIG_DS1803 is not set -# CONFIG_MAX5432 is not set -# CONFIG_MAX5481 is not set -# CONFIG_MAX5487 is not set -# CONFIG_MCP4018 is not set -# CONFIG_MCP4131 is not set -# CONFIG_MCP4531 is not set -# CONFIG_MCP41010 is not set -# CONFIG_TPL0102 is not set -# end of Digital potentiometers - -# -# Digital potentiostats -# -# CONFIG_LMP91000 is not set -# end of Digital potentiostats - -# -# Pressure sensors -# -# CONFIG_ABP060MG is not set -# CONFIG_BMP280 is not set -# CONFIG_DLHL60D is not set -# CONFIG_DPS310 is not set -# CONFIG_HP03 is not set -# CONFIG_ICP10100 is not set -# CONFIG_MPL115_I2C is not set -# CONFIG_MPL115_SPI is not set -# CONFIG_MPL3115 is not set -# CONFIG_MS5611 is not set -# CONFIG_MS5637 is not set -# CONFIG_IIO_ST_PRESS is not set -# CONFIG_T5403 is not set -# CONFIG_HP206C is not set -# CONFIG_ZPA2326 is not set -# end of Pressure sensors - -# -# Lightning sensors -# -# CONFIG_AS3935 is not set -# end of Lightning sensors - -# -# Proximity and distance sensors -# -# CONFIG_ISL29501 is not set -# CONFIG_LIDAR_LITE_V2 is not set -# CONFIG_MB1232 is not set -# CONFIG_PING is not set -# CONFIG_RFD77402 is not set -# CONFIG_SRF04 is not set -# CONFIG_SX9310 is not set -# CONFIG_SX9324 is not set -# CONFIG_SX9360 is not set -# CONFIG_SX9500 is not set -# CONFIG_SRF08 is not set -# CONFIG_VCNL3020 is not set -# CONFIG_VL53L0X_I2C is not set -# end of Proximity and distance sensors - -# -# Resolver to digital converters -# -# CONFIG_AD2S90 is not set -# CONFIG_AD2S1200 is not set -# end of Resolver to digital converters - -# -# Temperature sensors -# -# CONFIG_LTC2983 is not set -# CONFIG_MAXIM_THERMOCOUPLE is not set -# CONFIG_MLX90614 is not set -# CONFIG_MLX90632 is not set -# CONFIG_TMP006 is not set -# CONFIG_TMP007 is not set -# CONFIG_TMP117 is not set -# CONFIG_TSYS01 is not set -# CONFIG_TSYS02D is not set -# CONFIG_MAX30208 is not set -# CONFIG_MAX31856 is not set -# CONFIG_MAX31865 is not set -# end of Temperature sensors - -# CONFIG_NTB is not set -# CONFIG_PWM is not set - -# -# IRQ chip support -# -CONFIG_IRQCHIP=y -# CONFIG_AL_FIC is not set -CONFIG_RENESAS_RZG2L_IRQC=y -# CONFIG_XILINX_INTC is not set -CONFIG_RISCV_INTC=y -CONFIG_SIFIVE_PLIC=y -# end of IRQ chip support - -# CONFIG_IPACK_BUS is not set -CONFIG_RESET_CONTROLLER=y -CONFIG_RESET_POLARFIRE_SOC=y -# CONFIG_RESET_RZG2L_USBPHY_CTRL is not set -CONFIG_RESET_SIMPLE=y -CONFIG_RESET_SUNXI=y -# CONFIG_RESET_TI_SYSCON is not set -# CONFIG_RESET_TI_TPS380X is not set -CONFIG_RESET_STARFIVE_JH71X0=y -CONFIG_RESET_STARFIVE_JH7100=y -CONFIG_RESET_STARFIVE_JH7110=y - -# -# PHY Subsystem -# -CONFIG_GENERIC_PHY=y -CONFIG_GENERIC_PHY_MIPI_DPHY=y -# CONFIG_PHY_CAN_TRANSCEIVER is not set -CONFIG_PHY_SUN4I_USB=m -CONFIG_PHY_SUN6I_MIPI_DPHY=m -# CONFIG_PHY_SUN9I_USB is not set -# CONFIG_PHY_SUN50I_USB3 is not set - -# -# PHY drivers for Broadcom platforms -# -# CONFIG_BCM_KONA_USB2_PHY is not set -# end of PHY drivers for Broadcom platforms - -# CONFIG_PHY_CADENCE_TORRENT is not set -# CONFIG_PHY_CADENCE_DPHY is not set -# CONFIG_PHY_CADENCE_DPHY_RX is not set -# CONFIG_PHY_CADENCE_SIERRA is not set -# CONFIG_PHY_CADENCE_SALVO is not set -# CONFIG_PHY_PXA_28NM_HSIC is not set -# CONFIG_PHY_PXA_28NM_USB2 is not set -# CONFIG_PHY_LAN966X_SERDES is not set -# CONFIG_PHY_CPCAP_USB is not set -# CONFIG_PHY_MAPPHONE_MDM6600 is not set -# CONFIG_PHY_OCELOT_SERDES is not set -# CONFIG_PHY_R8A779F0_ETHERNET_SERDES is not set -# CONFIG_PHY_RCAR_GEN2 is not set -# CONFIG_PHY_RCAR_GEN3_PCIE is not set -# CONFIG_PHY_RCAR_GEN3_USB2 is not set -# CONFIG_PHY_RCAR_GEN3_USB3 is not set -# end of PHY Subsystem - -# CONFIG_POWERCAP is not set -# CONFIG_MCB is not set - -# -# Performance monitor support -# -CONFIG_RISCV_PMU=y -CONFIG_RISCV_PMU_LEGACY=y -CONFIG_RISCV_PMU_SBI=y -# end of Performance monitor support - -# CONFIG_RAS is not set -# CONFIG_USB4 is not set - -# -# Android -# -# CONFIG_ANDROID_BINDER_IPC is not set -# end of Android - -CONFIG_LIBNVDIMM=y -CONFIG_BLK_DEV_PMEM=y -CONFIG_ND_CLAIM=y -CONFIG_ND_BTT=y -CONFIG_BTT=y -CONFIG_OF_PMEM=y -CONFIG_DAX=y -CONFIG_NVMEM=y -CONFIG_NVMEM_SYSFS=y - -# -# Layout Types -# -# CONFIG_NVMEM_LAYOUT_SL28_VPD is not set -# CONFIG_NVMEM_LAYOUT_ONIE_TLV is not set -# end of Layout Types - -# CONFIG_NVMEM_RMEM is not set -CONFIG_NVMEM_SUNXI_SID=y - -# -# HW tracing support -# -# CONFIG_STM is not set -# CONFIG_INTEL_TH is not set -# end of HW tracing support - -# CONFIG_FPGA is not set -# CONFIG_FSI is not set -# CONFIG_SIOX is not set -# CONFIG_SLIMBUS is not set -# CONFIG_INTERCONNECT is not set -# CONFIG_COUNTER is not set -# CONFIG_MOST is not set -# CONFIG_PECI is not set -# CONFIG_HTE is not set -# end of Device Drivers - -# -# File systems -# -# CONFIG_VALIDATE_FS_PARSER is not set -CONFIG_FS_IOMAP=y -CONFIG_LEGACY_DIRECT_IO=y -# CONFIG_EXT2_FS is not set -# CONFIG_EXT3_FS is not set -CONFIG_EXT4_FS=y -CONFIG_EXT4_USE_FOR_EXT2=y -CONFIG_EXT4_FS_POSIX_ACL=y -CONFIG_EXT4_FS_SECURITY=y -# CONFIG_EXT4_DEBUG is not set -CONFIG_JBD2=y -# CONFIG_JBD2_DEBUG is not set -CONFIG_FS_MBCACHE=y -# CONFIG_REISERFS_FS is not set -# CONFIG_JFS_FS is not set -# CONFIG_XFS_FS is not set -# CONFIG_GFS2_FS is not set -# CONFIG_OCFS2_FS is not set -CONFIG_BTRFS_FS=m -CONFIG_BTRFS_FS_POSIX_ACL=y -# CONFIG_BTRFS_FS_CHECK_INTEGRITY is not set -# CONFIG_BTRFS_FS_RUN_SANITY_TESTS is not set -# CONFIG_BTRFS_DEBUG is not set -# CONFIG_BTRFS_ASSERT is not set -# CONFIG_BTRFS_FS_REF_VERIFY is not set -# CONFIG_NILFS2_FS is not set -# CONFIG_F2FS_FS is not set -CONFIG_FS_POSIX_ACL=y -CONFIG_EXPORTFS=y -# CONFIG_EXPORTFS_BLOCK_OPS is not set -CONFIG_FILE_LOCKING=y -# CONFIG_FS_ENCRYPTION is not set -# CONFIG_FS_VERITY is not set -CONFIG_FSNOTIFY=y -CONFIG_DNOTIFY=y -CONFIG_INOTIFY_USER=y -# CONFIG_FANOTIFY is not set -# CONFIG_QUOTA is not set -CONFIG_AUTOFS4_FS=y -CONFIG_AUTOFS_FS=y -# CONFIG_FUSE_FS is not set -CONFIG_OVERLAY_FS=m -# CONFIG_OVERLAY_FS_REDIRECT_DIR is not set -CONFIG_OVERLAY_FS_REDIRECT_ALWAYS_FOLLOW=y -# CONFIG_OVERLAY_FS_INDEX is not set -# CONFIG_OVERLAY_FS_XINO_AUTO is not set -# CONFIG_OVERLAY_FS_METACOPY is not set - -# -# Caches -# -CONFIG_NETFS_SUPPORT=y -# CONFIG_NETFS_STATS is not set -# CONFIG_FSCACHE is not set -# end of Caches - -# -# CD-ROM/DVD Filesystems -# -CONFIG_ISO9660_FS=y -CONFIG_JOLIET=y -CONFIG_ZISOFS=y -# CONFIG_UDF_FS is not set -# end of CD-ROM/DVD Filesystems - -# -# DOS/FAT/EXFAT/NT Filesystems -# -CONFIG_FAT_FS=y -CONFIG_MSDOS_FS=y -CONFIG_VFAT_FS=y -CONFIG_FAT_DEFAULT_CODEPAGE=437 -CONFIG_FAT_DEFAULT_IOCHARSET="iso8859-1" -# CONFIG_FAT_DEFAULT_UTF8 is not set -# CONFIG_EXFAT_FS is not set -# CONFIG_NTFS_FS is not set -# CONFIG_NTFS3_FS is not set -# end of DOS/FAT/EXFAT/NT Filesystems - -# -# Pseudo filesystems -# -CONFIG_PROC_FS=y -# CONFIG_PROC_KCORE is not set -CONFIG_PROC_SYSCTL=y -CONFIG_PROC_PAGE_MONITOR=y -CONFIG_PROC_CHILDREN=y -CONFIG_KERNFS=y -CONFIG_SYSFS=y -CONFIG_TMPFS=y -CONFIG_TMPFS_POSIX_ACL=y -CONFIG_TMPFS_XATTR=y -# CONFIG_TMPFS_INODE64 is not set -CONFIG_ARCH_SUPPORTS_HUGETLBFS=y -CONFIG_HUGETLBFS=y -CONFIG_HUGETLB_PAGE=y -CONFIG_HUGETLB_PAGE_OPTIMIZE_VMEMMAP=y -# CONFIG_HUGETLB_PAGE_OPTIMIZE_VMEMMAP_DEFAULT_ON is not set -CONFIG_MEMFD_CREATE=y -CONFIG_ARCH_HAS_GIGANTIC_PAGE=y -CONFIG_CONFIGFS_FS=y -CONFIG_EFIVAR_FS=m -# end of Pseudo filesystems - -CONFIG_MISC_FILESYSTEMS=y -# CONFIG_ORANGEFS_FS is not set -# CONFIG_ADFS_FS is not set -# CONFIG_AFFS_FS is not set -# CONFIG_ECRYPT_FS is not set -# CONFIG_HFS_FS is not set -# CONFIG_HFSPLUS_FS is not set -# CONFIG_BEFS_FS is not set -# CONFIG_BFS_FS is not set -# CONFIG_EFS_FS is not set -# CONFIG_CRAMFS is not set -# CONFIG_SQUASHFS is not set -# CONFIG_VXFS_FS is not set -# CONFIG_MINIX_FS is not set -# CONFIG_OMFS_FS is not set -# CONFIG_HPFS_FS is not set -# CONFIG_QNX4FS_FS is not set -# CONFIG_QNX6FS_FS is not set -# CONFIG_ROMFS_FS is not set -# CONFIG_PSTORE is not set -# CONFIG_SYSV_FS is not set -# CONFIG_UFS_FS is not set -# CONFIG_EROFS_FS is not set -CONFIG_NETWORK_FILESYSTEMS=y -CONFIG_NFS_FS=y -CONFIG_NFS_V2=y -CONFIG_NFS_V3=y -# CONFIG_NFS_V3_ACL is not set -CONFIG_NFS_V4=y -# CONFIG_NFS_SWAP is not set -CONFIG_NFS_V4_1=y -CONFIG_NFS_V4_2=y -CONFIG_PNFS_FILE_LAYOUT=y -CONFIG_PNFS_BLOCK=y -CONFIG_PNFS_FLEXFILE_LAYOUT=y -CONFIG_NFS_V4_1_IMPLEMENTATION_ID_DOMAIN="kernel.org" -# CONFIG_NFS_V4_1_MIGRATION is not set -CONFIG_NFS_V4_SECURITY_LABEL=y -CONFIG_ROOT_NFS=y -# CONFIG_NFS_USE_LEGACY_DNS is not set -CONFIG_NFS_USE_KERNEL_DNS=y -CONFIG_NFS_DISABLE_UDP_SUPPORT=y -# CONFIG_NFS_V4_2_READ_PLUS is not set -# CONFIG_NFSD is not set -CONFIG_GRACE_PERIOD=y -CONFIG_LOCKD=y -CONFIG_LOCKD_V4=y -CONFIG_NFS_COMMON=y -CONFIG_NFS_V4_2_SSC_HELPER=y -CONFIG_SUNRPC=y -CONFIG_SUNRPC_GSS=y -CONFIG_SUNRPC_BACKCHANNEL=y -CONFIG_RPCSEC_GSS_KRB5=y -# CONFIG_SUNRPC_DEBUG is not set -# CONFIG_CEPH_FS is not set -# CONFIG_CIFS is not set -# CONFIG_SMB_SERVER is not set -# CONFIG_CODA_FS is not set -# CONFIG_AFS_FS is not set -CONFIG_9P_FS=y -# CONFIG_9P_FS_POSIX_ACL is not set -# CONFIG_9P_FS_SECURITY is not set -CONFIG_NLS=y -CONFIG_NLS_DEFAULT="iso8859-1" -CONFIG_NLS_CODEPAGE_437=y -# CONFIG_NLS_CODEPAGE_737 is not set -# CONFIG_NLS_CODEPAGE_775 is not set -# CONFIG_NLS_CODEPAGE_850 is not set -# CONFIG_NLS_CODEPAGE_852 is not set -# CONFIG_NLS_CODEPAGE_855 is not set -# CONFIG_NLS_CODEPAGE_857 is not set -# CONFIG_NLS_CODEPAGE_860 is not set -# CONFIG_NLS_CODEPAGE_861 is not set -# CONFIG_NLS_CODEPAGE_862 is not set -# CONFIG_NLS_CODEPAGE_863 is not set -# CONFIG_NLS_CODEPAGE_864 is not set -# CONFIG_NLS_CODEPAGE_865 is not set -# CONFIG_NLS_CODEPAGE_866 is not set -# CONFIG_NLS_CODEPAGE_869 is not set -# CONFIG_NLS_CODEPAGE_936 is not set -# CONFIG_NLS_CODEPAGE_950 is not set -# CONFIG_NLS_CODEPAGE_932 is not set -# CONFIG_NLS_CODEPAGE_949 is not set -# CONFIG_NLS_CODEPAGE_874 is not set -# CONFIG_NLS_ISO8859_8 is not set -# CONFIG_NLS_CODEPAGE_1250 is not set -# CONFIG_NLS_CODEPAGE_1251 is not set -# CONFIG_NLS_ASCII is not set -CONFIG_NLS_ISO8859_1=y -# CONFIG_NLS_ISO8859_2 is not set -# CONFIG_NLS_ISO8859_3 is not set -# CONFIG_NLS_ISO8859_4 is not set -# CONFIG_NLS_ISO8859_5 is not set -# CONFIG_NLS_ISO8859_6 is not set -# CONFIG_NLS_ISO8859_7 is not set -# CONFIG_NLS_ISO8859_9 is not set -# CONFIG_NLS_ISO8859_13 is not set -# CONFIG_NLS_ISO8859_14 is not set -# CONFIG_NLS_ISO8859_15 is not set -# CONFIG_NLS_KOI8_R is not set -# CONFIG_NLS_KOI8_U is not set -# CONFIG_NLS_MAC_ROMAN is not set -# CONFIG_NLS_MAC_CELTIC is not set -# CONFIG_NLS_MAC_CENTEURO is not set -# CONFIG_NLS_MAC_CROATIAN is not set -# CONFIG_NLS_MAC_CYRILLIC is not set -# CONFIG_NLS_MAC_GAELIC is not set -# CONFIG_NLS_MAC_GREEK is not set -# CONFIG_NLS_MAC_ICELAND is not set -# CONFIG_NLS_MAC_INUIT is not set -# CONFIG_NLS_MAC_ROMANIAN is not set -# CONFIG_NLS_MAC_TURKISH is not set -# CONFIG_NLS_UTF8 is not set -# CONFIG_DLM is not set -# CONFIG_UNICODE is not set -CONFIG_IO_WQ=y -# end of File systems - -# -# Security options -# -CONFIG_KEYS=y -# CONFIG_KEYS_REQUEST_CACHE is not set -# CONFIG_PERSISTENT_KEYRINGS is not set -# CONFIG_TRUSTED_KEYS is not set -# CONFIG_ENCRYPTED_KEYS is not set -# CONFIG_KEY_DH_OPERATIONS is not set -# CONFIG_SECURITY_DMESG_RESTRICT is not set -CONFIG_SECURITY=y -CONFIG_SECURITYFS=y -CONFIG_SECURITY_NETWORK=y -# CONFIG_SECURITY_NETWORK_XFRM is not set -CONFIG_SECURITY_PATH=y -CONFIG_LSM_MMAP_MIN_ADDR=65536 -CONFIG_HAVE_HARDENED_USERCOPY_ALLOCATOR=y -# CONFIG_HARDENED_USERCOPY is not set -# CONFIG_FORTIFY_SOURCE is not set -# CONFIG_STATIC_USERMODEHELPER is not set -CONFIG_SECURITY_SELINUX=y -# CONFIG_SECURITY_SELINUX_BOOTPARAM is not set -CONFIG_SECURITY_SELINUX_DEVELOP=y -CONFIG_SECURITY_SELINUX_AVC_STATS=y -CONFIG_SECURITY_SELINUX_SIDTAB_HASH_BITS=9 -CONFIG_SECURITY_SELINUX_SID2STR_CACHE_SIZE=256 -# CONFIG_SECURITY_SMACK is not set -# CONFIG_SECURITY_TOMOYO is not set -CONFIG_SECURITY_APPARMOR=y -# CONFIG_SECURITY_APPARMOR_DEBUG is not set -CONFIG_SECURITY_APPARMOR_INTROSPECT_POLICY=y -CONFIG_SECURITY_APPARMOR_HASH=y -CONFIG_SECURITY_APPARMOR_HASH_DEFAULT=y -CONFIG_SECURITY_APPARMOR_EXPORT_BINARY=y -CONFIG_SECURITY_APPARMOR_PARANOID_LOAD=y -# CONFIG_SECURITY_LOADPIN is not set -# CONFIG_SECURITY_YAMA is not set -# CONFIG_SECURITY_SAFESETID is not set -# CONFIG_SECURITY_LOCKDOWN_LSM is not set -# CONFIG_SECURITY_LANDLOCK is not set -CONFIG_INTEGRITY=y -# CONFIG_INTEGRITY_SIGNATURE is not set -CONFIG_INTEGRITY_AUDIT=y -# CONFIG_IMA is not set -# CONFIG_EVM is not set -# CONFIG_DEFAULT_SECURITY_SELINUX is not set -# CONFIG_DEFAULT_SECURITY_APPARMOR is not set -CONFIG_DEFAULT_SECURITY_DAC=y -CONFIG_LSM="landlock,lockdown,yama,loadpin,safesetid,bpf" - -# -# Kernel hardening options -# - -# -# Memory initialization -# -CONFIG_INIT_STACK_NONE=y -# CONFIG_GCC_PLUGIN_STRUCTLEAK_USER is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF_ALL is not set -# CONFIG_INIT_ON_ALLOC_DEFAULT_ON is not set -# CONFIG_INIT_ON_FREE_DEFAULT_ON is not set -CONFIG_CC_HAS_ZERO_CALL_USED_REGS=y -# CONFIG_ZERO_CALL_USED_REGS is not set -# end of Memory initialization - -CONFIG_RANDSTRUCT_NONE=y -# CONFIG_RANDSTRUCT_FULL is not set -# CONFIG_RANDSTRUCT_PERFORMANCE is not set -# end of Kernel hardening options -# end of Security options - -CONFIG_XOR_BLOCKS=m -CONFIG_CRYPTO=y - -# -# Crypto core or helper -# -CONFIG_CRYPTO_ALGAPI=y -CONFIG_CRYPTO_ALGAPI2=y -CONFIG_CRYPTO_AEAD=y -CONFIG_CRYPTO_AEAD2=y -CONFIG_CRYPTO_SKCIPHER=y -CONFIG_CRYPTO_SKCIPHER2=y -CONFIG_CRYPTO_HASH=y -CONFIG_CRYPTO_HASH2=y -CONFIG_CRYPTO_RNG=m -CONFIG_CRYPTO_RNG2=y -CONFIG_CRYPTO_RNG_DEFAULT=m -CONFIG_CRYPTO_AKCIPHER2=y -CONFIG_CRYPTO_AKCIPHER=y -CONFIG_CRYPTO_KPP2=y -CONFIG_CRYPTO_ACOMP2=y -CONFIG_CRYPTO_MANAGER=y -CONFIG_CRYPTO_MANAGER2=y -# CONFIG_CRYPTO_USER is not set -CONFIG_CRYPTO_MANAGER_DISABLE_TESTS=y -CONFIG_CRYPTO_NULL=m -CONFIG_CRYPTO_NULL2=y -# CONFIG_CRYPTO_PCRYPT is not set -# CONFIG_CRYPTO_CRYPTD is not set -CONFIG_CRYPTO_AUTHENC=m -# CONFIG_CRYPTO_TEST is not set -CONFIG_CRYPTO_ENGINE=y -# end of Crypto core or helper - -# -# Public-key cryptography -# -CONFIG_CRYPTO_RSA=y -# CONFIG_CRYPTO_DH is not set -# CONFIG_CRYPTO_ECDH is not set -# CONFIG_CRYPTO_ECDSA is not set -# CONFIG_CRYPTO_ECRDSA is not set -# CONFIG_CRYPTO_SM2 is not set -# CONFIG_CRYPTO_CURVE25519 is not set -# end of Public-key cryptography - -# -# Block ciphers -# -CONFIG_CRYPTO_AES=m -# CONFIG_CRYPTO_AES_TI is not set -# CONFIG_CRYPTO_ANUBIS is not set -# CONFIG_CRYPTO_ARIA is not set -# CONFIG_CRYPTO_BLOWFISH is not set -# CONFIG_CRYPTO_CAMELLIA is not set -# CONFIG_CRYPTO_CAST5 is not set -# CONFIG_CRYPTO_CAST6 is not set -# CONFIG_CRYPTO_DES is not set -# CONFIG_CRYPTO_FCRYPT is not set -# CONFIG_CRYPTO_KHAZAD is not set -# CONFIG_CRYPTO_SEED is not set -# CONFIG_CRYPTO_SERPENT is not set -# CONFIG_CRYPTO_SM4_GENERIC is not set -# CONFIG_CRYPTO_TEA is not set -# CONFIG_CRYPTO_TWOFISH is not set -# end of Block ciphers - -# -# Length-preserving ciphers and modes -# -# CONFIG_CRYPTO_ADIANTUM is not set -# CONFIG_CRYPTO_ARC4 is not set -# CONFIG_CRYPTO_CHACHA20 is not set -CONFIG_CRYPTO_CBC=m -# CONFIG_CRYPTO_CFB is not set -CONFIG_CRYPTO_CTR=m -# CONFIG_CRYPTO_CTS is not set -# CONFIG_CRYPTO_ECB is not set -# CONFIG_CRYPTO_HCTR2 is not set -# CONFIG_CRYPTO_KEYWRAP is not set -# CONFIG_CRYPTO_LRW is not set -# CONFIG_CRYPTO_OFB is not set -# CONFIG_CRYPTO_PCBC is not set -# CONFIG_CRYPTO_XTS is not set -# end of Length-preserving ciphers and modes - -# -# AEAD (authenticated encryption with associated data) ciphers -# -# CONFIG_CRYPTO_AEGIS128 is not set -# CONFIG_CRYPTO_CHACHA20POLY1305 is not set -# CONFIG_CRYPTO_CCM is not set -CONFIG_CRYPTO_GCM=m -CONFIG_CRYPTO_SEQIV=m -CONFIG_CRYPTO_ECHAINIV=m -# CONFIG_CRYPTO_ESSIV is not set -# end of AEAD (authenticated encryption with associated data) ciphers - -# -# Hashes, digests, and MACs -# -CONFIG_CRYPTO_BLAKE2B=m -# CONFIG_CRYPTO_CMAC is not set -CONFIG_CRYPTO_GHASH=m -CONFIG_CRYPTO_HMAC=m -# CONFIG_CRYPTO_MD4 is not set -# CONFIG_CRYPTO_MD5 is not set -# CONFIG_CRYPTO_MICHAEL_MIC is not set -# CONFIG_CRYPTO_POLY1305 is not set -# CONFIG_CRYPTO_RMD160 is not set -CONFIG_CRYPTO_SHA1=y -CONFIG_CRYPTO_SHA256=m -CONFIG_CRYPTO_SHA512=m -# CONFIG_CRYPTO_SHA3 is not set -# CONFIG_CRYPTO_SM3_GENERIC is not set -# CONFIG_CRYPTO_STREEBOG is not set -# CONFIG_CRYPTO_VMAC is not set -# CONFIG_CRYPTO_WP512 is not set -# CONFIG_CRYPTO_XCBC is not set -CONFIG_CRYPTO_XXHASH=m -# end of Hashes, digests, and MACs - -# -# CRCs (cyclic redundancy checks) -# -CONFIG_CRYPTO_CRC32C=y -# CONFIG_CRYPTO_CRC32 is not set -# CONFIG_CRYPTO_CRCT10DIF is not set -# end of CRCs (cyclic redundancy checks) - -# -# Compression -# -# CONFIG_CRYPTO_DEFLATE is not set -# CONFIG_CRYPTO_LZO is not set -# CONFIG_CRYPTO_842 is not set -# CONFIG_CRYPTO_LZ4 is not set -# CONFIG_CRYPTO_LZ4HC is not set -# CONFIG_CRYPTO_ZSTD is not set -# end of Compression - -# -# Random number generation -# -# CONFIG_CRYPTO_ANSI_CPRNG is not set -CONFIG_CRYPTO_DRBG_MENU=m -CONFIG_CRYPTO_DRBG_HMAC=y -# CONFIG_CRYPTO_DRBG_HASH is not set -# CONFIG_CRYPTO_DRBG_CTR is not set -CONFIG_CRYPTO_DRBG=m -CONFIG_CRYPTO_JITTERENTROPY=m -# end of Random number generation - -# -# Userspace interface -# -CONFIG_CRYPTO_USER_API=y -CONFIG_CRYPTO_USER_API_HASH=y -# CONFIG_CRYPTO_USER_API_SKCIPHER is not set -# CONFIG_CRYPTO_USER_API_RNG is not set -# CONFIG_CRYPTO_USER_API_AEAD is not set -CONFIG_CRYPTO_USER_API_ENABLE_OBSOLETE=y -# end of Userspace interface - -CONFIG_CRYPTO_HW=y -CONFIG_CRYPTO_DEV_ALLWINNER=y -# CONFIG_CRYPTO_DEV_SUN4I_SS is not set -# CONFIG_CRYPTO_DEV_SUN8I_CE is not set -# CONFIG_CRYPTO_DEV_SUN8I_SS is not set -# CONFIG_CRYPTO_DEV_ATMEL_ECC is not set -# CONFIG_CRYPTO_DEV_ATMEL_SHA204A is not set -# CONFIG_CRYPTO_DEV_NITROX_CNN55XX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCC is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXX is not set -# CONFIG_CRYPTO_DEV_QAT_C62X is not set -# CONFIG_CRYPTO_DEV_QAT_4XXX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCCVF is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXXVF is not set -# CONFIG_CRYPTO_DEV_QAT_C62XVF is not set -CONFIG_CRYPTO_DEV_VIRTIO=y -# CONFIG_CRYPTO_DEV_SAFEXCEL is not set -# CONFIG_CRYPTO_DEV_CCREE is not set -# CONFIG_CRYPTO_DEV_AMLOGIC_GXL is not set -# CONFIG_ASYMMETRIC_KEY_TYPE is not set - -# -# Certificates for signature checking -# -# CONFIG_SYSTEM_BLACKLIST_KEYRING is not set -# end of Certificates for signature checking - -CONFIG_BINARY_PRINTF=y - -# -# Library routines -# -CONFIG_RAID6_PQ=m -CONFIG_RAID6_PQ_BENCHMARK=y -CONFIG_LINEAR_RANGES=y -# CONFIG_PACKING is not set -CONFIG_BITREVERSE=y -CONFIG_GENERIC_STRNCPY_FROM_USER=y -CONFIG_GENERIC_STRNLEN_USER=y -CONFIG_GENERIC_NET_UTILS=y -# CONFIG_CORDIC is not set -# CONFIG_PRIME_NUMBERS is not set -CONFIG_RATIONAL=y -CONFIG_GENERIC_PCI_IOMAP=y - -# -# Crypto library routines -# -CONFIG_CRYPTO_LIB_UTILS=y -CONFIG_CRYPTO_LIB_AES=m -CONFIG_CRYPTO_LIB_GF128MUL=m -CONFIG_CRYPTO_LIB_BLAKE2S_GENERIC=y -# CONFIG_CRYPTO_LIB_CHACHA is not set -# CONFIG_CRYPTO_LIB_CURVE25519 is not set -CONFIG_CRYPTO_LIB_POLY1305_RSIZE=1 -# CONFIG_CRYPTO_LIB_POLY1305 is not set -# CONFIG_CRYPTO_LIB_CHACHA20POLY1305 is not set -CONFIG_CRYPTO_LIB_SHA1=y -CONFIG_CRYPTO_LIB_SHA256=m -# end of Crypto library routines - -CONFIG_CRC_CCITT=m -CONFIG_CRC16=y -# CONFIG_CRC_T10DIF is not set -# CONFIG_CRC64_ROCKSOFT is not set -CONFIG_CRC_ITU_T=y -CONFIG_CRC32=y -# CONFIG_CRC32_SELFTEST is not set -CONFIG_CRC32_SLICEBY8=y -# CONFIG_CRC32_SLICEBY4 is not set -# CONFIG_CRC32_SARWATE is not set -# CONFIG_CRC32_BIT is not set -# CONFIG_CRC64 is not set -# CONFIG_CRC4 is not set -CONFIG_CRC7=y -CONFIG_LIBCRC32C=m -# CONFIG_CRC8 is not set -CONFIG_XXHASH=y -CONFIG_AUDIT_GENERIC=y -# CONFIG_RANDOM32_SELFTEST is not set -CONFIG_ZLIB_INFLATE=y -CONFIG_ZLIB_DEFLATE=m -CONFIG_LZO_COMPRESS=m -CONFIG_LZO_DECOMPRESS=y -CONFIG_LZ4_DECOMPRESS=y -CONFIG_ZSTD_COMMON=y -CONFIG_ZSTD_COMPRESS=y -CONFIG_ZSTD_DECOMPRESS=y -CONFIG_XZ_DEC=y -CONFIG_XZ_DEC_X86=y -CONFIG_XZ_DEC_POWERPC=y -CONFIG_XZ_DEC_IA64=y -CONFIG_XZ_DEC_ARM=y -CONFIG_XZ_DEC_ARMTHUMB=y -CONFIG_XZ_DEC_SPARC=y -# CONFIG_XZ_DEC_MICROLZMA is not set -CONFIG_XZ_DEC_BCJ=y -# CONFIG_XZ_DEC_TEST is not set -CONFIG_DECOMPRESS_GZIP=y -CONFIG_DECOMPRESS_BZIP2=y -CONFIG_DECOMPRESS_LZMA=y -CONFIG_DECOMPRESS_XZ=y -CONFIG_DECOMPRESS_LZO=y -CONFIG_DECOMPRESS_LZ4=y -CONFIG_DECOMPRESS_ZSTD=y -CONFIG_GENERIC_ALLOCATOR=y -CONFIG_INTERVAL_TREE=y -CONFIG_ASSOCIATIVE_ARRAY=y -CONFIG_HAS_IOMEM=y -CONFIG_HAS_IOPORT=y -CONFIG_HAS_IOPORT_MAP=y -CONFIG_HAS_DMA=y -CONFIG_NEED_DMA_MAP_STATE=y -CONFIG_ARCH_DMA_ADDR_T_64BIT=y -CONFIG_DMA_DECLARE_COHERENT=y -CONFIG_ARCH_HAS_SETUP_DMA_OPS=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_DEVICE=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_CPU=y -CONFIG_ARCH_HAS_DMA_PREP_COHERENT=y -CONFIG_ARCH_DMA_DEFAULT_COHERENT=y -CONFIG_SWIOTLB=y -# CONFIG_DMA_RESTRICTED_POOL is not set -CONFIG_DMA_NONCOHERENT_MMAP=y -CONFIG_DMA_COHERENT_POOL=y -CONFIG_DMA_DIRECT_REMAP=y -# CONFIG_DMA_API_DEBUG is not set -# CONFIG_DMA_MAP_BENCHMARK is not set -CONFIG_SGL_ALLOC=y -# CONFIG_CPUMASK_OFFSTACK is not set -# CONFIG_FORCE_NR_CPUS is not set -CONFIG_CPU_RMAP=y -CONFIG_DQL=y -CONFIG_GLOB=y -# CONFIG_GLOB_SELFTEST is not set -CONFIG_NLATTR=y -CONFIG_CLZ_TAB=y -# CONFIG_IRQ_POLL is not set -CONFIG_MPILIB=y -CONFIG_LIBFDT=y -CONFIG_OID_REGISTRY=y -CONFIG_UCS2_STRING=y -CONFIG_HAVE_GENERIC_VDSO=y -CONFIG_GENERIC_GETTIMEOFDAY=y -CONFIG_GENERIC_VDSO_TIME_NS=y -CONFIG_FONT_SUPPORT=y -# CONFIG_FONTS is not set -CONFIG_FONT_8x8=y -CONFIG_FONT_8x16=y -CONFIG_SG_POOL=y -CONFIG_ARCH_HAS_PMEM_API=y -CONFIG_MEMREGION=y -CONFIG_ARCH_STACKWALK=y -CONFIG_STACKDEPOT=y -CONFIG_SBITMAP=y -# end of Library routines - -CONFIG_GENERIC_IOREMAP=y -CONFIG_GENERIC_LIB_DEVMEM_IS_ALLOWED=y - -# -# Kernel hacking -# - -# -# printk and dmesg options -# -CONFIG_PRINTK_TIME=y -# CONFIG_PRINTK_CALLER is not set -# CONFIG_STACKTRACE_BUILD_ID is not set -CONFIG_CONSOLE_LOGLEVEL_DEFAULT=7 -CONFIG_CONSOLE_LOGLEVEL_QUIET=4 -CONFIG_MESSAGE_LOGLEVEL_DEFAULT=4 -# CONFIG_BOOT_PRINTK_DELAY is not set -# CONFIG_DYNAMIC_DEBUG is not set -# CONFIG_DYNAMIC_DEBUG_CORE is not set -CONFIG_SYMBOLIC_ERRNAME=y -CONFIG_DEBUG_BUGVERBOSE=y -# end of printk and dmesg options - -CONFIG_DEBUG_KERNEL=y -CONFIG_DEBUG_MISC=y - -# -# Compile-time checks and compiler options -# -CONFIG_DEBUG_INFO_NONE=y -# CONFIG_DEBUG_INFO_DWARF_TOOLCHAIN_DEFAULT is not set -# CONFIG_DEBUG_INFO_DWARF4 is not set -# CONFIG_DEBUG_INFO_DWARF5 is not set -CONFIG_FRAME_WARN=2048 -# CONFIG_STRIP_ASM_SYMS is not set -# CONFIG_READABLE_ASM is not set -# CONFIG_HEADERS_INSTALL is not set -# CONFIG_DEBUG_SECTION_MISMATCH is not set -CONFIG_SECTION_MISMATCH_WARN_ONLY=y -CONFIG_ARCH_WANT_FRAME_POINTERS=y -CONFIG_FRAME_POINTER=y -# CONFIG_VMLINUX_MAP is not set -# CONFIG_DEBUG_FORCE_WEAK_PER_CPU is not set -# end of Compile-time checks and compiler options - -# -# Generic Kernel Debugging Instruments -# -# CONFIG_MAGIC_SYSRQ is not set -CONFIG_DEBUG_FS=y -CONFIG_DEBUG_FS_ALLOW_ALL=y -# CONFIG_DEBUG_FS_DISALLOW_MOUNT is not set -# CONFIG_DEBUG_FS_ALLOW_NONE is not set -CONFIG_HAVE_ARCH_KGDB=y -CONFIG_HAVE_ARCH_KGDB_QXFER_PKT=y -# CONFIG_KGDB is not set -CONFIG_ARCH_HAS_UBSAN_SANITIZE_ALL=y -# CONFIG_UBSAN is not set -CONFIG_HAVE_KCSAN_COMPILER=y -# end of Generic Kernel Debugging Instruments - -# -# Networking Debugging -# -# CONFIG_NET_DEV_REFCNT_TRACKER is not set -# CONFIG_NET_NS_REFCNT_TRACKER is not set -# CONFIG_DEBUG_NET is not set -# end of Networking Debugging - -# -# Memory Debugging -# -# CONFIG_PAGE_EXTENSION is not set -CONFIG_DEBUG_PAGEALLOC=y -# CONFIG_DEBUG_PAGEALLOC_ENABLE_DEFAULT is not set -CONFIG_SLUB_DEBUG=y -# CONFIG_SLUB_DEBUG_ON is not set -# CONFIG_PAGE_OWNER is not set -# CONFIG_PAGE_POISONING is not set -# CONFIG_DEBUG_RODATA_TEST is not set -CONFIG_ARCH_HAS_DEBUG_WX=y -# CONFIG_DEBUG_WX is not set -CONFIG_GENERIC_PTDUMP=y -# CONFIG_PTDUMP_DEBUGFS is not set -CONFIG_HAVE_DEBUG_KMEMLEAK=y -# CONFIG_DEBUG_KMEMLEAK is not set -# CONFIG_DEBUG_OBJECTS is not set -# CONFIG_SHRINKER_DEBUG is not set -# CONFIG_DEBUG_STACK_USAGE is not set -CONFIG_SCHED_STACK_END_CHECK=y -CONFIG_ARCH_HAS_DEBUG_VM_PGTABLE=y -CONFIG_DEBUG_VM_IRQSOFF=y -CONFIG_DEBUG_VM=y -# CONFIG_DEBUG_VM_MAPLE_TREE is not set -# CONFIG_DEBUG_VM_RB is not set -CONFIG_DEBUG_VM_PGFLAGS=y -CONFIG_DEBUG_VM_PGTABLE=y -CONFIG_ARCH_HAS_DEBUG_VIRTUAL=y -# CONFIG_DEBUG_VIRTUAL is not set -CONFIG_DEBUG_MEMORY_INIT=y -CONFIG_DEBUG_PER_CPU_MAPS=y -CONFIG_HAVE_ARCH_KASAN=y -CONFIG_HAVE_ARCH_KASAN_VMALLOC=y -CONFIG_CC_HAS_KASAN_GENERIC=y -CONFIG_CC_HAS_WORKING_NOSANITIZE_ADDRESS=y -# CONFIG_KASAN is not set -CONFIG_HAVE_ARCH_KFENCE=y -# CONFIG_KFENCE is not set -# end of Memory Debugging - -# CONFIG_DEBUG_SHIRQ is not set - -# -# Debug Oops, Lockups and Hangs -# -# CONFIG_PANIC_ON_OOPS is not set -CONFIG_PANIC_ON_OOPS_VALUE=0 -CONFIG_PANIC_TIMEOUT=0 -CONFIG_LOCKUP_DETECTOR=y -CONFIG_SOFTLOCKUP_DETECTOR=y -# CONFIG_BOOTPARAM_SOFTLOCKUP_PANIC is not set -CONFIG_DETECT_HUNG_TASK=y -CONFIG_DEFAULT_HUNG_TASK_TIMEOUT=120 -# CONFIG_BOOTPARAM_HUNG_TASK_PANIC is not set -CONFIG_WQ_WATCHDOG=y -# CONFIG_TEST_LOCKUP is not set -# end of Debug Oops, Lockups and Hangs - -# -# Scheduler Debugging -# -CONFIG_SCHED_DEBUG=y -# CONFIG_SCHEDSTATS is not set -# end of Scheduler Debugging - -CONFIG_DEBUG_TIMEKEEPING=y - -# -# Lock Debugging (spinlocks, mutexes, etc...) -# -CONFIG_LOCK_DEBUGGING_SUPPORT=y -# CONFIG_PROVE_LOCKING is not set -# CONFIG_LOCK_STAT is not set -CONFIG_DEBUG_RT_MUTEXES=y -CONFIG_DEBUG_SPINLOCK=y -CONFIG_DEBUG_MUTEXES=y -# CONFIG_DEBUG_WW_MUTEX_SLOWPATH is not set -CONFIG_DEBUG_RWSEMS=y -# CONFIG_DEBUG_LOCK_ALLOC is not set -CONFIG_DEBUG_ATOMIC_SLEEP=y -# CONFIG_DEBUG_LOCKING_API_SELFTESTS is not set -# CONFIG_LOCK_TORTURE_TEST is not set -# CONFIG_WW_MUTEX_SELFTEST is not set -# CONFIG_SCF_TORTURE_TEST is not set -# CONFIG_CSD_LOCK_WAIT_DEBUG is not set -# end of Lock Debugging (spinlocks, mutexes, etc...) - -# CONFIG_DEBUG_IRQFLAGS is not set -CONFIG_STACKTRACE=y -# CONFIG_WARN_ALL_UNSEEDED_RANDOM is not set -# CONFIG_DEBUG_KOBJECT is not set - -# -# Debug kernel data structures -# -CONFIG_DEBUG_LIST=y -CONFIG_DEBUG_PLIST=y -CONFIG_DEBUG_SG=y -# CONFIG_DEBUG_NOTIFIERS is not set -# CONFIG_BUG_ON_DATA_CORRUPTION is not set -# CONFIG_DEBUG_MAPLE_TREE is not set -# end of Debug kernel data structures - -# CONFIG_DEBUG_CREDENTIALS is not set - -# -# RCU Debugging -# -# CONFIG_RCU_SCALE_TEST is not set -# CONFIG_RCU_TORTURE_TEST is not set -# CONFIG_RCU_REF_SCALE_TEST is not set -CONFIG_RCU_CPU_STALL_TIMEOUT=21 -CONFIG_RCU_EXP_CPU_STALL_TIMEOUT=0 -# CONFIG_RCU_CPU_STALL_CPUTIME is not set -# CONFIG_RCU_TRACE is not set -CONFIG_RCU_EQS_DEBUG=y -# end of RCU Debugging - -# CONFIG_DEBUG_WQ_FORCE_RR_CPU is not set -# CONFIG_CPU_HOTPLUG_STATE_CONTROL is not set -# CONFIG_LATENCYTOP is not set -CONFIG_HAVE_RETHOOK=y -CONFIG_HAVE_FUNCTION_TRACER=y -CONFIG_HAVE_FUNCTION_GRAPH_TRACER=y -CONFIG_HAVE_DYNAMIC_FTRACE=y -CONFIG_HAVE_DYNAMIC_FTRACE_WITH_REGS=y -CONFIG_HAVE_FTRACE_MCOUNT_RECORD=y -CONFIG_HAVE_SYSCALL_TRACEPOINTS=y -CONFIG_TRACING_SUPPORT=y -# CONFIG_FTRACE is not set -# CONFIG_SAMPLES is not set -# CONFIG_STRICT_DEVMEM is not set - -# -# riscv Debugging -# -# end of riscv Debugging - -# -# Kernel Testing and Coverage -# -# CONFIG_KUNIT is not set -# CONFIG_NOTIFIER_ERROR_INJECTION is not set -# CONFIG_FAULT_INJECTION is not set -CONFIG_ARCH_HAS_KCOV=y -CONFIG_CC_HAS_SANCOV_TRACE_PC=y -# CONFIG_KCOV is not set -# CONFIG_RUNTIME_TESTING_MENU is not set -CONFIG_ARCH_USE_MEMTEST=y -CONFIG_MEMTEST=y -# end of Kernel Testing and Coverage - -# -# Rust hacking -# -# end of Rust hacking -# end of Kernel hacking diff --git a/patches/linux/linux-6.4.y/dts/mpfs-beaglev-fire-fabric.dtsi b/patches/linux/linux-6.4.y/dts/mpfs-beaglev-fire-fabric.dtsi deleted file mode 100644 index 1069134..0000000 --- a/patches/linux/linux-6.4.y/dts/mpfs-beaglev-fire-fabric.dtsi +++ /dev/null @@ -1,71 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/ { - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs-icicle-kit", - "microchip,mpfs"; - - core_pwm0: pwm@40000000 { - compatible = "microchip,corepwm-rtl-v4"; - reg = <0x0 0x40000000 0x0 0xF0>; - microchip,sync-update-mask = /bits/ 32 <0>; - #pwm-cells = <3>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - status = "disabled"; - }; - - i2c2: i2c@40000200 { - compatible = "microchip,corei2c-rtl-v7"; - reg = <0x0 0x40000200 0x0 0x100>; - #address-cells = <1>; - #size-cells = <0>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - interrupt-parent = <&plic>; - interrupts = <122>; - clock-frequency = <100000>; - status = "disabled"; - }; - - pcie: pcie@3000000000 { - compatible = "microchip,pcie-host-1.0"; - #address-cells = <0x3>; - #interrupt-cells = <0x1>; - #size-cells = <0x2>; - device_type = "pci"; - reg = <0x30 0x0 0x0 0x8000000>, <0x0 0x43000000 0x0 0x10000>; - reg-names = "cfg", "apb"; - bus-range = <0x0 0x7f>; - interrupt-parent = <&plic>; - interrupts = <119>; - interrupt-map = <0 0 0 1 &pcie_intc 0>, - <0 0 0 2 &pcie_intc 1>, - <0 0 0 3 &pcie_intc 2>, - <0 0 0 4 &pcie_intc 3>; - interrupt-map-mask = <0 0 0 7>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT1>, <&ccc_nw CLK_CCC_PLL0_OUT3>; - clock-names = "fic1", "fic3"; - ranges = <0x3000000 0x0 0x8000000 0x30 0x8000000 0x0 0x80000000>; - dma-ranges = <0x02000000 0x0 0x00000000 0x0 0x00000000 0x1 0x00000000>; - msi-parent = <&pcie>; - msi-controller; - status = "disabled"; - pcie_intc: interrupt-controller { - #address-cells = <0>; - #interrupt-cells = <1>; - interrupt-controller; - }; - }; - - refclk_ccc: cccrefclk { - compatible = "fixed-clock"; - #clock-cells = <0>; - }; -}; - -&ccc_nw { - clocks = <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, - <&refclk_ccc>, <&refclk_ccc>; - clock-names = "pll0_ref0", "pll0_ref1", "pll1_ref0", "pll1_ref1", - "dll0_ref", "dll1_ref"; - status = "okay"; -}; diff --git a/patches/linux/linux-6.4.y/dts/mpfs-beaglev-fire.dts b/patches/linux/linux-6.4.y/dts/mpfs-beaglev-fire.dts deleted file mode 100644 index c811d50..0000000 --- a/patches/linux/linux-6.4.y/dts/mpfs-beaglev-fire.dts +++ /dev/null @@ -1,323 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/dts-v1/; - -#include "mpfs.dtsi" -#include "mpfs-beaglev-fire-fabric.dtsi" -#include -#include - -/* Clock frequency (in Hz) of the rtcclk */ -#define RTCCLK_FREQ 1000000 - -/ { - #address-cells = <2>; - #size-cells = <2>; - model = "BeagleBoard BeagleV-Fire"; - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs"; - - aliases { - mmc0 = &mmc; - ethernet0 = &mac1; - serial0 = &mmuart0; - serial1 = &mmuart1; - serial2 = &mmuart2; - serial3 = &mmuart3; - serial4 = &mmuart4; - }; - - chosen { - stdout-path = "serial0:115200n8"; - }; - - cpus { - timebase-frequency = ; - }; - - ddrc_cache_lo: memory@80000000 { - device_type = "memory"; - reg = <0x0 0x80000000 0x0 0x40000000>; - status = "okay"; - }; - - ddrc_cache_hi: memory@1040000000 { - device_type = "memory"; - reg = <0x10 0x40000000 0x0 0x40000000>; - status = "okay"; - }; - - reserved-memory { - #address-cells = <2>; - #size-cells = <2>; - ranges; - - hss_payload: region@BFC00000 { - reg = <0x0 0xBFC00000 0x0 0x400000>; - no-map; - }; - }; - - imx219_vana: fixedregulator@0 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vana"; - regulator-min-microvolt = <2800000>; - regulator-max-microvolt = <2800000>; - }; - imx219_vdig: fixedregulator@1 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vdig"; - regulator-min-microvolt = <1800000>; - regulator-max-microvolt = <1800000>; - }; - imx219_vddl: fixedregulator@2 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vddl"; - regulator-min-microvolt = <1200000>; - regulator-max-microvolt = <1200000>; - }; - - imx219_clk: camera-clk { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <24000000>; - }; -}; - -&gpio0 { - ngpios=<14>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", "", "", "SD_CARD_CS", "USER_BUTTON"; - status = "okay"; - - sd_card_cs { - gpio-hog; - gpios = <12 12>; - output_high; - line-name = "SD_CARD_CS"; - }; - - user_button { - gpio-hog; - gpios = <13 13>; - input; - line-name = "USER_BUTTON"; - }; -}; - -&gpio1 { - ngpios=<24>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", - "", "", "", "", "", "", "", "", "", "", - "ADC_IRQn", "", "", "USB_OCn"; - status = "okay"; - - adc_irqn { - gpio-hog; - gpios = <20 20>; - input; - line-name = "ADC_IRQn"; - }; - - user_button { - gpio-hog; - gpios = <23 23>; - input; - line-name = "USB_OCn"; - }; - -}; - -&gpio2 { - interrupts = <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>; - gpio-line-names = "P8_PIN3_USER_LED_0", "P8_PIN4_USER_LED_1", "P8_PIN5_USER_LED_2", - "P8_PIN6_USER_LED_3", "P8_PIN7_USER_LED_4", "P8_PIN8_USER_LED_5", - "P8_PIN9_USER_LED_6", "P8_PIN10_USER_LED_7", "P8_PIN11_USER_LED_8", - "P8_PIN12_USER_LED_9", "P8_PIN13_USER_LED_10", "P8_PIN14_USER_LED_11", - "P8_PIN15", "P8_PIN16", "P8_PIN17", "P8_PIN18", "P8_PIN19", - "P8_PIN20", "P8_PIN21", "P8_PIN22", "P8_PIN23", "P8_PIN24", - "P8_PIN25", "P8_PIN26", "P8_PIN27", "P8_PIN28", "P8_PIN29", - "P8_PIN30", - "M2_W_DISABLE1", "M2_W_DISABLE2", - "VIO_ENABLE", "SD_DET"; - status = "okay"; - - vio_enable { - gpio-hog; - gpios = <30 30>; - output_high; - line-name = "VIO_ENABLE"; - }; - - sd_det { - gpio-hog; - gpios = <31 31>; - input; - line-name = "SD_DET"; - }; -}; - -&i2c0 { - status = "okay"; -}; - -&i2c1 { - status = "okay"; - eeprom: eeprom@50 { - compatible = "at,24c32"; - reg = <0x50>; - }; - - imx219: sensor@10 { - compatible = "sony,imx219"; - reg = <0x10>; - clocks = <&imx219_clk>; - VANA-supply = <&imx219_vana>; /* 2.8v */ - VDIG-supply = <&imx219_vdig>; /* 1.8v */ - VDDL-supply = <&imx219_vddl>; /* 1.2v */ - - port { - imx219_0: endpoint { -// remote-endpoint = <&csi1_ep>; - data-lanes = <1 2>; - clock-noncontinuous; - link-frequencies = /bits/ 64 <456000000>; - }; - }; - }; -}; - -&mac0 { - phy-mode = "sgmii"; - phy-handle = <&phy0>; - status = "okay"; - - phy0: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mac1 { - phy-mode = "sgmii"; - phy-handle = <&phy1>; - status = "okay"; - - phy1: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mbox { - status = "okay"; -}; - -//&mmc { -// status = "okay"; -// bus-width = <8>; -// disable-wp; -// cap-mmc-highspeed; -// mmc-ddr-1_8v; -// mmc-hs200-1_8v; -//}; - -&mmc { - //dma-noncoherent; - bus-width = <4>; - disable-wp; - cap-sd-highspeed; - cap-mmc-highspeed; - mmc-ddr-1_8v; - mmc-hs200-1_8v; - sd-uhs-sdr12; - sd-uhs-sdr25; - sd-uhs-sdr50; - sd-uhs-sdr104; - status = "okay"; -}; - - -&mmuart0 { - status = "okay"; -}; - -&mmuart1 { - status = "okay"; -}; - -//&mmuart2 { -// status = "okay"; -//}; - -//&mmuart3 //{ -// statu//s = "okay"; -//};// -// -//&mmuart4 { -// status = "okay"; -//}; - -//&pcie { -// status = "okay"; -//}; - -&qspi { - status = "okay"; - cs-gpios = <&gpio1 17 GPIO_ACTIVE_LOW>, <&gpio0 12 GPIO_ACTIVE_LOW>; - num-cs = <2>; - - - mcp3464: mcp3464@0 { - compatible = "microchip,mcp3464r"; - reg = <0>; /* CE0 */ - spi-cpol; - spi-cpha; - spi-max-frequency = <15000000>; - status = "okay"; - microchip,hw-device-address = <1>; - }; - - mmc-slot@1 { - compatible = "mmc-spi-slot"; - reg = <1>; - gpios = <&gpio2 31 1>; - voltage-ranges = <3300 3300>; - spi-max-frequency = <15000000>; - disable-wp; - }; -}; - -&refclk { - clock-frequency = <125000000>; -}; - -&refclk_ccc { - clock-frequency = <50000000>; -}; - -&rtc { - status = "okay"; -}; - -&spi0 { - status = "okay"; -}; - -&spi1 { - status = "okay"; -}; - -&syscontroller { - status = "okay"; -}; - -&usb { - //dma-noncoherent; - status = "okay"; - dr_mode = "otg"; -}; diff --git a/patches/linux/mainline/Makefile b/patches/linux/mainline/Makefile deleted file mode 100644 index 65af281..0000000 --- a/patches/linux/mainline/Makefile +++ /dev/null @@ -1,8 +0,0 @@ -# SPDX-License-Identifier: GPL-2.0 -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-icicle-kit.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-m100pfsevp.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-polarberry.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-sev-kit.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-tysom-m.dtb -dtb-$(CONFIG_ARCH_MICROCHIP_POLARFIRE) += mpfs-beaglev-fire.dtb -obj-$(CONFIG_BUILTIN_DTB) += $(addsuffix .o, $(dtb-y)) diff --git a/patches/linux/mainline/defconfig b/patches/linux/mainline/defconfig deleted file mode 100644 index 1533f40..0000000 --- a/patches/linux/mainline/defconfig +++ /dev/null @@ -1,5679 +0,0 @@ -# -# Automatically generated file; DO NOT EDIT. -# Linux/riscv 6.5.0-rc6 Kernel Configuration -# -CONFIG_CC_VERSION_TEXT="riscv64-linux-gcc (GCC) 11.4.0" -CONFIG_CC_IS_GCC=y -CONFIG_GCC_VERSION=110400 -CONFIG_CLANG_VERSION=0 -CONFIG_AS_IS_GNU=y -CONFIG_AS_VERSION=24000 -CONFIG_LD_IS_BFD=y -CONFIG_LD_VERSION=24000 -CONFIG_LLD_VERSION=0 -CONFIG_CC_HAS_ASM_GOTO_OUTPUT=y -CONFIG_CC_HAS_ASM_GOTO_TIED_OUTPUT=y -CONFIG_CC_HAS_ASM_INLINE=y -CONFIG_CC_HAS_NO_PROFILE_FN_ATTR=y -CONFIG_PAHOLE_VERSION=0 -CONFIG_IRQ_WORK=y -CONFIG_BUILDTIME_TABLE_SORT=y -CONFIG_THREAD_INFO_IN_TASK=y - -# -# General setup -# -CONFIG_INIT_ENV_ARG_LIMIT=32 -# CONFIG_COMPILE_TEST is not set -# CONFIG_WERROR is not set -CONFIG_LOCALVERSION="" -CONFIG_LOCALVERSION_AUTO=y -CONFIG_BUILD_SALT="" -CONFIG_DEFAULT_INIT="" -CONFIG_DEFAULT_HOSTNAME="(none)" -CONFIG_SYSVIPC=y -CONFIG_SYSVIPC_SYSCTL=y -CONFIG_SYSVIPC_COMPAT=y -CONFIG_POSIX_MQUEUE=y -CONFIG_POSIX_MQUEUE_SYSCTL=y -# CONFIG_WATCH_QUEUE is not set -CONFIG_CROSS_MEMORY_ATTACH=y -# CONFIG_USELIB is not set -CONFIG_AUDIT=y -CONFIG_HAVE_ARCH_AUDITSYSCALL=y -CONFIG_AUDITSYSCALL=y - -# -# IRQ subsystem -# -CONFIG_GENERIC_IRQ_SHOW=y -CONFIG_GENERIC_IRQ_SHOW_LEVEL=y -CONFIG_GENERIC_IRQ_EFFECTIVE_AFF_MASK=y -CONFIG_GENERIC_IRQ_MIGRATION=y -CONFIG_HARDIRQS_SW_RESEND=y -CONFIG_GENERIC_IRQ_CHIP=y -CONFIG_IRQ_DOMAIN=y -CONFIG_IRQ_DOMAIN_HIERARCHY=y -CONFIG_GENERIC_IRQ_IPI=y -CONFIG_GENERIC_IRQ_IPI_MUX=y -CONFIG_GENERIC_MSI_IRQ=y -CONFIG_IRQ_FORCED_THREADING=y -CONFIG_SPARSE_IRQ=y -# CONFIG_GENERIC_IRQ_DEBUGFS is not set -# end of IRQ subsystem - -CONFIG_GENERIC_IRQ_MULTI_HANDLER=y -CONFIG_GENERIC_TIME_VSYSCALL=y -CONFIG_GENERIC_CLOCKEVENTS=y -CONFIG_ARCH_HAS_TICK_BROADCAST=y -CONFIG_GENERIC_CLOCKEVENTS_BROADCAST=y -CONFIG_HAVE_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_POSIX_CPU_TIMERS_TASK_WORK=y -CONFIG_CONTEXT_TRACKING=y -CONFIG_CONTEXT_TRACKING_IDLE=y - -# -# Timers subsystem -# -CONFIG_TICK_ONESHOT=y -CONFIG_NO_HZ_COMMON=y -# CONFIG_HZ_PERIODIC is not set -CONFIG_NO_HZ_IDLE=y -# CONFIG_NO_HZ_FULL is not set -# CONFIG_NO_HZ is not set -CONFIG_HIGH_RES_TIMERS=y -# end of Timers subsystem - -CONFIG_BPF=y -CONFIG_HAVE_EBPF_JIT=y - -# -# BPF subsystem -# -CONFIG_BPF_SYSCALL=y -# CONFIG_BPF_JIT is not set -CONFIG_BPF_UNPRIV_DEFAULT_OFF=y -# CONFIG_BPF_PRELOAD is not set -# end of BPF subsystem - -CONFIG_PREEMPT_NONE_BUILD=y -CONFIG_PREEMPT_NONE=y -# CONFIG_PREEMPT_VOLUNTARY is not set -# CONFIG_PREEMPT is not set -CONFIG_PREEMPT_COUNT=y - -# -# CPU/Task time and stats accounting -# -CONFIG_TICK_CPU_ACCOUNTING=y -# CONFIG_VIRT_CPU_ACCOUNTING_GEN is not set -# CONFIG_IRQ_TIME_ACCOUNTING is not set -# CONFIG_BSD_PROCESS_ACCT is not set -# CONFIG_TASKSTATS is not set -# CONFIG_PSI is not set -# end of CPU/Task time and stats accounting - -CONFIG_CPU_ISOLATION=y - -# -# RCU Subsystem -# -CONFIG_TREE_RCU=y -# CONFIG_RCU_EXPERT is not set -CONFIG_TREE_SRCU=y -CONFIG_TASKS_RCU_GENERIC=y -CONFIG_TASKS_TRACE_RCU=y -CONFIG_RCU_STALL_COMMON=y -CONFIG_RCU_NEED_SEGCBLIST=y -# end of RCU Subsystem - -CONFIG_IKCONFIG=y -CONFIG_IKCONFIG_PROC=y -# CONFIG_IKHEADERS is not set -CONFIG_LOG_BUF_SHIFT=17 -CONFIG_LOG_CPU_MAX_BUF_SHIFT=12 -# CONFIG_PRINTK_INDEX is not set -CONFIG_GENERIC_SCHED_CLOCK=y - -# -# Scheduler features -# -# end of Scheduler features - -CONFIG_CC_HAS_INT128=y -CONFIG_CC_IMPLICIT_FALLTHROUGH="-Wimplicit-fallthrough=5" -CONFIG_GCC11_NO_ARRAY_BOUNDS=y -CONFIG_CC_NO_ARRAY_BOUNDS=y -CONFIG_ARCH_SUPPORTS_INT128=y -CONFIG_CGROUPS=y -CONFIG_PAGE_COUNTER=y -# CONFIG_CGROUP_FAVOR_DYNMODS is not set -CONFIG_MEMCG=y -CONFIG_MEMCG_KMEM=y -# CONFIG_BLK_CGROUP is not set -CONFIG_CGROUP_SCHED=y -CONFIG_FAIR_GROUP_SCHED=y -CONFIG_CFS_BANDWIDTH=y -CONFIG_RT_GROUP_SCHED=y -CONFIG_SCHED_MM_CID=y -CONFIG_CGROUP_PIDS=y -# CONFIG_CGROUP_RDMA is not set -CONFIG_CGROUP_FREEZER=y -CONFIG_CGROUP_HUGETLB=y -CONFIG_CPUSETS=y -CONFIG_PROC_PID_CPUSET=y -CONFIG_CGROUP_DEVICE=y -CONFIG_CGROUP_CPUACCT=y -CONFIG_CGROUP_PERF=y -CONFIG_CGROUP_BPF=y -# CONFIG_CGROUP_MISC is not set -# CONFIG_CGROUP_DEBUG is not set -CONFIG_SOCK_CGROUP_DATA=y -CONFIG_NAMESPACES=y -CONFIG_UTS_NS=y -CONFIG_TIME_NS=y -CONFIG_IPC_NS=y -CONFIG_USER_NS=y -CONFIG_PID_NS=y -CONFIG_NET_NS=y -CONFIG_CHECKPOINT_RESTORE=y -# CONFIG_SCHED_AUTOGROUP is not set -# CONFIG_RELAY is not set -CONFIG_BLK_DEV_INITRD=y -CONFIG_INITRAMFS_SOURCE="" -CONFIG_RD_GZIP=y -CONFIG_RD_BZIP2=y -CONFIG_RD_LZMA=y -CONFIG_RD_XZ=y -CONFIG_RD_LZO=y -CONFIG_RD_LZ4=y -CONFIG_RD_ZSTD=y -# CONFIG_BOOT_CONFIG is not set -CONFIG_INITRAMFS_PRESERVE_MTIME=y -CONFIG_CC_OPTIMIZE_FOR_PERFORMANCE=y -# CONFIG_CC_OPTIMIZE_FOR_SIZE is not set -CONFIG_HAVE_LD_DEAD_CODE_DATA_ELIMINATION=y -# CONFIG_LD_DEAD_CODE_DATA_ELIMINATION is not set -CONFIG_LD_ORPHAN_WARN=y -CONFIG_LD_ORPHAN_WARN_LEVEL="warn" -CONFIG_SYSCTL=y -CONFIG_SYSCTL_EXCEPTION_TRACE=y -CONFIG_EXPERT=y -CONFIG_MULTIUSER=y -# CONFIG_SGETMASK_SYSCALL is not set -# CONFIG_SYSFS_SYSCALL is not set -CONFIG_FHANDLE=y -CONFIG_POSIX_TIMERS=y -CONFIG_PRINTK=y -CONFIG_BUG=y -CONFIG_ELF_CORE=y -CONFIG_BASE_FULL=y -CONFIG_FUTEX=y -CONFIG_FUTEX_PI=y -CONFIG_EPOLL=y -CONFIG_SIGNALFD=y -CONFIG_TIMERFD=y -CONFIG_EVENTFD=y -CONFIG_SHMEM=y -CONFIG_AIO=y -CONFIG_IO_URING=y -CONFIG_ADVISE_SYSCALLS=y -CONFIG_MEMBARRIER=y -CONFIG_KALLSYMS=y -# CONFIG_KALLSYMS_SELFTEST is not set -# CONFIG_KALLSYMS_ALL is not set -CONFIG_KALLSYMS_BASE_RELATIVE=y -CONFIG_KCMP=y -CONFIG_RSEQ=y -CONFIG_CACHESTAT_SYSCALL=y -# CONFIG_DEBUG_RSEQ is not set -# CONFIG_EMBEDDED is not set -CONFIG_HAVE_PERF_EVENTS=y -# CONFIG_PC104 is not set - -# -# Kernel Performance Events And Counters -# -CONFIG_PERF_EVENTS=y -# CONFIG_DEBUG_PERF_USE_VMALLOC is not set -# end of Kernel Performance Events And Counters - -CONFIG_PROFILING=y -# end of General setup - -CONFIG_64BIT=y -CONFIG_RISCV=y -CONFIG_GCC_SUPPORTS_DYNAMIC_FTRACE=y -CONFIG_ARCH_MMAP_RND_BITS_MIN=18 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MIN=8 -CONFIG_ARCH_MMAP_RND_BITS_MAX=24 -CONFIG_ARCH_MMAP_RND_COMPAT_BITS_MAX=17 -CONFIG_RISCV_SBI=y -CONFIG_MMU=y -CONFIG_PAGE_OFFSET=0xff60000000000000 -CONFIG_ARCH_FLATMEM_ENABLE=y -CONFIG_ARCH_SPARSEMEM_ENABLE=y -CONFIG_ARCH_SELECT_MEMORY_MODEL=y -CONFIG_ARCH_SUPPORTS_UPROBES=y -CONFIG_STACKTRACE_SUPPORT=y -CONFIG_GENERIC_BUG=y -CONFIG_GENERIC_BUG_RELATIVE_POINTERS=y -CONFIG_GENERIC_CALIBRATE_DELAY=y -CONFIG_GENERIC_CSUM=y -CONFIG_GENERIC_HWEIGHT=y -CONFIG_FIX_EARLYCON_MEM=y -CONFIG_PGTABLE_LEVELS=5 -CONFIG_LOCKDEP_SUPPORT=y -CONFIG_RISCV_DMA_NONCOHERENT=y -CONFIG_AS_HAS_INSN=y -CONFIG_AS_HAS_OPTION_ARCH=y - -# -# SoC selection -# -CONFIG_ARCH_MICROCHIP_POLARFIRE=y -CONFIG_SOC_MICROCHIP_POLARFIRE=y -CONFIG_ARCH_RENESAS=y -CONFIG_ARCH_SIFIVE=y -CONFIG_SOC_SIFIVE=y -CONFIG_ARCH_STARFIVE=y -CONFIG_SOC_STARFIVE=y -CONFIG_ARCH_SUNXI=y -CONFIG_ARCH_THEAD=y -CONFIG_ARCH_VIRT=y -CONFIG_SOC_VIRT=y -# end of SoC selection - -# -# CPU errata selection -# -CONFIG_ERRATA_SIFIVE=y -CONFIG_ERRATA_SIFIVE_CIP_453=y -CONFIG_ERRATA_SIFIVE_CIP_1200=y -CONFIG_ERRATA_THEAD=y -CONFIG_ERRATA_THEAD_PBMT=y -CONFIG_ERRATA_THEAD_CMO=y -CONFIG_ERRATA_THEAD_PMU=y -# end of CPU errata selection - -# -# Platform type -# -# CONFIG_NONPORTABLE is not set -CONFIG_ARCH_RV64I=y -# CONFIG_CMODEL_MEDLOW is not set -CONFIG_CMODEL_MEDANY=y -CONFIG_MODULE_SECTIONS=y -CONFIG_SMP=y -# CONFIG_SCHED_MC is not set -CONFIG_NR_CPUS=64 -CONFIG_HOTPLUG_CPU=y -CONFIG_TUNE_GENERIC=y -# CONFIG_NUMA is not set -CONFIG_RISCV_ALTERNATIVE=y -CONFIG_RISCV_ALTERNATIVE_EARLY=y -CONFIG_RISCV_ISA_C=y -CONFIG_RISCV_ISA_SVNAPOT=y -CONFIG_RISCV_ISA_SVPBMT=y -CONFIG_TOOLCHAIN_HAS_V=y -CONFIG_RISCV_ISA_V=y -CONFIG_RISCV_ISA_V_DEFAULT_ENABLE=y -CONFIG_TOOLCHAIN_HAS_ZBB=y -CONFIG_RISCV_ISA_ZBB=y -CONFIG_RISCV_ISA_ZICBOM=y -CONFIG_RISCV_ISA_ZICBOZ=y -CONFIG_TOOLCHAIN_HAS_ZIHINTPAUSE=y -CONFIG_TOOLCHAIN_NEEDS_EXPLICIT_ZICSR_ZIFENCEI=y -CONFIG_FPU=y -CONFIG_IRQ_STACKS=y -CONFIG_THREAD_SIZE_ORDER=2 -# end of Platform type - -# -# Kernel features -# -# CONFIG_HZ_100 is not set -CONFIG_HZ_250=y -# CONFIG_HZ_300 is not set -# CONFIG_HZ_1000 is not set -CONFIG_HZ=250 -CONFIG_SCHED_HRTICK=y -# CONFIG_RISCV_SBI_V01 is not set -# CONFIG_RISCV_BOOT_SPINWAIT is not set -# CONFIG_KEXEC is not set -# CONFIG_KEXEC_FILE is not set -# CONFIG_CRASH_DUMP is not set -CONFIG_COMPAT=y -# CONFIG_RELOCATABLE is not set -# end of Kernel features - -# -# Boot options -# -CONFIG_CMDLINE="" -CONFIG_EFI_STUB=y -CONFIG_EFI=y -CONFIG_CC_HAVE_STACKPROTECTOR_TLS=y -CONFIG_STACKPROTECTOR_PER_TASK=y -# end of Boot options - -CONFIG_PORTABLE=y - -# -# Power management options -# -CONFIG_SUSPEND=y -CONFIG_SUSPEND_FREEZER=y -# CONFIG_SUSPEND_SKIP_SYNC is not set -CONFIG_PM_SLEEP=y -CONFIG_PM_SLEEP_SMP=y -# CONFIG_PM_AUTOSLEEP is not set -# CONFIG_PM_USERSPACE_AUTOSLEEP is not set -# CONFIG_PM_WAKELOCKS is not set -CONFIG_PM=y -# CONFIG_PM_DEBUG is not set -CONFIG_PM_CLK=y -CONFIG_PM_GENERIC_DOMAINS=y -# CONFIG_WQ_POWER_EFFICIENT_DEFAULT is not set -CONFIG_PM_GENERIC_DOMAINS_SLEEP=y -CONFIG_PM_GENERIC_DOMAINS_OF=y -CONFIG_CPU_PM=y -CONFIG_ARCH_SUSPEND_POSSIBLE=y -# end of Power management options - -# -# CPU Power Management -# - -# -# CPU Idle -# -CONFIG_CPU_IDLE=y -CONFIG_CPU_IDLE_MULTIPLE_DRIVERS=y -# CONFIG_CPU_IDLE_GOV_LADDER is not set -CONFIG_CPU_IDLE_GOV_MENU=y -# CONFIG_CPU_IDLE_GOV_TEO is not set -CONFIG_DT_IDLE_STATES=y -CONFIG_DT_IDLE_GENPD=y - -# -# RISC-V CPU Idle Drivers -# -CONFIG_RISCV_SBI_CPUIDLE=y -# end of RISC-V CPU Idle Drivers -# end of CPU Idle - -# -# CPU Frequency scaling -# -# CONFIG_CPU_FREQ is not set -# end of CPU Frequency scaling -# end of CPU Power Management - -CONFIG_HAVE_KVM_IRQCHIP=y -CONFIG_HAVE_KVM_IRQFD=y -CONFIG_HAVE_KVM_IRQ_ROUTING=y -CONFIG_HAVE_KVM_EVENTFD=y -CONFIG_KVM_MMIO=y -CONFIG_HAVE_KVM_MSI=y -CONFIG_KVM_GENERIC_DIRTYLOG_READ_PROTECT=y -CONFIG_HAVE_KVM_VCPU_ASYNC_IOCTL=y -CONFIG_KVM_XFER_TO_GUEST_WORK=y -CONFIG_KVM_GENERIC_HARDWARE_ENABLING=y -CONFIG_VIRTUALIZATION=y -CONFIG_KVM=m -CONFIG_ARCH_SUPPORTS_ACPI=y -CONFIG_ACPI=y -CONFIG_ACPI_GENERIC_GSI=y -# CONFIG_ACPI_DEBUGGER is not set -# CONFIG_ACPI_SPCR_TABLE is not set -# CONFIG_ACPI_EC_DEBUGFS is not set -CONFIG_ACPI_AC=y -CONFIG_ACPI_BATTERY=y -CONFIG_ACPI_BUTTON=y -CONFIG_ACPI_VIDEO=m -CONFIG_ACPI_FAN=y -# CONFIG_ACPI_TAD is not set -# CONFIG_ACPI_DOCK is not set -# CONFIG_ACPI_DEBUG is not set -# CONFIG_ACPI_PCI_SLOT is not set -# CONFIG_ACPI_CONTAINER is not set -# CONFIG_ACPI_HED is not set -# CONFIG_ACPI_CUSTOM_METHOD is not set -CONFIG_ACPI_REDUCED_HARDWARE_ONLY=y -# CONFIG_ACPI_NFIT is not set -# CONFIG_ACPI_CONFIGFS is not set -# CONFIG_ACPI_PFRUT is not set -# CONFIG_ACPI_FFH is not set -# CONFIG_PMIC_OPREGION is not set - -# -# General architecture-dependent options -# -CONFIG_HOTPLUG_CORE_SYNC=y -CONFIG_HOTPLUG_CORE_SYNC_DEAD=y -CONFIG_GENERIC_ENTRY=y -# CONFIG_KPROBES is not set -CONFIG_JUMP_LABEL=y -# CONFIG_STATIC_KEYS_SELFTEST is not set -CONFIG_HAVE_64BIT_ALIGNED_ACCESS=y -CONFIG_HAVE_KPROBES=y -CONFIG_HAVE_KRETPROBES=y -CONFIG_HAVE_KPROBES_ON_FTRACE=y -CONFIG_HAVE_FUNCTION_ERROR_INJECTION=y -CONFIG_TRACE_IRQFLAGS_SUPPORT=y -CONFIG_HAVE_ARCH_TRACEHOOK=y -CONFIG_HAVE_DMA_CONTIGUOUS=y -CONFIG_GENERIC_SMP_IDLE_THREAD=y -CONFIG_GENERIC_IDLE_POLL_SETUP=y -CONFIG_ARCH_HAS_FORTIFY_SOURCE=y -CONFIG_ARCH_HAS_SET_MEMORY=y -CONFIG_ARCH_HAS_SET_DIRECT_MAP=y -CONFIG_HAVE_ARCH_THREAD_STRUCT_WHITELIST=y -CONFIG_HAVE_ASM_MODVERSIONS=y -CONFIG_HAVE_REGS_AND_STACK_ACCESS_API=y -CONFIG_HAVE_RSEQ=y -CONFIG_HAVE_FUNCTION_ARG_ACCESS_API=y -CONFIG_HAVE_PERF_REGS=y -CONFIG_HAVE_PERF_USER_STACK_DUMP=y -CONFIG_HAVE_ARCH_JUMP_LABEL=y -CONFIG_HAVE_ARCH_JUMP_LABEL_RELATIVE=y -CONFIG_MMU_LAZY_TLB_REFCOUNT=y -CONFIG_HAVE_ARCH_SECCOMP=y -CONFIG_HAVE_ARCH_SECCOMP_FILTER=y -CONFIG_SECCOMP=y -CONFIG_SECCOMP_FILTER=y -# CONFIG_SECCOMP_CACHE_DEBUG is not set -CONFIG_HAVE_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR=y -CONFIG_STACKPROTECTOR_STRONG=y -CONFIG_LTO_NONE=y -CONFIG_HAVE_CONTEXT_TRACKING_USER=y -CONFIG_HAVE_VIRT_CPU_ACCOUNTING_GEN=y -CONFIG_HAVE_IRQ_TIME_ACCOUNTING=y -CONFIG_HAVE_MOVE_PUD=y -CONFIG_HAVE_MOVE_PMD=y -CONFIG_HAVE_ARCH_TRANSPARENT_HUGEPAGE=y -CONFIG_HAVE_ARCH_HUGE_VMAP=y -CONFIG_HAVE_ARCH_HUGE_VMALLOC=y -CONFIG_ARCH_WANT_HUGE_PMD_SHARE=y -CONFIG_HAVE_MOD_ARCH_SPECIFIC=y -CONFIG_MODULES_USE_ELF_RELA=y -CONFIG_HAVE_IRQ_EXIT_ON_IRQ_STACK=y -CONFIG_HAVE_SOFTIRQ_ON_OWN_STACK=y -CONFIG_SOFTIRQ_ON_OWN_STACK=y -CONFIG_ARCH_HAS_ELF_RANDOMIZE=y -CONFIG_HAVE_ARCH_MMAP_RND_BITS=y -CONFIG_ARCH_MMAP_RND_BITS=18 -CONFIG_HAVE_ARCH_MMAP_RND_COMPAT_BITS=y -CONFIG_ARCH_MMAP_RND_COMPAT_BITS=8 -CONFIG_PAGE_SIZE_LESS_THAN_64KB=y -CONFIG_PAGE_SIZE_LESS_THAN_256KB=y -CONFIG_ARCH_WANT_DEFAULT_TOPDOWN_MMAP_LAYOUT=y -CONFIG_CLONE_BACKWARDS=y -CONFIG_COMPAT_32BIT_TIME=y -CONFIG_HAVE_ARCH_VMAP_STACK=y -CONFIG_VMAP_STACK=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX=y -CONFIG_ARCH_OPTIONAL_KERNEL_RWX_DEFAULT=y -CONFIG_ARCH_HAS_STRICT_KERNEL_RWX=y -CONFIG_STRICT_KERNEL_RWX=y -CONFIG_ARCH_HAS_STRICT_MODULE_RWX=y -CONFIG_STRICT_MODULE_RWX=y -CONFIG_ARCH_USE_MEMREMAP_PROT=y -# CONFIG_LOCK_EVENT_COUNTS is not set -CONFIG_ARCH_HAS_VDSO_DATA=y -CONFIG_ARCH_WANT_LD_ORPHAN_WARN=y -CONFIG_ARCH_SUPPORTS_DEBUG_PAGEALLOC=y -CONFIG_ARCH_SUPPORTS_PAGE_TABLE_CHECK=y -CONFIG_DYNAMIC_SIGFRAME=y - -# -# GCOV-based kernel profiling -# -# CONFIG_GCOV_KERNEL is not set -CONFIG_ARCH_HAS_GCOV_PROFILE_ALL=y -# end of GCOV-based kernel profiling - -CONFIG_HAVE_GCC_PLUGINS=y -CONFIG_GCC_PLUGINS=y -# CONFIG_GCC_PLUGIN_LATENT_ENTROPY is not set -CONFIG_FUNCTION_ALIGNMENT=0 -# end of General architecture-dependent options - -CONFIG_RT_MUTEXES=y -CONFIG_BASE_SMALL=0 -CONFIG_MODULES=y -# CONFIG_MODULE_DEBUG is not set -# CONFIG_MODULE_FORCE_LOAD is not set -CONFIG_MODULE_UNLOAD=y -# CONFIG_MODULE_FORCE_UNLOAD is not set -# CONFIG_MODULE_UNLOAD_TAINT_TRACKING is not set -# CONFIG_MODVERSIONS is not set -# CONFIG_MODULE_SRCVERSION_ALL is not set -# CONFIG_MODULE_SIG is not set -CONFIG_MODULE_COMPRESS_NONE=y -# CONFIG_MODULE_COMPRESS_GZIP is not set -# CONFIG_MODULE_COMPRESS_XZ is not set -# CONFIG_MODULE_COMPRESS_ZSTD is not set -# CONFIG_MODULE_ALLOW_MISSING_NAMESPACE_IMPORTS is not set -CONFIG_MODPROBE_PATH="/sbin/modprobe" -# CONFIG_TRIM_UNUSED_KSYMS is not set -CONFIG_MODULES_TREE_LOOKUP=y -CONFIG_BLOCK=y -CONFIG_BLOCK_LEGACY_AUTOLOAD=y -CONFIG_BLK_CGROUP_PUNT_BIO=y -CONFIG_BLK_DEV_BSG_COMMON=y -CONFIG_BLK_ICQ=y -# CONFIG_BLK_DEV_BSGLIB is not set -# CONFIG_BLK_DEV_INTEGRITY is not set -# CONFIG_BLK_DEV_ZONED is not set -# CONFIG_BLK_WBT is not set -CONFIG_BLK_DEBUG_FS=y -# CONFIG_BLK_SED_OPAL is not set -# CONFIG_BLK_INLINE_ENCRYPTION is not set - -# -# Partition Types -# -# CONFIG_PARTITION_ADVANCED is not set -CONFIG_MSDOS_PARTITION=y -CONFIG_EFI_PARTITION=y -# end of Partition Types - -CONFIG_BLK_MQ_PCI=y -CONFIG_BLK_MQ_VIRTIO=y -CONFIG_BLK_PM=y -CONFIG_BLOCK_HOLDER_DEPRECATED=y -CONFIG_BLK_MQ_STACKING=y - -# -# IO Schedulers -# -CONFIG_MQ_IOSCHED_DEADLINE=y -CONFIG_MQ_IOSCHED_KYBER=y -CONFIG_IOSCHED_BFQ=y -# end of IO Schedulers - -CONFIG_PREEMPT_NOTIFIERS=y -CONFIG_ASN1=y -CONFIG_UNINLINE_SPIN_UNLOCK=y -CONFIG_ARCH_SUPPORTS_ATOMIC_RMW=y -CONFIG_MUTEX_SPIN_ON_OWNER=y -CONFIG_RWSEM_SPIN_ON_OWNER=y -CONFIG_LOCK_SPIN_ON_OWNER=y -CONFIG_ARCH_USE_QUEUED_RWLOCKS=y -CONFIG_QUEUED_RWLOCKS=y -CONFIG_ARCH_HAS_MMIOWB=y -CONFIG_MMIOWB=y -CONFIG_ARCH_HAS_NON_OVERLAPPING_ADDRESS_SPACE=y -CONFIG_FREEZER=y - -# -# Executable file formats -# -CONFIG_BINFMT_ELF=y -CONFIG_COMPAT_BINFMT_ELF=y -CONFIG_ELFCORE=y -CONFIG_CORE_DUMP_DEFAULT_ELF_HEADERS=y -CONFIG_BINFMT_SCRIPT=y -CONFIG_ARCH_HAS_BINFMT_FLAT=y -# CONFIG_BINFMT_FLAT is not set -# CONFIG_BINFMT_MISC is not set -CONFIG_COREDUMP=y -# end of Executable file formats - -# -# Memory Management options -# -CONFIG_SWAP=y -# CONFIG_ZSWAP is not set - -# -# SLAB allocator options -# -# CONFIG_SLAB_DEPRECATED is not set -CONFIG_SLUB=y -# CONFIG_SLUB_TINY is not set -CONFIG_SLAB_MERGE_DEFAULT=y -# CONFIG_SLAB_FREELIST_RANDOM is not set -# CONFIG_SLAB_FREELIST_HARDENED is not set -# CONFIG_SLUB_STATS is not set -CONFIG_SLUB_CPU_PARTIAL=y -# end of SLAB allocator options - -# CONFIG_SHUFFLE_PAGE_ALLOCATOR is not set -CONFIG_COMPAT_BRK=y -CONFIG_SELECT_MEMORY_MODEL=y -# CONFIG_FLATMEM_MANUAL is not set -CONFIG_SPARSEMEM_MANUAL=y -CONFIG_SPARSEMEM=y -CONFIG_SPARSEMEM_EXTREME=y -CONFIG_SPARSEMEM_VMEMMAP_ENABLE=y -CONFIG_SPARSEMEM_VMEMMAP=y -CONFIG_ARCH_WANT_OPTIMIZE_VMEMMAP=y -CONFIG_SPLIT_PTLOCK_CPUS=4 -CONFIG_ARCH_ENABLE_SPLIT_PMD_PTLOCK=y -CONFIG_MEMORY_BALLOON=y -CONFIG_BALLOON_COMPACTION=y -CONFIG_COMPACTION=y -CONFIG_COMPACT_UNEVICTABLE_DEFAULT=1 -CONFIG_PAGE_REPORTING=y -CONFIG_MIGRATION=y -CONFIG_ARCH_ENABLE_HUGEPAGE_MIGRATION=y -CONFIG_PHYS_ADDR_T_64BIT=y -CONFIG_MMU_NOTIFIER=y -# CONFIG_KSM is not set -CONFIG_DEFAULT_MMAP_MIN_ADDR=4096 -CONFIG_ARCH_WANTS_THP_SWAP=y -# CONFIG_TRANSPARENT_HUGEPAGE is not set -# CONFIG_CMA is not set -CONFIG_GENERIC_EARLY_IOREMAP=y -# CONFIG_DEFERRED_STRUCT_PAGE_INIT is not set -# CONFIG_IDLE_PAGE_TRACKING is not set -CONFIG_ARCH_HAS_CURRENT_STACK_POINTER=y -CONFIG_ZONE_DMA32=y -CONFIG_VM_EVENT_COUNTERS=y -# CONFIG_PERCPU_STATS is not set -# CONFIG_GUP_TEST is not set -# CONFIG_DMAPOOL_TEST is not set -CONFIG_ARCH_HAS_PTE_SPECIAL=y -CONFIG_SECRETMEM=y -# CONFIG_ANON_VMA_NAME is not set -# CONFIG_USERFAULTFD is not set -# CONFIG_LRU_GEN is not set -CONFIG_ARCH_SUPPORTS_PER_VMA_LOCK=y -CONFIG_PER_VMA_LOCK=y -CONFIG_LOCK_MM_AND_FIND_VMA=y - -# -# Data Access Monitoring -# -# CONFIG_DAMON is not set -# end of Data Access Monitoring -# end of Memory Management options - -CONFIG_NET=y -CONFIG_NET_INGRESS=y -CONFIG_NET_EGRESS=y -CONFIG_SKB_EXTENSIONS=y - -# -# Networking options -# -CONFIG_PACKET=y -# CONFIG_PACKET_DIAG is not set -CONFIG_UNIX=y -CONFIG_UNIX_SCM=y -CONFIG_AF_UNIX_OOB=y -# CONFIG_UNIX_DIAG is not set -# CONFIG_TLS is not set -CONFIG_XFRM=y -CONFIG_XFRM_ALGO=m -CONFIG_XFRM_USER=m -# CONFIG_XFRM_INTERFACE is not set -# CONFIG_XFRM_SUB_POLICY is not set -# CONFIG_XFRM_MIGRATE is not set -# CONFIG_XFRM_STATISTICS is not set -CONFIG_XFRM_ESP=m -# CONFIG_NET_KEY is not set -# CONFIG_XDP_SOCKETS is not set -CONFIG_NET_HANDSHAKE=y -CONFIG_INET=y -CONFIG_IP_MULTICAST=y -CONFIG_IP_ADVANCED_ROUTER=y -# CONFIG_IP_FIB_TRIE_STATS is not set -# CONFIG_IP_MULTIPLE_TABLES is not set -# CONFIG_IP_ROUTE_MULTIPATH is not set -# CONFIG_IP_ROUTE_VERBOSE is not set -CONFIG_IP_PNP=y -CONFIG_IP_PNP_DHCP=y -CONFIG_IP_PNP_BOOTP=y -CONFIG_IP_PNP_RARP=y -# CONFIG_NET_IPIP is not set -# CONFIG_NET_IPGRE_DEMUX is not set -CONFIG_NET_IP_TUNNEL=y -# CONFIG_IP_MROUTE is not set -# CONFIG_SYN_COOKIES is not set -# CONFIG_NET_IPVTI is not set -CONFIG_NET_UDP_TUNNEL=m -# CONFIG_NET_FOU is not set -# CONFIG_NET_FOU_IP_TUNNELS is not set -# CONFIG_INET_AH is not set -CONFIG_INET_ESP=m -# CONFIG_INET_ESP_OFFLOAD is not set -# CONFIG_INET_ESPINTCP is not set -# CONFIG_INET_IPCOMP is not set -CONFIG_INET_TABLE_PERTURB_ORDER=16 -CONFIG_INET_TUNNEL=y -CONFIG_INET_DIAG=y -CONFIG_INET_TCP_DIAG=y -# CONFIG_INET_UDP_DIAG is not set -# CONFIG_INET_RAW_DIAG is not set -# CONFIG_INET_DIAG_DESTROY is not set -# CONFIG_TCP_CONG_ADVANCED is not set -CONFIG_TCP_CONG_CUBIC=y -CONFIG_DEFAULT_TCP_CONG="cubic" -# CONFIG_TCP_MD5SIG is not set -CONFIG_IPV6=y -# CONFIG_IPV6_ROUTER_PREF is not set -# CONFIG_IPV6_OPTIMISTIC_DAD is not set -# CONFIG_INET6_AH is not set -# CONFIG_INET6_ESP is not set -# CONFIG_INET6_IPCOMP is not set -# CONFIG_IPV6_MIP6 is not set -# CONFIG_IPV6_ILA is not set -# CONFIG_IPV6_VTI is not set -CONFIG_IPV6_SIT=y -# CONFIG_IPV6_SIT_6RD is not set -CONFIG_IPV6_NDISC_NODETYPE=y -# CONFIG_IPV6_TUNNEL is not set -# CONFIG_IPV6_MULTIPLE_TABLES is not set -# CONFIG_IPV6_MROUTE is not set -# CONFIG_IPV6_SEG6_LWTUNNEL is not set -# CONFIG_IPV6_SEG6_HMAC is not set -# CONFIG_IPV6_RPL_LWTUNNEL is not set -# CONFIG_IPV6_IOAM6_LWTUNNEL is not set -# CONFIG_NETLABEL is not set -# CONFIG_MPTCP is not set -CONFIG_NETWORK_SECMARK=y -# CONFIG_NETWORK_PHY_TIMESTAMPING is not set -CONFIG_NETFILTER=y -CONFIG_NETFILTER_ADVANCED=y -CONFIG_BRIDGE_NETFILTER=m - -# -# Core Netfilter Configuration -# -CONFIG_NETFILTER_INGRESS=y -CONFIG_NETFILTER_EGRESS=y -CONFIG_NETFILTER_FAMILY_BRIDGE=y -CONFIG_NETFILTER_BPF_LINK=y -# CONFIG_NETFILTER_NETLINK_ACCT is not set -# CONFIG_NETFILTER_NETLINK_QUEUE is not set -# CONFIG_NETFILTER_NETLINK_LOG is not set -# CONFIG_NETFILTER_NETLINK_OSF is not set -CONFIG_NF_CONNTRACK=m -CONFIG_NF_LOG_SYSLOG=m -# CONFIG_NF_CONNTRACK_MARK is not set -# CONFIG_NF_CONNTRACK_SECMARK is not set -# CONFIG_NF_CONNTRACK_ZONES is not set -# CONFIG_NF_CONNTRACK_PROCFS is not set -# CONFIG_NF_CONNTRACK_EVENTS is not set -# CONFIG_NF_CONNTRACK_TIMEOUT is not set -# CONFIG_NF_CONNTRACK_TIMESTAMP is not set -# CONFIG_NF_CONNTRACK_LABELS is not set -CONFIG_NF_CT_PROTO_DCCP=y -CONFIG_NF_CT_PROTO_SCTP=y -CONFIG_NF_CT_PROTO_UDPLITE=y -# CONFIG_NF_CONNTRACK_AMANDA is not set -CONFIG_NF_CONNTRACK_FTP=m -# CONFIG_NF_CONNTRACK_H323 is not set -# CONFIG_NF_CONNTRACK_IRC is not set -# CONFIG_NF_CONNTRACK_NETBIOS_NS is not set -# CONFIG_NF_CONNTRACK_SNMP is not set -# CONFIG_NF_CONNTRACK_PPTP is not set -# CONFIG_NF_CONNTRACK_SANE is not set -# CONFIG_NF_CONNTRACK_SIP is not set -CONFIG_NF_CONNTRACK_TFTP=m -# CONFIG_NF_CT_NETLINK is not set -CONFIG_NF_NAT=m -CONFIG_NF_NAT_FTP=m -CONFIG_NF_NAT_TFTP=m -CONFIG_NF_NAT_REDIRECT=y -CONFIG_NF_NAT_MASQUERADE=y -# CONFIG_NF_TABLES is not set -CONFIG_NETFILTER_XTABLES=y -# CONFIG_NETFILTER_XTABLES_COMPAT is not set - -# -# Xtables combined modules -# -CONFIG_NETFILTER_XT_MARK=m -# CONFIG_NETFILTER_XT_CONNMARK is not set - -# -# Xtables targets -# -# CONFIG_NETFILTER_XT_TARGET_AUDIT is not set -# CONFIG_NETFILTER_XT_TARGET_CHECKSUM is not set -# CONFIG_NETFILTER_XT_TARGET_CLASSIFY is not set -# CONFIG_NETFILTER_XT_TARGET_CONNMARK is not set -# CONFIG_NETFILTER_XT_TARGET_DSCP is not set -# CONFIG_NETFILTER_XT_TARGET_HL is not set -# CONFIG_NETFILTER_XT_TARGET_HMARK is not set -# CONFIG_NETFILTER_XT_TARGET_IDLETIMER is not set -# CONFIG_NETFILTER_XT_TARGET_LOG is not set -# CONFIG_NETFILTER_XT_TARGET_MARK is not set -CONFIG_NETFILTER_XT_NAT=m -# CONFIG_NETFILTER_XT_TARGET_NETMAP is not set -# CONFIG_NETFILTER_XT_TARGET_NFLOG is not set -# CONFIG_NETFILTER_XT_TARGET_NFQUEUE is not set -# CONFIG_NETFILTER_XT_TARGET_RATEEST is not set -CONFIG_NETFILTER_XT_TARGET_REDIRECT=m -CONFIG_NETFILTER_XT_TARGET_MASQUERADE=m -# CONFIG_NETFILTER_XT_TARGET_TEE is not set -# CONFIG_NETFILTER_XT_TARGET_TPROXY is not set -# CONFIG_NETFILTER_XT_TARGET_SECMARK is not set -# CONFIG_NETFILTER_XT_TARGET_TCPMSS is not set -# CONFIG_NETFILTER_XT_TARGET_TCPOPTSTRIP is not set - -# -# Xtables matches -# -CONFIG_NETFILTER_XT_MATCH_ADDRTYPE=m -# CONFIG_NETFILTER_XT_MATCH_BPF is not set -# CONFIG_NETFILTER_XT_MATCH_CGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_CLUSTER is not set -# CONFIG_NETFILTER_XT_MATCH_COMMENT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNBYTES is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLABEL is not set -# CONFIG_NETFILTER_XT_MATCH_CONNLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_CONNMARK is not set -CONFIG_NETFILTER_XT_MATCH_CONNTRACK=m -# CONFIG_NETFILTER_XT_MATCH_CPU is not set -# CONFIG_NETFILTER_XT_MATCH_DCCP is not set -# CONFIG_NETFILTER_XT_MATCH_DEVGROUP is not set -# CONFIG_NETFILTER_XT_MATCH_DSCP is not set -# CONFIG_NETFILTER_XT_MATCH_ECN is not set -# CONFIG_NETFILTER_XT_MATCH_ESP is not set -# CONFIG_NETFILTER_XT_MATCH_HASHLIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_HELPER is not set -# CONFIG_NETFILTER_XT_MATCH_HL is not set -# CONFIG_NETFILTER_XT_MATCH_IPCOMP is not set -# CONFIG_NETFILTER_XT_MATCH_IPRANGE is not set -CONFIG_NETFILTER_XT_MATCH_IPVS=m -# CONFIG_NETFILTER_XT_MATCH_L2TP is not set -# CONFIG_NETFILTER_XT_MATCH_LENGTH is not set -# CONFIG_NETFILTER_XT_MATCH_LIMIT is not set -# CONFIG_NETFILTER_XT_MATCH_MAC is not set -# CONFIG_NETFILTER_XT_MATCH_MARK is not set -# CONFIG_NETFILTER_XT_MATCH_MULTIPORT is not set -# CONFIG_NETFILTER_XT_MATCH_NFACCT is not set -# CONFIG_NETFILTER_XT_MATCH_OSF is not set -# CONFIG_NETFILTER_XT_MATCH_OWNER is not set -# CONFIG_NETFILTER_XT_MATCH_POLICY is not set -# CONFIG_NETFILTER_XT_MATCH_PHYSDEV is not set -# CONFIG_NETFILTER_XT_MATCH_PKTTYPE is not set -# CONFIG_NETFILTER_XT_MATCH_QUOTA is not set -# CONFIG_NETFILTER_XT_MATCH_RATEEST is not set -# CONFIG_NETFILTER_XT_MATCH_REALM is not set -# CONFIG_NETFILTER_XT_MATCH_RECENT is not set -# CONFIG_NETFILTER_XT_MATCH_SCTP is not set -# CONFIG_NETFILTER_XT_MATCH_SOCKET is not set -# CONFIG_NETFILTER_XT_MATCH_STATE is not set -# CONFIG_NETFILTER_XT_MATCH_STATISTIC is not set -# CONFIG_NETFILTER_XT_MATCH_STRING is not set -# CONFIG_NETFILTER_XT_MATCH_TCPMSS is not set -# CONFIG_NETFILTER_XT_MATCH_TIME is not set -# CONFIG_NETFILTER_XT_MATCH_U32 is not set -# end of Core Netfilter Configuration - -# CONFIG_IP_SET is not set -CONFIG_IP_VS=m -# CONFIG_IP_VS_IPV6 is not set -# CONFIG_IP_VS_DEBUG is not set -CONFIG_IP_VS_TAB_BITS=12 - -# -# IPVS transport protocol load balancing support -# -CONFIG_IP_VS_PROTO_TCP=y -CONFIG_IP_VS_PROTO_UDP=y -# CONFIG_IP_VS_PROTO_ESP is not set -# CONFIG_IP_VS_PROTO_AH is not set -# CONFIG_IP_VS_PROTO_SCTP is not set - -# -# IPVS scheduler -# -CONFIG_IP_VS_RR=m -# CONFIG_IP_VS_WRR is not set -# CONFIG_IP_VS_LC is not set -# CONFIG_IP_VS_WLC is not set -# CONFIG_IP_VS_FO is not set -# CONFIG_IP_VS_OVF is not set -# CONFIG_IP_VS_LBLC is not set -# CONFIG_IP_VS_LBLCR is not set -# CONFIG_IP_VS_DH is not set -# CONFIG_IP_VS_SH is not set -# CONFIG_IP_VS_MH is not set -# CONFIG_IP_VS_SED is not set -# CONFIG_IP_VS_NQ is not set -# CONFIG_IP_VS_TWOS is not set - -# -# IPVS SH scheduler -# -CONFIG_IP_VS_SH_TAB_BITS=8 - -# -# IPVS MH scheduler -# -CONFIG_IP_VS_MH_TAB_INDEX=12 - -# -# IPVS application helper -# -# CONFIG_IP_VS_FTP is not set -CONFIG_IP_VS_NFCT=y - -# -# IP: Netfilter Configuration -# -CONFIG_NF_DEFRAG_IPV4=m -# CONFIG_NF_SOCKET_IPV4 is not set -# CONFIG_NF_TPROXY_IPV4 is not set -# CONFIG_NF_DUP_IPV4 is not set -CONFIG_NF_LOG_ARP=m -CONFIG_NF_LOG_IPV4=m -CONFIG_NF_REJECT_IPV4=m -CONFIG_IP_NF_IPTABLES=y -# CONFIG_IP_NF_MATCH_AH is not set -# CONFIG_IP_NF_MATCH_ECN is not set -# CONFIG_IP_NF_MATCH_RPFILTER is not set -# CONFIG_IP_NF_MATCH_TTL is not set -CONFIG_IP_NF_FILTER=m -CONFIG_IP_NF_TARGET_REJECT=m -# CONFIG_IP_NF_TARGET_SYNPROXY is not set -CONFIG_IP_NF_NAT=m -CONFIG_IP_NF_TARGET_MASQUERADE=m -# CONFIG_IP_NF_TARGET_NETMAP is not set -CONFIG_IP_NF_TARGET_REDIRECT=m -CONFIG_IP_NF_MANGLE=m -# CONFIG_IP_NF_TARGET_ECN is not set -# CONFIG_IP_NF_TARGET_TTL is not set -# CONFIG_IP_NF_RAW is not set -# CONFIG_IP_NF_SECURITY is not set -# CONFIG_IP_NF_ARPTABLES is not set -# end of IP: Netfilter Configuration - -# -# IPv6: Netfilter Configuration -# -# CONFIG_NF_SOCKET_IPV6 is not set -# CONFIG_NF_TPROXY_IPV6 is not set -# CONFIG_NF_DUP_IPV6 is not set -CONFIG_NF_REJECT_IPV6=m -CONFIG_NF_LOG_IPV6=m -CONFIG_IP6_NF_IPTABLES=m -# CONFIG_IP6_NF_MATCH_AH is not set -# CONFIG_IP6_NF_MATCH_EUI64 is not set -# CONFIG_IP6_NF_MATCH_FRAG is not set -# CONFIG_IP6_NF_MATCH_OPTS is not set -# CONFIG_IP6_NF_MATCH_HL is not set -CONFIG_IP6_NF_MATCH_IPV6HEADER=m -# CONFIG_IP6_NF_MATCH_MH is not set -# CONFIG_IP6_NF_MATCH_RPFILTER is not set -# CONFIG_IP6_NF_MATCH_RT is not set -# CONFIG_IP6_NF_MATCH_SRH is not set -# CONFIG_IP6_NF_TARGET_HL is not set -CONFIG_IP6_NF_FILTER=m -CONFIG_IP6_NF_TARGET_REJECT=m -# CONFIG_IP6_NF_TARGET_SYNPROXY is not set -CONFIG_IP6_NF_MANGLE=m -# CONFIG_IP6_NF_RAW is not set -# CONFIG_IP6_NF_SECURITY is not set -# CONFIG_IP6_NF_NAT is not set -# end of IPv6: Netfilter Configuration - -CONFIG_NF_DEFRAG_IPV6=m -# CONFIG_NF_CONNTRACK_BRIDGE is not set -# CONFIG_BRIDGE_NF_EBTABLES is not set -# CONFIG_BPFILTER is not set -# CONFIG_IP_DCCP is not set -# CONFIG_IP_SCTP is not set -# CONFIG_RDS is not set -# CONFIG_TIPC is not set -# CONFIG_ATM is not set -# CONFIG_L2TP is not set -CONFIG_STP=m -CONFIG_BRIDGE=m -CONFIG_BRIDGE_IGMP_SNOOPING=y -CONFIG_BRIDGE_VLAN_FILTERING=y -# CONFIG_BRIDGE_MRP is not set -# CONFIG_BRIDGE_CFM is not set -# CONFIG_NET_DSA is not set -CONFIG_VLAN_8021Q=m -# CONFIG_VLAN_8021Q_GVRP is not set -# CONFIG_VLAN_8021Q_MVRP is not set -CONFIG_LLC=m -# CONFIG_LLC2 is not set -# CONFIG_ATALK is not set -# CONFIG_X25 is not set -# CONFIG_LAPB is not set -# CONFIG_PHONET is not set -# CONFIG_6LOWPAN is not set -# CONFIG_IEEE802154 is not set -CONFIG_NET_SCHED=y - -# -# Queueing/Scheduling -# -# CONFIG_NET_SCH_HTB is not set -# CONFIG_NET_SCH_HFSC is not set -# CONFIG_NET_SCH_PRIO is not set -# CONFIG_NET_SCH_MULTIQ is not set -# CONFIG_NET_SCH_RED is not set -# CONFIG_NET_SCH_SFB is not set -# CONFIG_NET_SCH_SFQ is not set -# CONFIG_NET_SCH_TEQL is not set -# CONFIG_NET_SCH_TBF is not set -# CONFIG_NET_SCH_CBS is not set -# CONFIG_NET_SCH_ETF is not set -# CONFIG_NET_SCH_TAPRIO is not set -# CONFIG_NET_SCH_GRED is not set -# CONFIG_NET_SCH_NETEM is not set -# CONFIG_NET_SCH_DRR is not set -# CONFIG_NET_SCH_MQPRIO is not set -# CONFIG_NET_SCH_SKBPRIO is not set -# CONFIG_NET_SCH_CHOKE is not set -# CONFIG_NET_SCH_QFQ is not set -# CONFIG_NET_SCH_CODEL is not set -# CONFIG_NET_SCH_FQ_CODEL is not set -# CONFIG_NET_SCH_CAKE is not set -# CONFIG_NET_SCH_FQ is not set -# CONFIG_NET_SCH_HHF is not set -# CONFIG_NET_SCH_PIE is not set -# CONFIG_NET_SCH_PLUG is not set -# CONFIG_NET_SCH_ETS is not set -# CONFIG_NET_SCH_DEFAULT is not set - -# -# Classification -# -CONFIG_NET_CLS=y -# CONFIG_NET_CLS_BASIC is not set -# CONFIG_NET_CLS_ROUTE4 is not set -# CONFIG_NET_CLS_FW is not set -# CONFIG_NET_CLS_U32 is not set -# CONFIG_NET_CLS_FLOW is not set -CONFIG_NET_CLS_CGROUP=m -# CONFIG_NET_CLS_BPF is not set -# CONFIG_NET_CLS_FLOWER is not set -# CONFIG_NET_CLS_MATCHALL is not set -# CONFIG_NET_EMATCH is not set -# CONFIG_NET_CLS_ACT is not set -CONFIG_NET_SCH_FIFO=y -# CONFIG_DCB is not set -CONFIG_DNS_RESOLVER=y -# CONFIG_BATMAN_ADV is not set -# CONFIG_OPENVSWITCH is not set -# CONFIG_VSOCKETS is not set -CONFIG_NETLINK_DIAG=y -# CONFIG_MPLS is not set -# CONFIG_NET_NSH is not set -# CONFIG_HSR is not set -# CONFIG_NET_SWITCHDEV is not set -CONFIG_NET_L3_MASTER_DEV=y -# CONFIG_QRTR is not set -# CONFIG_NET_NCSI is not set -CONFIG_PCPU_DEV_REFCNT=y -CONFIG_MAX_SKB_FRAGS=17 -CONFIG_RPS=y -CONFIG_RFS_ACCEL=y -CONFIG_SOCK_RX_QUEUE_MAPPING=y -CONFIG_XPS=y -CONFIG_CGROUP_NET_PRIO=y -CONFIG_CGROUP_NET_CLASSID=y -CONFIG_NET_RX_BUSY_POLL=y -CONFIG_BQL=y -# CONFIG_BPF_STREAM_PARSER is not set -CONFIG_NET_FLOW_LIMIT=y - -# -# Network testing -# -# CONFIG_NET_PKTGEN is not set -# end of Network testing -# end of Networking options - -# CONFIG_HAMRADIO is not set -# CONFIG_CAN is not set -# CONFIG_BT is not set -# CONFIG_AF_RXRPC is not set -# CONFIG_AF_KCM is not set -# CONFIG_MCTP is not set -CONFIG_WIRELESS=y -# CONFIG_CFG80211 is not set - -# -# CFG80211 needs to be enabled for MAC80211 -# -CONFIG_MAC80211_STA_HASH_MAX_SIZE=0 -# CONFIG_RFKILL is not set -CONFIG_NET_9P=y -CONFIG_NET_9P_FD=y -CONFIG_NET_9P_VIRTIO=y -# CONFIG_NET_9P_DEBUG is not set -# CONFIG_CAIF is not set -# CONFIG_CEPH_LIB is not set -# CONFIG_NFC is not set -# CONFIG_PSAMPLE is not set -# CONFIG_NET_IFE is not set -# CONFIG_LWTUNNEL is not set -CONFIG_DST_CACHE=y -CONFIG_GRO_CELLS=y -CONFIG_NET_SELFTESTS=y -CONFIG_NET_SOCK_MSG=y -CONFIG_PAGE_POOL=y -# CONFIG_PAGE_POOL_STATS is not set -CONFIG_FAILOVER=y -CONFIG_ETHTOOL_NETLINK=y - -# -# Device Drivers -# -CONFIG_HAVE_PCI=y -CONFIG_PCI=y -CONFIG_PCI_DOMAINS=y -CONFIG_PCI_DOMAINS_GENERIC=y -CONFIG_PCIEPORTBUS=y -# CONFIG_PCIEAER is not set -CONFIG_PCIEASPM=y -CONFIG_PCIEASPM_DEFAULT=y -# CONFIG_PCIEASPM_POWERSAVE is not set -# CONFIG_PCIEASPM_POWER_SUPERSAVE is not set -# CONFIG_PCIEASPM_PERFORMANCE is not set -CONFIG_PCIE_PME=y -# CONFIG_PCIE_PTM is not set -CONFIG_PCI_MSI=y -CONFIG_PCI_QUIRKS=y -# CONFIG_PCI_DEBUG is not set -# CONFIG_PCI_STUB is not set -CONFIG_PCI_ECAM=y -# CONFIG_PCI_IOV is not set -# CONFIG_PCI_PRI is not set -# CONFIG_PCI_PASID is not set -CONFIG_PCI_LABEL=y -# CONFIG_PCIE_BUS_TUNE_OFF is not set -CONFIG_PCIE_BUS_DEFAULT=y -# CONFIG_PCIE_BUS_SAFE is not set -# CONFIG_PCIE_BUS_PERFORMANCE is not set -# CONFIG_PCIE_BUS_PEER2PEER is not set -CONFIG_VGA_ARB=y -CONFIG_VGA_ARB_MAX_GPUS=16 -# CONFIG_HOTPLUG_PCI is not set - -# -# PCI controller drivers -# -# CONFIG_PCI_FTPCI100 is not set -CONFIG_PCI_HOST_COMMON=y -CONFIG_PCI_HOST_GENERIC=y -CONFIG_PCIE_MICROCHIP_HOST=y -# CONFIG_PCIE_RCAR_HOST is not set -CONFIG_PCIE_XILINX=y - -# -# Cadence-based PCIe controllers -# -# CONFIG_PCIE_CADENCE_PLAT_HOST is not set -# CONFIG_PCI_J721E_HOST is not set -# end of Cadence-based PCIe controllers - -# -# DesignWare-based PCIe controllers -# -CONFIG_PCIE_DW=y -CONFIG_PCIE_DW_HOST=y -# CONFIG_PCI_MESON is not set -# CONFIG_PCIE_DW_PLAT_HOST is not set -CONFIG_PCIE_FU740=y -# end of DesignWare-based PCIe controllers - -# -# Mobiveil-based PCIe controllers -# -# end of Mobiveil-based PCIe controllers -# end of PCI controller drivers - -# -# PCI Endpoint -# -# CONFIG_PCI_ENDPOINT is not set -# end of PCI Endpoint - -# -# PCI switch controller drivers -# -# CONFIG_PCI_SW_SWITCHTEC is not set -# end of PCI switch controller drivers - -# CONFIG_CXL_BUS is not set -# CONFIG_PCCARD is not set -# CONFIG_RAPIDIO is not set - -# -# Generic Driver Options -# -CONFIG_AUXILIARY_BUS=y -# CONFIG_UEVENT_HELPER is not set -CONFIG_DEVTMPFS=y -CONFIG_DEVTMPFS_MOUNT=y -# CONFIG_DEVTMPFS_SAFE is not set -CONFIG_STANDALONE=y -CONFIG_PREVENT_FIRMWARE_BUILD=y - -# -# Firmware loader -# -CONFIG_FW_LOADER=y -CONFIG_EXTRA_FIRMWARE="" -# CONFIG_FW_LOADER_USER_HELPER is not set -# CONFIG_FW_LOADER_COMPRESS is not set -CONFIG_FW_CACHE=y -# CONFIG_FW_UPLOAD is not set -# end of Firmware loader - -CONFIG_WANT_DEV_COREDUMP=y -CONFIG_ALLOW_DEV_COREDUMP=y -CONFIG_DEV_COREDUMP=y -# CONFIG_DEBUG_DRIVER is not set -# CONFIG_DEBUG_DEVRES is not set -# CONFIG_DEBUG_TEST_DRIVER_REMOVE is not set -# CONFIG_TEST_ASYNC_DRIVER_PROBE is not set -CONFIG_SOC_BUS=y -CONFIG_REGMAP=y -CONFIG_REGMAP_I2C=y -CONFIG_REGMAP_MMIO=y -CONFIG_DMA_SHARED_BUFFER=y -# CONFIG_DMA_FENCE_TRACE is not set -CONFIG_GENERIC_ARCH_TOPOLOGY=y -# CONFIG_FW_DEVLINK_SYNC_STATE_TIMEOUT is not set -# end of Generic Driver Options - -# -# Bus devices -# -# CONFIG_MOXTET is not set -# CONFIG_SUN50I_DE2_BUS is not set -# CONFIG_SUNXI_RSB is not set -# CONFIG_MHI_BUS is not set -# CONFIG_MHI_BUS_EP is not set -# end of Bus devices - -# CONFIG_CONNECTOR is not set - -# -# Firmware Drivers -# - -# -# ARM System Control and Management Interface Protocol -# -# end of ARM System Control and Management Interface Protocol - -# CONFIG_FIRMWARE_MEMMAP is not set -# CONFIG_ISCSI_IBFT is not set -# CONFIG_SYSFB_SIMPLEFB is not set -# CONFIG_GOOGLE_FIRMWARE is not set - -# -# EFI (Extensible Firmware Interface) Support -# -CONFIG_EFI_ESRT=y -CONFIG_EFI_PARAMS_FROM_FDT=y -CONFIG_EFI_RUNTIME_WRAPPERS=y -CONFIG_EFI_GENERIC_STUB=y -# CONFIG_EFI_ZBOOT is not set -# CONFIG_EFI_BOOTLOADER_CONTROL is not set -# CONFIG_EFI_CAPSULE_LOADER is not set -# CONFIG_EFI_TEST is not set -# CONFIG_RESET_ATTACK_MITIGATION is not set -# CONFIG_EFI_DISABLE_PCI_DMA is not set -CONFIG_EFI_EARLYCON=y -# CONFIG_EFI_CUSTOM_SSDT_OVERLAYS is not set -# CONFIG_EFI_DISABLE_RUNTIME is not set -# CONFIG_EFI_COCO_SECRET is not set -# end of EFI (Extensible Firmware Interface) Support - -# -# Tegra firmware driver -# -# end of Tegra firmware driver -# end of Firmware Drivers - -# CONFIG_GNSS is not set -# CONFIG_MTD is not set -CONFIG_DTC=y -CONFIG_OF=y -# CONFIG_OF_UNITTEST is not set -CONFIG_OF_FLATTREE=y -CONFIG_OF_EARLY_FLATTREE=y -CONFIG_OF_KOBJ=y -CONFIG_OF_DYNAMIC=y -CONFIG_OF_ADDRESS=y -CONFIG_OF_IRQ=y -CONFIG_OF_RESERVED_MEM=y -CONFIG_OF_RESOLVE=y -CONFIG_OF_OVERLAY=y -# CONFIG_PARPORT is not set -CONFIG_PNP=y -CONFIG_PNP_DEBUG_MESSAGES=y - -# -# Protocols -# -CONFIG_PNPACPI=y -CONFIG_BLK_DEV=y -# CONFIG_BLK_DEV_NULL_BLK is not set -CONFIG_CDROM=y -# CONFIG_BLK_DEV_PCIESSD_MTIP32XX is not set -CONFIG_BLK_DEV_LOOP=y -CONFIG_BLK_DEV_LOOP_MIN_COUNT=8 -# CONFIG_BLK_DEV_DRBD is not set -# CONFIG_BLK_DEV_NBD is not set -# CONFIG_BLK_DEV_RAM is not set -# CONFIG_CDROM_PKTCDVD is not set -# CONFIG_ATA_OVER_ETH is not set -CONFIG_VIRTIO_BLK=y -# CONFIG_BLK_DEV_RBD is not set -# CONFIG_BLK_DEV_UBLK is not set - -# -# NVME Support -# -CONFIG_NVME_CORE=m -CONFIG_BLK_DEV_NVME=m -# CONFIG_NVME_MULTIPATH is not set -# CONFIG_NVME_VERBOSE_ERRORS is not set -# CONFIG_NVME_HWMON is not set -# CONFIG_NVME_FC is not set -# CONFIG_NVME_TCP is not set -# CONFIG_NVME_AUTH is not set -# CONFIG_NVME_TARGET is not set -# end of NVME Support - -# -# Misc devices -# -# CONFIG_AD525X_DPOT is not set -# CONFIG_DUMMY_IRQ is not set -# CONFIG_PHANTOM is not set -# CONFIG_TIFM_CORE is not set -# CONFIG_ICS932S401 is not set -# CONFIG_ENCLOSURE_SERVICES is not set -# CONFIG_HP_ILO is not set -# CONFIG_APDS9802ALS is not set -# CONFIG_ISL29003 is not set -# CONFIG_ISL29020 is not set -# CONFIG_SENSORS_TSL2550 is not set -# CONFIG_SENSORS_BH1770 is not set -# CONFIG_SENSORS_APDS990X is not set -# CONFIG_HMC6352 is not set -# CONFIG_DS1682 is not set -# CONFIG_LATTICE_ECP3_CONFIG is not set -# CONFIG_SRAM is not set -# CONFIG_DW_XDATA_PCIE is not set -# CONFIG_PCI_ENDPOINT_TEST is not set -# CONFIG_XILINX_SDFEC is not set -# CONFIG_OPEN_DICE is not set -# CONFIG_VCPU_STALL_DETECTOR is not set -# CONFIG_C2PORT is not set - -# -# EEPROM support -# -CONFIG_EEPROM_AT24=y -# CONFIG_EEPROM_AT25 is not set -# CONFIG_EEPROM_LEGACY is not set -# CONFIG_EEPROM_MAX6875 is not set -# CONFIG_EEPROM_93CX6 is not set -# CONFIG_EEPROM_93XX46 is not set -# CONFIG_EEPROM_IDT_89HPESX is not set -# CONFIG_EEPROM_EE1004 is not set -# end of EEPROM support - -# CONFIG_CB710_CORE is not set - -# -# Texas Instruments shared transport line discipline -# -# CONFIG_TI_ST is not set -# end of Texas Instruments shared transport line discipline - -# CONFIG_SENSORS_LIS3_I2C is not set -# CONFIG_ALTERA_STAPL is not set -# CONFIG_GENWQE is not set -# CONFIG_ECHO is not set -# CONFIG_BCM_VK is not set -# CONFIG_MISC_ALCOR_PCI is not set -# CONFIG_MISC_RTSX_PCI is not set -# CONFIG_MISC_RTSX_USB is not set -# CONFIG_UACCE is not set -# CONFIG_PVPANIC is not set -# CONFIG_GP_PCI1XXXX is not set -# end of Misc devices - -# -# SCSI device support -# -CONFIG_SCSI_MOD=y -# CONFIG_RAID_ATTRS is not set -CONFIG_SCSI_COMMON=y -CONFIG_SCSI=y -CONFIG_SCSI_DMA=y -CONFIG_SCSI_PROC_FS=y - -# -# SCSI support type (disk, tape, CD-ROM) -# -CONFIG_BLK_DEV_SD=y -# CONFIG_CHR_DEV_ST is not set -CONFIG_BLK_DEV_SR=y -# CONFIG_CHR_DEV_SG is not set -CONFIG_BLK_DEV_BSG=y -# CONFIG_CHR_DEV_SCH is not set -# CONFIG_SCSI_CONSTANTS is not set -# CONFIG_SCSI_LOGGING is not set -# CONFIG_SCSI_SCAN_ASYNC is not set - -# -# SCSI Transports -# -# CONFIG_SCSI_SPI_ATTRS is not set -# CONFIG_SCSI_FC_ATTRS is not set -# CONFIG_SCSI_ISCSI_ATTRS is not set -# CONFIG_SCSI_SAS_ATTRS is not set -# CONFIG_SCSI_SAS_LIBSAS is not set -# CONFIG_SCSI_SRP_ATTRS is not set -# end of SCSI Transports - -CONFIG_SCSI_LOWLEVEL=y -# CONFIG_ISCSI_TCP is not set -# CONFIG_ISCSI_BOOT_SYSFS is not set -# CONFIG_SCSI_CXGB3_ISCSI is not set -# CONFIG_SCSI_CXGB4_ISCSI is not set -# CONFIG_SCSI_BNX2_ISCSI is not set -# CONFIG_BE2ISCSI is not set -# CONFIG_BLK_DEV_3W_XXXX_RAID is not set -# CONFIG_SCSI_HPSA is not set -# CONFIG_SCSI_3W_9XXX is not set -# CONFIG_SCSI_3W_SAS is not set -# CONFIG_SCSI_ACARD is not set -# CONFIG_SCSI_AACRAID is not set -# CONFIG_SCSI_AIC7XXX is not set -# CONFIG_SCSI_AIC79XX is not set -# CONFIG_SCSI_AIC94XX is not set -# CONFIG_SCSI_MVSAS is not set -# CONFIG_SCSI_MVUMI is not set -# CONFIG_SCSI_ADVANSYS is not set -# CONFIG_SCSI_ARCMSR is not set -# CONFIG_SCSI_ESAS2R is not set -# CONFIG_MEGARAID_NEWGEN is not set -# CONFIG_MEGARAID_LEGACY is not set -# CONFIG_MEGARAID_SAS is not set -# CONFIG_SCSI_MPT3SAS is not set -# CONFIG_SCSI_MPT2SAS is not set -# CONFIG_SCSI_MPI3MR is not set -# CONFIG_SCSI_SMARTPQI is not set -# CONFIG_SCSI_HPTIOP is not set -# CONFIG_SCSI_BUSLOGIC is not set -# CONFIG_SCSI_MYRB is not set -# CONFIG_SCSI_MYRS is not set -# CONFIG_SCSI_SNIC is not set -# CONFIG_SCSI_DMX3191D is not set -# CONFIG_SCSI_FDOMAIN_PCI is not set -# CONFIG_SCSI_IPS is not set -# CONFIG_SCSI_INITIO is not set -# CONFIG_SCSI_INIA100 is not set -# CONFIG_SCSI_STEX is not set -# CONFIG_SCSI_SYM53C8XX_2 is not set -# CONFIG_SCSI_IPR is not set -# CONFIG_SCSI_QLOGIC_1280 is not set -# CONFIG_SCSI_QLA_ISCSI is not set -# CONFIG_SCSI_DC395x is not set -# CONFIG_SCSI_AM53C974 is not set -# CONFIG_SCSI_WD719X is not set -# CONFIG_SCSI_DEBUG is not set -# CONFIG_SCSI_PMCRAID is not set -# CONFIG_SCSI_PM8001 is not set -CONFIG_SCSI_VIRTIO=y -# CONFIG_SCSI_DH is not set -# end of SCSI device support - -CONFIG_ATA=y -CONFIG_SATA_HOST=y -CONFIG_PATA_TIMINGS=y -CONFIG_ATA_VERBOSE_ERROR=y -CONFIG_ATA_FORCE=y -CONFIG_ATA_ACPI=y -# CONFIG_SATA_ZPODD is not set -CONFIG_SATA_PMP=y - -# -# Controllers with non-SFF native interface -# -CONFIG_SATA_AHCI=y -CONFIG_SATA_MOBILE_LPM_POLICY=0 -CONFIG_SATA_AHCI_PLATFORM=y -# CONFIG_AHCI_DWC is not set -# CONFIG_AHCI_CEVA is not set -# CONFIG_AHCI_SUNXI is not set -# CONFIG_SATA_INIC162X is not set -# CONFIG_SATA_ACARD_AHCI is not set -# CONFIG_SATA_SIL24 is not set -CONFIG_ATA_SFF=y - -# -# SFF controllers with custom DMA interface -# -# CONFIG_PDC_ADMA is not set -# CONFIG_SATA_QSTOR is not set -# CONFIG_SATA_SX4 is not set -CONFIG_ATA_BMDMA=y - -# -# SATA SFF controllers with BMDMA -# -# CONFIG_ATA_PIIX is not set -# CONFIG_SATA_DWC is not set -# CONFIG_SATA_MV is not set -# CONFIG_SATA_NV is not set -# CONFIG_SATA_PROMISE is not set -# CONFIG_SATA_RCAR is not set -# CONFIG_SATA_SIL is not set -# CONFIG_SATA_SIS is not set -# CONFIG_SATA_SVW is not set -# CONFIG_SATA_ULI is not set -# CONFIG_SATA_VIA is not set -# CONFIG_SATA_VITESSE is not set - -# -# PATA SFF controllers with BMDMA -# -# CONFIG_PATA_ALI is not set -# CONFIG_PATA_AMD is not set -# CONFIG_PATA_ARTOP is not set -# CONFIG_PATA_ATIIXP is not set -# CONFIG_PATA_ATP867X is not set -# CONFIG_PATA_CMD64X is not set -# CONFIG_PATA_CYPRESS is not set -# CONFIG_PATA_EFAR is not set -# CONFIG_PATA_HPT366 is not set -# CONFIG_PATA_HPT37X is not set -# CONFIG_PATA_HPT3X2N is not set -# CONFIG_PATA_HPT3X3 is not set -# CONFIG_PATA_IT8213 is not set -# CONFIG_PATA_IT821X is not set -# CONFIG_PATA_JMICRON is not set -# CONFIG_PATA_MARVELL is not set -# CONFIG_PATA_NETCELL is not set -# CONFIG_PATA_NINJA32 is not set -# CONFIG_PATA_NS87415 is not set -# CONFIG_PATA_OLDPIIX is not set -# CONFIG_PATA_OPTIDMA is not set -# CONFIG_PATA_PDC2027X is not set -# CONFIG_PATA_PDC_OLD is not set -# CONFIG_PATA_RADISYS is not set -# CONFIG_PATA_RDC is not set -# CONFIG_PATA_SCH is not set -# CONFIG_PATA_SERVERWORKS is not set -# CONFIG_PATA_SIL680 is not set -# CONFIG_PATA_SIS is not set -# CONFIG_PATA_TOSHIBA is not set -# CONFIG_PATA_TRIFLEX is not set -# CONFIG_PATA_VIA is not set -# CONFIG_PATA_WINBOND is not set - -# -# PIO-only SFF controllers -# -# CONFIG_PATA_CMD640_PCI is not set -# CONFIG_PATA_MPIIX is not set -# CONFIG_PATA_NS87410 is not set -# CONFIG_PATA_OPTI is not set -# CONFIG_PATA_OF_PLATFORM is not set -# CONFIG_PATA_RZ1000 is not set - -# -# Generic fallback / legacy drivers -# -# CONFIG_PATA_ACPI is not set -# CONFIG_ATA_GENERIC is not set -# CONFIG_PATA_LEGACY is not set -CONFIG_MD=y -# CONFIG_BLK_DEV_MD is not set -# CONFIG_BCACHE is not set -CONFIG_BLK_DEV_DM_BUILTIN=y -CONFIG_BLK_DEV_DM=y -# CONFIG_DM_DEBUG is not set -CONFIG_DM_BUFIO=m -# CONFIG_DM_DEBUG_BLOCK_MANAGER_LOCKING is not set -CONFIG_DM_BIO_PRISON=m -CONFIG_DM_PERSISTENT_DATA=m -# CONFIG_DM_UNSTRIPED is not set -# CONFIG_DM_CRYPT is not set -# CONFIG_DM_SNAPSHOT is not set -CONFIG_DM_THIN_PROVISIONING=m -# CONFIG_DM_CACHE is not set -# CONFIG_DM_WRITECACHE is not set -# CONFIG_DM_EBS is not set -# CONFIG_DM_ERA is not set -# CONFIG_DM_CLONE is not set -# CONFIG_DM_MIRROR is not set -# CONFIG_DM_RAID is not set -# CONFIG_DM_ZERO is not set -# CONFIG_DM_MULTIPATH is not set -# CONFIG_DM_DELAY is not set -# CONFIG_DM_DUST is not set -# CONFIG_DM_INIT is not set -# CONFIG_DM_UEVENT is not set -# CONFIG_DM_FLAKEY is not set -# CONFIG_DM_VERITY is not set -# CONFIG_DM_SWITCH is not set -# CONFIG_DM_LOG_WRITES is not set -# CONFIG_DM_INTEGRITY is not set -# CONFIG_DM_AUDIT is not set -# CONFIG_TARGET_CORE is not set -# CONFIG_FUSION is not set - -# -# IEEE 1394 (FireWire) support -# -# CONFIG_FIREWIRE is not set -# CONFIG_FIREWIRE_NOSY is not set -# end of IEEE 1394 (FireWire) support - -CONFIG_NETDEVICES=y -CONFIG_MII=m -CONFIG_NET_CORE=y -# CONFIG_BONDING is not set -CONFIG_DUMMY=m -# CONFIG_WIREGUARD is not set -# CONFIG_EQUALIZER is not set -# CONFIG_NET_FC is not set -# CONFIG_NET_TEAM is not set -CONFIG_MACVLAN=m -# CONFIG_MACVTAP is not set -CONFIG_IPVLAN_L3S=y -CONFIG_IPVLAN=m -# CONFIG_IPVTAP is not set -CONFIG_VXLAN=m -# CONFIG_GENEVE is not set -# CONFIG_BAREUDP is not set -# CONFIG_GTP is not set -# CONFIG_AMT is not set -# CONFIG_MACSEC is not set -# CONFIG_NETCONSOLE is not set -# CONFIG_TUN is not set -# CONFIG_TUN_VNET_CROSS_LE is not set -CONFIG_VETH=m -CONFIG_VIRTIO_NET=y -# CONFIG_NLMON is not set -# CONFIG_ARCNET is not set -CONFIG_ETHERNET=y -CONFIG_NET_VENDOR_3COM=y -# CONFIG_VORTEX is not set -# CONFIG_TYPHOON is not set -CONFIG_NET_VENDOR_ADAPTEC=y -# CONFIG_ADAPTEC_STARFIRE is not set -CONFIG_NET_VENDOR_AGERE=y -# CONFIG_ET131X is not set -CONFIG_NET_VENDOR_ALACRITECH=y -# CONFIG_SLICOSS is not set -CONFIG_NET_VENDOR_ALLWINNER=y -# CONFIG_SUN4I_EMAC is not set -CONFIG_NET_VENDOR_ALTEON=y -# CONFIG_ACENIC is not set -# CONFIG_ALTERA_TSE is not set -CONFIG_NET_VENDOR_AMAZON=y -# CONFIG_ENA_ETHERNET is not set -CONFIG_NET_VENDOR_AMD=y -# CONFIG_AMD8111_ETH is not set -# CONFIG_PCNET32 is not set -# CONFIG_PDS_CORE is not set -CONFIG_NET_VENDOR_AQUANTIA=y -# CONFIG_AQTION is not set -CONFIG_NET_VENDOR_ARC=y -CONFIG_NET_VENDOR_ASIX=y -# CONFIG_SPI_AX88796C is not set -CONFIG_NET_VENDOR_ATHEROS=y -# CONFIG_ATL2 is not set -# CONFIG_ATL1 is not set -# CONFIG_ATL1E is not set -# CONFIG_ATL1C is not set -# CONFIG_ALX is not set -CONFIG_NET_VENDOR_BROADCOM=y -# CONFIG_B44 is not set -# CONFIG_BCMGENET is not set -# CONFIG_BNX2 is not set -# CONFIG_CNIC is not set -# CONFIG_TIGON3 is not set -# CONFIG_BNX2X is not set -# CONFIG_SYSTEMPORT is not set -# CONFIG_BNXT is not set -CONFIG_NET_VENDOR_CADENCE=y -CONFIG_MACB=y -# CONFIG_MACB_PCI is not set -CONFIG_NET_VENDOR_CAVIUM=y -# CONFIG_THUNDER_NIC_PF is not set -# CONFIG_THUNDER_NIC_VF is not set -# CONFIG_THUNDER_NIC_BGX is not set -# CONFIG_THUNDER_NIC_RGX is not set -# CONFIG_LIQUIDIO is not set -# CONFIG_LIQUIDIO_VF is not set -CONFIG_NET_VENDOR_CHELSIO=y -# CONFIG_CHELSIO_T1 is not set -# CONFIG_CHELSIO_T3 is not set -# CONFIG_CHELSIO_T4 is not set -# CONFIG_CHELSIO_T4VF is not set -CONFIG_NET_VENDOR_CISCO=y -# CONFIG_ENIC is not set -CONFIG_NET_VENDOR_CORTINA=y -# CONFIG_GEMINI_ETHERNET is not set -CONFIG_NET_VENDOR_DAVICOM=y -# CONFIG_DM9051 is not set -# CONFIG_DNET is not set -CONFIG_NET_VENDOR_DEC=y -# CONFIG_NET_TULIP is not set -CONFIG_NET_VENDOR_DLINK=y -# CONFIG_DL2K is not set -# CONFIG_SUNDANCE is not set -CONFIG_NET_VENDOR_EMULEX=y -# CONFIG_BE2NET is not set -CONFIG_NET_VENDOR_ENGLEDER=y -# CONFIG_TSNEP is not set -CONFIG_NET_VENDOR_EZCHIP=y -# CONFIG_EZCHIP_NPS_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_FUNGIBLE=y -# CONFIG_FUN_ETH is not set -CONFIG_NET_VENDOR_GOOGLE=y -CONFIG_NET_VENDOR_HUAWEI=y -CONFIG_NET_VENDOR_I825XX=y -CONFIG_NET_VENDOR_INTEL=y -# CONFIG_E100 is not set -# CONFIG_E1000 is not set -CONFIG_E1000E=y -# CONFIG_IGB is not set -# CONFIG_IGBVF is not set -# CONFIG_IXGBE is not set -# CONFIG_IXGBEVF is not set -# CONFIG_I40E is not set -# CONFIG_I40EVF is not set -# CONFIG_ICE is not set -# CONFIG_FM10K is not set -# CONFIG_IGC is not set -# CONFIG_JME is not set -CONFIG_NET_VENDOR_ADI=y -CONFIG_NET_VENDOR_LITEX=y -# CONFIG_LITEX_LITEETH is not set -CONFIG_NET_VENDOR_MARVELL=y -# CONFIG_MVMDIO is not set -# CONFIG_SKGE is not set -# CONFIG_SKY2 is not set -# CONFIG_OCTEON_EP is not set -CONFIG_NET_VENDOR_MELLANOX=y -# CONFIG_MLX4_EN is not set -# CONFIG_MLX5_CORE is not set -# CONFIG_MLXSW_CORE is not set -# CONFIG_MLXFW is not set -CONFIG_NET_VENDOR_MICREL=y -# CONFIG_KS8842 is not set -# CONFIG_KS8851 is not set -# CONFIG_KS8851_MLL is not set -# CONFIG_KSZ884X_PCI is not set -CONFIG_NET_VENDOR_MICROCHIP=y -# CONFIG_ENC28J60 is not set -# CONFIG_ENCX24J600 is not set -# CONFIG_LAN743X is not set -# CONFIG_VCAP is not set -CONFIG_NET_VENDOR_MICROSEMI=y -CONFIG_NET_VENDOR_MICROSOFT=y -CONFIG_NET_VENDOR_MYRI=y -# CONFIG_MYRI10GE is not set -# CONFIG_FEALNX is not set -CONFIG_NET_VENDOR_NI=y -# CONFIG_NI_XGE_MANAGEMENT_ENET is not set -CONFIG_NET_VENDOR_NATSEMI=y -# CONFIG_NATSEMI is not set -# CONFIG_NS83820 is not set -CONFIG_NET_VENDOR_NETERION=y -# CONFIG_S2IO is not set -CONFIG_NET_VENDOR_NETRONOME=y -# CONFIG_NFP is not set -CONFIG_NET_VENDOR_8390=y -# CONFIG_NE2K_PCI is not set -CONFIG_NET_VENDOR_NVIDIA=y -# CONFIG_FORCEDETH is not set -CONFIG_NET_VENDOR_OKI=y -# CONFIG_ETHOC is not set -CONFIG_NET_VENDOR_PACKET_ENGINES=y -# CONFIG_HAMACHI is not set -# CONFIG_YELLOWFIN is not set -CONFIG_NET_VENDOR_PENSANDO=y -# CONFIG_IONIC is not set -CONFIG_NET_VENDOR_QLOGIC=y -# CONFIG_QLA3XXX is not set -# CONFIG_QLCNIC is not set -# CONFIG_NETXEN_NIC is not set -# CONFIG_QED is not set -CONFIG_NET_VENDOR_BROCADE=y -# CONFIG_BNA is not set -CONFIG_NET_VENDOR_QUALCOMM=y -# CONFIG_QCA7000_SPI is not set -# CONFIG_QCOM_EMAC is not set -# CONFIG_RMNET is not set -CONFIG_NET_VENDOR_RDC=y -# CONFIG_R6040 is not set -CONFIG_NET_VENDOR_REALTEK=y -# CONFIG_8139CP is not set -# CONFIG_8139TOO is not set -CONFIG_R8169=y -CONFIG_NET_VENDOR_RENESAS=y -# CONFIG_SH_ETH is not set -# CONFIG_RAVB is not set -# CONFIG_RENESAS_ETHER_SWITCH is not set -CONFIG_NET_VENDOR_ROCKER=y -CONFIG_NET_VENDOR_SAMSUNG=y -# CONFIG_SXGBE_ETH is not set -CONFIG_NET_VENDOR_SEEQ=y -CONFIG_NET_VENDOR_SILAN=y -# CONFIG_SC92031 is not set -CONFIG_NET_VENDOR_SIS=y -# CONFIG_SIS900 is not set -# CONFIG_SIS190 is not set -CONFIG_NET_VENDOR_SOLARFLARE=y -# CONFIG_SFC is not set -# CONFIG_SFC_FALCON is not set -CONFIG_NET_VENDOR_SMSC=y -# CONFIG_EPIC100 is not set -# CONFIG_SMSC911X is not set -# CONFIG_SMSC9420 is not set -CONFIG_NET_VENDOR_SOCIONEXT=y -CONFIG_NET_VENDOR_STMICRO=y -CONFIG_STMMAC_ETH=m -# CONFIG_STMMAC_SELFTESTS is not set -CONFIG_STMMAC_PLATFORM=m -# CONFIG_DWMAC_DWC_QOS_ETH is not set -CONFIG_DWMAC_GENERIC=m -CONFIG_DWMAC_STARFIVE=m -CONFIG_DWMAC_SUNXI=m -CONFIG_DWMAC_SUN8I=m -# CONFIG_DWMAC_INTEL_PLAT is not set -# CONFIG_DWMAC_LOONGSON is not set -# CONFIG_STMMAC_PCI is not set -CONFIG_NET_VENDOR_SUN=y -# CONFIG_HAPPYMEAL is not set -# CONFIG_SUNGEM is not set -# CONFIG_CASSINI is not set -# CONFIG_NIU is not set -CONFIG_NET_VENDOR_SYNOPSYS=y -# CONFIG_DWC_XLGMAC is not set -CONFIG_NET_VENDOR_TEHUTI=y -# CONFIG_TEHUTI is not set -CONFIG_NET_VENDOR_TI=y -# CONFIG_TI_CPSW_PHY_SEL is not set -# CONFIG_TLAN is not set -CONFIG_NET_VENDOR_VERTEXCOM=y -# CONFIG_MSE102X is not set -CONFIG_NET_VENDOR_VIA=y -# CONFIG_VIA_RHINE is not set -# CONFIG_VIA_VELOCITY is not set -CONFIG_NET_VENDOR_WANGXUN=y -# CONFIG_NGBE is not set -# CONFIG_TXGBE is not set -CONFIG_NET_VENDOR_WIZNET=y -# CONFIG_WIZNET_W5100 is not set -# CONFIG_WIZNET_W5300 is not set -CONFIG_NET_VENDOR_XILINX=y -# CONFIG_XILINX_EMACLITE is not set -# CONFIG_XILINX_AXI_EMAC is not set -# CONFIG_XILINX_LL_TEMAC is not set -# CONFIG_FDDI is not set -# CONFIG_HIPPI is not set -# CONFIG_NET_SB1000 is not set -CONFIG_PHYLINK=y -CONFIG_PHYLIB=y -CONFIG_SWPHY=y -CONFIG_FIXED_PHY=y -# CONFIG_SFP is not set - -# -# MII PHY device drivers -# -# CONFIG_AMD_PHY is not set -# CONFIG_ADIN_PHY is not set -# CONFIG_ADIN1100_PHY is not set -# CONFIG_AQUANTIA_PHY is not set -# CONFIG_AX88796B_PHY is not set -# CONFIG_BROADCOM_PHY is not set -# CONFIG_BCM54140_PHY is not set -# CONFIG_BCM7XXX_PHY is not set -# CONFIG_BCM84881_PHY is not set -# CONFIG_BCM87XX_PHY is not set -# CONFIG_CICADA_PHY is not set -# CONFIG_CORTINA_PHY is not set -# CONFIG_DAVICOM_PHY is not set -# CONFIG_ICPLUS_PHY is not set -# CONFIG_LXT_PHY is not set -# CONFIG_INTEL_XWAY_PHY is not set -# CONFIG_LSI_ET1011C_PHY is not set -# CONFIG_MARVELL_PHY is not set -# CONFIG_MARVELL_10G_PHY is not set -# CONFIG_MARVELL_88X2222_PHY is not set -# CONFIG_MAXLINEAR_GPHY is not set -# CONFIG_MEDIATEK_GE_PHY is not set -# CONFIG_MICREL_PHY is not set -# CONFIG_MICROCHIP_T1S_PHY is not set -# CONFIG_MICROCHIP_PHY is not set -# CONFIG_MICROCHIP_T1_PHY is not set -CONFIG_MICROSEMI_PHY=y -# CONFIG_MOTORCOMM_PHY is not set -# CONFIG_NATIONAL_PHY is not set -# CONFIG_NXP_CBTX_PHY is not set -# CONFIG_NXP_C45_TJA11XX_PHY is not set -# CONFIG_NXP_TJA11XX_PHY is not set -# CONFIG_NCN26000_PHY is not set -# CONFIG_AT803X_PHY is not set -# CONFIG_QSEMI_PHY is not set -CONFIG_REALTEK_PHY=y -# CONFIG_RENESAS_PHY is not set -# CONFIG_ROCKCHIP_PHY is not set -# CONFIG_SMSC_PHY is not set -# CONFIG_STE10XP is not set -# CONFIG_TERANETICS_PHY is not set -# CONFIG_DP83822_PHY is not set -# CONFIG_DP83TC811_PHY is not set -# CONFIG_DP83848_PHY is not set -# CONFIG_DP83867_PHY is not set -# CONFIG_DP83869_PHY is not set -# CONFIG_DP83TD510_PHY is not set -# CONFIG_VITESSE_PHY is not set -# CONFIG_XILINX_GMII2RGMII is not set -# CONFIG_MICREL_KS8995MA is not set -# CONFIG_PSE_CONTROLLER is not set -CONFIG_MDIO_DEVICE=y -CONFIG_MDIO_BUS=y -CONFIG_FWNODE_MDIO=y -CONFIG_OF_MDIO=y -CONFIG_ACPI_MDIO=y -CONFIG_MDIO_DEVRES=y -# CONFIG_MDIO_SUN4I is not set -# CONFIG_MDIO_BITBANG is not set -# CONFIG_MDIO_BCM_UNIMAC is not set -# CONFIG_MDIO_HISI_FEMAC is not set -# CONFIG_MDIO_MVUSB is not set -# CONFIG_MDIO_MSCC_MIIM is not set -# CONFIG_MDIO_OCTEON is not set -# CONFIG_MDIO_IPQ4019 is not set -# CONFIG_MDIO_IPQ8064 is not set -# CONFIG_MDIO_THUNDER is not set - -# -# MDIO Multiplexers -# -CONFIG_MDIO_BUS_MUX=m -# CONFIG_MDIO_BUS_MUX_GPIO is not set -# CONFIG_MDIO_BUS_MUX_MULTIPLEXER is not set -# CONFIG_MDIO_BUS_MUX_MMIOREG is not set - -# -# PCS device drivers -# -CONFIG_PCS_XPCS=m -# end of PCS device drivers - -# CONFIG_PPP is not set -# CONFIG_SLIP is not set -CONFIG_USB_NET_DRIVERS=y -# CONFIG_USB_CATC is not set -# CONFIG_USB_KAWETH is not set -# CONFIG_USB_PEGASUS is not set -# CONFIG_USB_RTL8150 is not set -# CONFIG_USB_RTL8152 is not set -# CONFIG_USB_LAN78XX is not set -# CONFIG_USB_USBNET is not set -# CONFIG_USB_IPHETH is not set -CONFIG_WLAN=y -CONFIG_WLAN_VENDOR_ADMTEK=y -CONFIG_WLAN_VENDOR_ATH=y -# CONFIG_ATH_DEBUG is not set -# CONFIG_ATH5K_PCI is not set -CONFIG_WLAN_VENDOR_ATMEL=y -CONFIG_WLAN_VENDOR_BROADCOM=y -CONFIG_WLAN_VENDOR_CISCO=y -CONFIG_WLAN_VENDOR_INTEL=y -CONFIG_WLAN_VENDOR_INTERSIL=y -# CONFIG_HOSTAP is not set -CONFIG_WLAN_VENDOR_MARVELL=y -CONFIG_WLAN_VENDOR_MEDIATEK=y -CONFIG_WLAN_VENDOR_MICROCHIP=y -CONFIG_WLAN_VENDOR_PURELIFI=y -CONFIG_WLAN_VENDOR_RALINK=y -CONFIG_WLAN_VENDOR_REALTEK=y -CONFIG_WLAN_VENDOR_RSI=y -CONFIG_WLAN_VENDOR_SILABS=y -CONFIG_WLAN_VENDOR_ST=y -CONFIG_WLAN_VENDOR_TI=y -CONFIG_WLAN_VENDOR_ZYDAS=y -CONFIG_WLAN_VENDOR_QUANTENNA=y -# CONFIG_WAN is not set - -# -# Wireless WAN -# -# CONFIG_WWAN is not set -# end of Wireless WAN - -# CONFIG_VMXNET3 is not set -# CONFIG_FUJITSU_ES is not set -# CONFIG_NETDEVSIM is not set -CONFIG_NET_FAILOVER=y -# CONFIG_ISDN is not set - -# -# Input device support -# -CONFIG_INPUT=y -# CONFIG_INPUT_FF_MEMLESS is not set -# CONFIG_INPUT_SPARSEKMAP is not set -# CONFIG_INPUT_MATRIXKMAP is not set -CONFIG_INPUT_VIVALDIFMAP=y - -# -# Userland interfaces -# -CONFIG_INPUT_MOUSEDEV=y -# CONFIG_INPUT_MOUSEDEV_PSAUX is not set -CONFIG_INPUT_MOUSEDEV_SCREEN_X=1024 -CONFIG_INPUT_MOUSEDEV_SCREEN_Y=768 -# CONFIG_INPUT_JOYDEV is not set -# CONFIG_INPUT_EVDEV is not set -# CONFIG_INPUT_EVBUG is not set - -# -# Input Device Drivers -# -CONFIG_INPUT_KEYBOARD=y -# CONFIG_KEYBOARD_ADC is not set -# CONFIG_KEYBOARD_ADP5588 is not set -# CONFIG_KEYBOARD_ADP5589 is not set -CONFIG_KEYBOARD_ATKBD=y -# CONFIG_KEYBOARD_QT1050 is not set -# CONFIG_KEYBOARD_QT1070 is not set -# CONFIG_KEYBOARD_QT2160 is not set -# CONFIG_KEYBOARD_DLINK_DIR685 is not set -# CONFIG_KEYBOARD_LKKBD is not set -# CONFIG_KEYBOARD_GPIO is not set -# CONFIG_KEYBOARD_GPIO_POLLED is not set -# CONFIG_KEYBOARD_TCA6416 is not set -# CONFIG_KEYBOARD_TCA8418 is not set -# CONFIG_KEYBOARD_MATRIX is not set -# CONFIG_KEYBOARD_LM8333 is not set -# CONFIG_KEYBOARD_MAX7359 is not set -# CONFIG_KEYBOARD_MCS is not set -# CONFIG_KEYBOARD_MPR121 is not set -# CONFIG_KEYBOARD_NEWTON is not set -# CONFIG_KEYBOARD_OPENCORES is not set -# CONFIG_KEYBOARD_PINEPHONE is not set -# CONFIG_KEYBOARD_SAMSUNG is not set -# CONFIG_KEYBOARD_GOLDFISH_EVENTS is not set -# CONFIG_KEYBOARD_STOWAWAY is not set -# CONFIG_KEYBOARD_SUNKBD is not set -CONFIG_KEYBOARD_SUN4I_LRADC=m -# CONFIG_KEYBOARD_OMAP4 is not set -# CONFIG_KEYBOARD_XTKBD is not set -# CONFIG_KEYBOARD_CAP11XX is not set -# CONFIG_KEYBOARD_BCM is not set -# CONFIG_KEYBOARD_CYPRESS_SF is not set -CONFIG_INPUT_MOUSE=y -CONFIG_MOUSE_PS2=y -CONFIG_MOUSE_PS2_ALPS=y -CONFIG_MOUSE_PS2_BYD=y -CONFIG_MOUSE_PS2_LOGIPS2PP=y -CONFIG_MOUSE_PS2_SYNAPTICS=y -CONFIG_MOUSE_PS2_SYNAPTICS_SMBUS=y -CONFIG_MOUSE_PS2_CYPRESS=y -CONFIG_MOUSE_PS2_TRACKPOINT=y -# CONFIG_MOUSE_PS2_ELANTECH is not set -# CONFIG_MOUSE_PS2_SENTELIC is not set -# CONFIG_MOUSE_PS2_TOUCHKIT is not set -CONFIG_MOUSE_PS2_FOCALTECH=y -CONFIG_MOUSE_PS2_SMBUS=y -# CONFIG_MOUSE_SERIAL is not set -# CONFIG_MOUSE_APPLETOUCH is not set -# CONFIG_MOUSE_BCM5974 is not set -# CONFIG_MOUSE_CYAPA is not set -# CONFIG_MOUSE_ELAN_I2C is not set -# CONFIG_MOUSE_VSXXXAA is not set -# CONFIG_MOUSE_GPIO is not set -# CONFIG_MOUSE_SYNAPTICS_I2C is not set -# CONFIG_MOUSE_SYNAPTICS_USB is not set -# CONFIG_INPUT_JOYSTICK is not set -# CONFIG_INPUT_TABLET is not set -# CONFIG_INPUT_TOUCHSCREEN is not set -# CONFIG_INPUT_MISC is not set -# CONFIG_RMI4_CORE is not set - -# -# Hardware I/O ports -# -CONFIG_SERIO=y -CONFIG_SERIO_SERPORT=y -# CONFIG_SERIO_PCIPS2 is not set -CONFIG_SERIO_LIBPS2=y -# CONFIG_SERIO_RAW is not set -# CONFIG_SERIO_ALTERA_PS2 is not set -# CONFIG_SERIO_PS2MULT is not set -# CONFIG_SERIO_ARC_PS2 is not set -# CONFIG_SERIO_APBPS2 is not set -# CONFIG_SERIO_SUN4I_PS2 is not set -# CONFIG_SERIO_GPIO_PS2 is not set -# CONFIG_USERIO is not set -# CONFIG_GAMEPORT is not set -# end of Hardware I/O ports -# end of Input device support - -# -# Character devices -# -CONFIG_TTY=y -CONFIG_VT=y -CONFIG_CONSOLE_TRANSLATIONS=y -CONFIG_VT_CONSOLE=y -CONFIG_VT_CONSOLE_SLEEP=y -CONFIG_HW_CONSOLE=y -CONFIG_VT_HW_CONSOLE_BINDING=y -CONFIG_UNIX98_PTYS=y -CONFIG_LEGACY_PTYS=y -CONFIG_LEGACY_PTY_COUNT=256 -CONFIG_LEGACY_TIOCSTI=y -CONFIG_LDISC_AUTOLOAD=y - -# -# Serial drivers -# -CONFIG_SERIAL_EARLYCON=y -CONFIG_SERIAL_8250=y -CONFIG_SERIAL_8250_DEPRECATED_OPTIONS=y -CONFIG_SERIAL_8250_PNP=y -CONFIG_SERIAL_8250_16550A_VARIANTS=y -# CONFIG_SERIAL_8250_FINTEK is not set -CONFIG_SERIAL_8250_CONSOLE=y -CONFIG_SERIAL_8250_DMA=y -CONFIG_SERIAL_8250_PCILIB=y -CONFIG_SERIAL_8250_PCI=y -CONFIG_SERIAL_8250_EXAR=y -CONFIG_SERIAL_8250_NR_UARTS=4 -CONFIG_SERIAL_8250_RUNTIME_UARTS=4 -# CONFIG_SERIAL_8250_EXTENDED is not set -# CONFIG_SERIAL_8250_PCI1XXXX is not set -CONFIG_SERIAL_8250_DWLIB=y -CONFIG_SERIAL_8250_DW=y -# CONFIG_SERIAL_8250_EM is not set -# CONFIG_SERIAL_8250_RT288X is not set -CONFIG_SERIAL_8250_PERICOM=y -CONFIG_SERIAL_OF_PLATFORM=y - -# -# Non-8250 serial port support -# -# CONFIG_SERIAL_EARLYCON_SEMIHOST is not set -# CONFIG_SERIAL_MAX3100 is not set -# CONFIG_SERIAL_MAX310X is not set -# CONFIG_SERIAL_UARTLITE is not set -CONFIG_SERIAL_SH_SCI=y -CONFIG_SERIAL_SH_SCI_NR_UARTS=18 -CONFIG_SERIAL_SH_SCI_CONSOLE=y -CONFIG_SERIAL_SH_SCI_EARLYCON=y -CONFIG_SERIAL_SH_SCI_DMA=y -CONFIG_SERIAL_CORE=y -CONFIG_SERIAL_CORE_CONSOLE=y -# CONFIG_SERIAL_JSM is not set -CONFIG_SERIAL_SIFIVE=y -CONFIG_SERIAL_SIFIVE_CONSOLE=y -# CONFIG_SERIAL_SCCNXP is not set -# CONFIG_SERIAL_SC16IS7XX is not set -# CONFIG_SERIAL_ALTERA_JTAGUART is not set -# CONFIG_SERIAL_ALTERA_UART is not set -# CONFIG_SERIAL_XILINX_PS_UART is not set -# CONFIG_SERIAL_ARC is not set -# CONFIG_SERIAL_RP2 is not set -# CONFIG_SERIAL_FSL_LPUART is not set -# CONFIG_SERIAL_FSL_LINFLEXUART is not set -# CONFIG_SERIAL_CONEXANT_DIGICOLOR is not set -# CONFIG_SERIAL_SPRD is not set -# end of Serial drivers - -CONFIG_SERIAL_MCTRL_GPIO=y -# CONFIG_SERIAL_NONSTANDARD is not set -# CONFIG_GOLDFISH_TTY is not set -# CONFIG_N_GSM is not set -# CONFIG_NOZOMI is not set -# CONFIG_NULL_TTY is not set -CONFIG_HVC_DRIVER=y -# CONFIG_RPMSG_TTY is not set -# CONFIG_SERIAL_DEV_BUS is not set -# CONFIG_TTY_PRINTK is not set -CONFIG_VIRTIO_CONSOLE=y -# CONFIG_IPMI_HANDLER is not set -CONFIG_HW_RANDOM=y -# CONFIG_HW_RANDOM_TIMERIOMEM is not set -# CONFIG_HW_RANDOM_BA431 is not set -CONFIG_HW_RANDOM_VIRTIO=y -CONFIG_HW_RANDOM_POLARFIRE_SOC=y -# CONFIG_HW_RANDOM_CCTRNG is not set -# CONFIG_HW_RANDOM_XIPHERA is not set -# CONFIG_HW_RANDOM_JH7110 is not set -# CONFIG_APPLICOM is not set -CONFIG_DEVMEM=y -CONFIG_DEVPORT=y -# CONFIG_TCG_TPM is not set -# CONFIG_XILLYBUS is not set -# CONFIG_XILLYUSB is not set -# end of Character devices - -# -# I2C support -# -CONFIG_I2C=y -CONFIG_ACPI_I2C_OPREGION=y -CONFIG_I2C_BOARDINFO=y -CONFIG_I2C_COMPAT=y -# CONFIG_I2C_CHARDEV is not set -CONFIG_I2C_MUX=m - -# -# Multiplexer I2C Chip support -# -# CONFIG_I2C_ARB_GPIO_CHALLENGE is not set -# CONFIG_I2C_MUX_GPIO is not set -# CONFIG_I2C_MUX_GPMUX is not set -# CONFIG_I2C_MUX_LTC4306 is not set -# CONFIG_I2C_MUX_PCA9541 is not set -# CONFIG_I2C_MUX_PCA954x is not set -# CONFIG_I2C_MUX_PINCTRL is not set -# CONFIG_I2C_MUX_REG is not set -# CONFIG_I2C_DEMUX_PINCTRL is not set -# CONFIG_I2C_MUX_MLXCPLD is not set -# end of Multiplexer I2C Chip support - -CONFIG_I2C_HELPER_AUTO=y - -# -# I2C Hardware Bus support -# - -# -# PC SMBus host controller drivers -# -# CONFIG_I2C_ALI1535 is not set -# CONFIG_I2C_ALI1563 is not set -# CONFIG_I2C_ALI15X3 is not set -# CONFIG_I2C_AMD756 is not set -# CONFIG_I2C_AMD8111 is not set -# CONFIG_I2C_AMD_MP2 is not set -# CONFIG_I2C_I801 is not set -# CONFIG_I2C_ISCH is not set -# CONFIG_I2C_PIIX4 is not set -# CONFIG_I2C_NFORCE2 is not set -# CONFIG_I2C_NVIDIA_GPU is not set -# CONFIG_I2C_SIS5595 is not set -# CONFIG_I2C_SIS630 is not set -# CONFIG_I2C_SIS96X is not set -# CONFIG_I2C_VIA is not set -# CONFIG_I2C_VIAPRO is not set - -# -# ACPI drivers -# -# CONFIG_I2C_SCMI is not set - -# -# I2C system bus drivers (mostly embedded / system-on-chip) -# -# CONFIG_I2C_CBUS_GPIO is not set -# CONFIG_I2C_DESIGNWARE_PLATFORM is not set -# CONFIG_I2C_DESIGNWARE_PCI is not set -# CONFIG_I2C_EMEV2 is not set -# CONFIG_I2C_GPIO is not set -CONFIG_I2C_MICROCHIP_CORE=y -CONFIG_I2C_MV64XXX=m -# CONFIG_I2C_OCORES is not set -# CONFIG_I2C_PCA_PLATFORM is not set -# CONFIG_I2C_RIIC is not set -# CONFIG_I2C_RK3X is not set -# CONFIG_I2C_RZV2M is not set -# CONFIG_I2C_SH_MOBILE is not set -# CONFIG_I2C_SIMTEC is not set -# CONFIG_I2C_XILINX is not set -# CONFIG_I2C_RCAR is not set - -# -# External I2C/SMBus adapter drivers -# -# CONFIG_I2C_DIOLAN_U2C is not set -# CONFIG_I2C_CP2615 is not set -# CONFIG_I2C_PCI1XXXX is not set -# CONFIG_I2C_ROBOTFUZZ_OSIF is not set -# CONFIG_I2C_TAOS_EVM is not set -# CONFIG_I2C_TINY_USB is not set - -# -# Other I2C/SMBus bus drivers -# -# CONFIG_I2C_VIRTIO is not set -# end of I2C Hardware Bus support - -# CONFIG_I2C_STUB is not set -# CONFIG_I2C_SLAVE is not set -# CONFIG_I2C_DEBUG_CORE is not set -# CONFIG_I2C_DEBUG_ALGO is not set -# CONFIG_I2C_DEBUG_BUS is not set -# end of I2C support - -# CONFIG_I3C is not set -CONFIG_SPI=y -# CONFIG_SPI_DEBUG is not set -CONFIG_SPI_MASTER=y -# CONFIG_SPI_MEM is not set - -# -# SPI Master Controller Drivers -# -# CONFIG_SPI_ALTERA is not set -# CONFIG_SPI_AXI_SPI_ENGINE is not set -# CONFIG_SPI_BITBANG is not set -# CONFIG_SPI_CADENCE is not set -# CONFIG_SPI_CADENCE_QUADSPI is not set -# CONFIG_SPI_DESIGNWARE is not set -# CONFIG_SPI_GPIO is not set -# CONFIG_SPI_FSL_SPI is not set -CONFIG_SPI_MICROCHIP_CORE=y -CONFIG_SPI_MICROCHIP_CORE_QSPI=y -# CONFIG_SPI_OC_TINY is not set -# CONFIG_SPI_PCI1XXXX is not set -# CONFIG_SPI_PXA2XX is not set -# CONFIG_SPI_RSPI is not set -# CONFIG_SPI_RZV2M_CSI is not set -# CONFIG_SPI_SC18IS602 is not set -# CONFIG_SPI_SH_MSIOF is not set -# CONFIG_SPI_SH_HSPI is not set -CONFIG_SPI_SIFIVE=y -# CONFIG_SPI_SUN4I is not set -CONFIG_SPI_SUN6I=y -# CONFIG_SPI_MXIC is not set -# CONFIG_SPI_XCOMM is not set -# CONFIG_SPI_XILINX is not set -# CONFIG_SPI_ZYNQMP_GQSPI is not set -# CONFIG_SPI_AMD is not set - -# -# SPI Multiplexer support -# -# CONFIG_SPI_MUX is not set - -# -# SPI Protocol Masters -# -CONFIG_SPI_SPIDEV=m -# CONFIG_SPI_LOOPBACK_TEST is not set -# CONFIG_SPI_TLE62X0 is not set -# CONFIG_SPI_SLAVE is not set -CONFIG_SPI_DYNAMIC=y -# CONFIG_SPMI is not set -# CONFIG_HSI is not set -# CONFIG_PPS is not set - -# -# PTP clock support -# -# CONFIG_PTP_1588_CLOCK is not set -CONFIG_PTP_1588_CLOCK_OPTIONAL=y - -# -# Enable PHYLIB and NETWORK_PHY_TIMESTAMPING to see the additional clocks. -# -# end of PTP clock support - -CONFIG_PINCTRL=y -CONFIG_GENERIC_PINCTRL_GROUPS=y -CONFIG_PINMUX=y -CONFIG_GENERIC_PINMUX_FUNCTIONS=y -CONFIG_PINCONF=y -CONFIG_GENERIC_PINCONF=y -# CONFIG_DEBUG_PINCTRL is not set -# CONFIG_PINCTRL_AMD is not set -# CONFIG_PINCTRL_CY8C95X0 is not set -# CONFIG_PINCTRL_MCP23S08 is not set -# CONFIG_PINCTRL_MICROCHIP_SGPIO is not set -# CONFIG_PINCTRL_OCELOT is not set -# CONFIG_PINCTRL_SINGLE is not set -# CONFIG_PINCTRL_STMFX is not set -# CONFIG_PINCTRL_SX150X is not set - -# -# Renesas pinctrl drivers -# -CONFIG_PINCTRL_RENESAS=y -CONFIG_PINCTRL_RZG2L=y -# end of Renesas pinctrl drivers - -CONFIG_PINCTRL_STARFIVE_JH7100=y -CONFIG_PINCTRL_STARFIVE_JH7110=y -CONFIG_PINCTRL_STARFIVE_JH7110_SYS=y -CONFIG_PINCTRL_STARFIVE_JH7110_AON=y -CONFIG_PINCTRL_SUNXI=y -# CONFIG_PINCTRL_SUN4I_A10 is not set -# CONFIG_PINCTRL_SUN5I is not set -# CONFIG_PINCTRL_SUN6I_A31 is not set -# CONFIG_PINCTRL_SUN6I_A31_R is not set -# CONFIG_PINCTRL_SUN8I_A23 is not set -# CONFIG_PINCTRL_SUN8I_A33 is not set -# CONFIG_PINCTRL_SUN8I_A83T is not set -# CONFIG_PINCTRL_SUN8I_A83T_R is not set -# CONFIG_PINCTRL_SUN8I_A23_R is not set -# CONFIG_PINCTRL_SUN8I_H3 is not set -# CONFIG_PINCTRL_SUN8I_H3_R is not set -# CONFIG_PINCTRL_SUN8I_V3S is not set -# CONFIG_PINCTRL_SUN9I_A80 is not set -# CONFIG_PINCTRL_SUN9I_A80_R is not set -CONFIG_PINCTRL_SUN20I_D1=y -# CONFIG_PINCTRL_SUN50I_A64 is not set -# CONFIG_PINCTRL_SUN50I_A64_R is not set -# CONFIG_PINCTRL_SUN50I_A100 is not set -# CONFIG_PINCTRL_SUN50I_A100_R is not set -# CONFIG_PINCTRL_SUN50I_H5 is not set -# CONFIG_PINCTRL_SUN50I_H6 is not set -# CONFIG_PINCTRL_SUN50I_H6_R is not set -# CONFIG_PINCTRL_SUN50I_H616 is not set -# CONFIG_PINCTRL_SUN50I_H616_R is not set -CONFIG_GPIOLIB=y -CONFIG_GPIOLIB_FASTPATH_LIMIT=512 -CONFIG_OF_GPIO=y -CONFIG_GPIO_ACPI=y -CONFIG_GPIOLIB_IRQCHIP=y -# CONFIG_DEBUG_GPIO is not set -CONFIG_GPIO_SYSFS=y -CONFIG_GPIO_CDEV=y -CONFIG_GPIO_CDEV_V1=y -CONFIG_GPIO_GENERIC=y - -# -# Memory mapped GPIO drivers -# -# CONFIG_GPIO_74XX_MMIO is not set -# CONFIG_GPIO_ALTERA is not set -# CONFIG_GPIO_AMDPT is not set -# CONFIG_GPIO_CADENCE is not set -# CONFIG_GPIO_DWAPB is not set -# CONFIG_GPIO_EXAR is not set -# CONFIG_GPIO_FTGPIO010 is not set -# CONFIG_GPIO_GENERIC_PLATFORM is not set -# CONFIG_GPIO_GRGPIO is not set -# CONFIG_GPIO_HLWD is not set -# CONFIG_GPIO_LOGICVC is not set -# CONFIG_GPIO_MB86S7X is not set -# CONFIG_GPIO_RCAR is not set -CONFIG_GPIO_SIFIVE=y -# CONFIG_GPIO_SYSCON is not set -# CONFIG_GPIO_XILINX is not set -# CONFIG_GPIO_AMD_FCH is not set -# end of Memory mapped GPIO drivers - -# -# I2C GPIO expanders -# -# CONFIG_GPIO_ADNP is not set -# CONFIG_GPIO_FXL6408 is not set -# CONFIG_GPIO_GW_PLD is not set -# CONFIG_GPIO_MAX7300 is not set -# CONFIG_GPIO_MAX732X is not set -# CONFIG_GPIO_PCA953X is not set -# CONFIG_GPIO_PCA9570 is not set -# CONFIG_GPIO_PCF857X is not set -# CONFIG_GPIO_TPIC2810 is not set -# end of I2C GPIO expanders - -# -# MFD GPIO expanders -# -# end of MFD GPIO expanders - -# -# PCI GPIO expanders -# -# CONFIG_GPIO_BT8XX is not set -# CONFIG_GPIO_PCI_IDIO_16 is not set -# CONFIG_GPIO_PCIE_IDIO_24 is not set -# CONFIG_GPIO_RDC321X is not set -# end of PCI GPIO expanders - -# -# SPI GPIO expanders -# -# CONFIG_GPIO_74X164 is not set -# CONFIG_GPIO_MAX3191X is not set -# CONFIG_GPIO_MAX7301 is not set -# CONFIG_GPIO_MC33880 is not set -# CONFIG_GPIO_PISOSR is not set -# CONFIG_GPIO_XRA1403 is not set -# end of SPI GPIO expanders - -# -# USB GPIO expanders -# -# end of USB GPIO expanders - -# -# Virtual GPIO drivers -# -# CONFIG_GPIO_AGGREGATOR is not set -# CONFIG_GPIO_LATCH is not set -# CONFIG_GPIO_MOCKUP is not set -# CONFIG_GPIO_VIRTIO is not set -# CONFIG_GPIO_SIM is not set -# end of Virtual GPIO drivers - -# CONFIG_W1 is not set -CONFIG_POWER_RESET=y -# CONFIG_POWER_RESET_GPIO is not set -# CONFIG_POWER_RESET_GPIO_RESTART is not set -# CONFIG_POWER_RESET_LTC2952 is not set -# CONFIG_POWER_RESET_REGULATOR is not set -# CONFIG_POWER_RESET_RESTART is not set -CONFIG_POWER_RESET_SYSCON=y -CONFIG_POWER_RESET_SYSCON_POWEROFF=y -# CONFIG_SYSCON_REBOOT_MODE is not set -# CONFIG_NVMEM_REBOOT_MODE is not set -CONFIG_POWER_SUPPLY=y -# CONFIG_POWER_SUPPLY_DEBUG is not set -CONFIG_POWER_SUPPLY_HWMON=y -# CONFIG_GENERIC_ADC_BATTERY is not set -# CONFIG_IP5XXX_POWER is not set -# CONFIG_TEST_POWER is not set -# CONFIG_CHARGER_ADP5061 is not set -# CONFIG_BATTERY_CW2015 is not set -# CONFIG_BATTERY_DS2780 is not set -# CONFIG_BATTERY_DS2781 is not set -# CONFIG_BATTERY_DS2782 is not set -# CONFIG_BATTERY_SAMSUNG_SDI is not set -# CONFIG_BATTERY_SBS is not set -# CONFIG_CHARGER_SBS is not set -# CONFIG_MANAGER_SBS is not set -# CONFIG_BATTERY_BQ27XXX is not set -# CONFIG_BATTERY_MAX17040 is not set -# CONFIG_BATTERY_MAX17042 is not set -# CONFIG_CHARGER_ISP1704 is not set -# CONFIG_CHARGER_MAX8903 is not set -# CONFIG_CHARGER_LP8727 is not set -# CONFIG_CHARGER_GPIO is not set -# CONFIG_CHARGER_MANAGER is not set -# CONFIG_CHARGER_LT3651 is not set -# CONFIG_CHARGER_LTC4162L is not set -# CONFIG_CHARGER_DETECTOR_MAX14656 is not set -# CONFIG_CHARGER_MAX77976 is not set -# CONFIG_CHARGER_BQ2415X is not set -# CONFIG_CHARGER_BQ24190 is not set -# CONFIG_CHARGER_BQ24257 is not set -# CONFIG_CHARGER_BQ24735 is not set -# CONFIG_CHARGER_BQ2515X is not set -# CONFIG_CHARGER_BQ25890 is not set -# CONFIG_CHARGER_BQ25980 is not set -# CONFIG_CHARGER_BQ256XX is not set -# CONFIG_CHARGER_SMB347 is not set -# CONFIG_BATTERY_GAUGE_LTC2941 is not set -# CONFIG_BATTERY_GOLDFISH is not set -# CONFIG_BATTERY_RT5033 is not set -# CONFIG_CHARGER_RT9455 is not set -# CONFIG_CHARGER_RT9467 is not set -# CONFIG_CHARGER_RT9471 is not set -# CONFIG_CHARGER_UCS1002 is not set -# CONFIG_CHARGER_BD99954 is not set -# CONFIG_BATTERY_UG3105 is not set -CONFIG_HWMON=y -# CONFIG_HWMON_DEBUG_CHIP is not set - -# -# Native drivers -# -# CONFIG_SENSORS_AD7314 is not set -# CONFIG_SENSORS_AD7414 is not set -# CONFIG_SENSORS_AD7418 is not set -# CONFIG_SENSORS_ADM1021 is not set -# CONFIG_SENSORS_ADM1025 is not set -# CONFIG_SENSORS_ADM1026 is not set -# CONFIG_SENSORS_ADM1029 is not set -# CONFIG_SENSORS_ADM1031 is not set -# CONFIG_SENSORS_ADM1177 is not set -# CONFIG_SENSORS_ADM9240 is not set -# CONFIG_SENSORS_ADT7310 is not set -# CONFIG_SENSORS_ADT7410 is not set -# CONFIG_SENSORS_ADT7411 is not set -# CONFIG_SENSORS_ADT7462 is not set -# CONFIG_SENSORS_ADT7470 is not set -# CONFIG_SENSORS_ADT7475 is not set -# CONFIG_SENSORS_AHT10 is not set -# CONFIG_SENSORS_AQUACOMPUTER_D5NEXT is not set -# CONFIG_SENSORS_AS370 is not set -# CONFIG_SENSORS_ASC7621 is not set -# CONFIG_SENSORS_AXI_FAN_CONTROL is not set -# CONFIG_SENSORS_ATXP1 is not set -# CONFIG_SENSORS_CORSAIR_CPRO is not set -# CONFIG_SENSORS_CORSAIR_PSU is not set -# CONFIG_SENSORS_DRIVETEMP is not set -# CONFIG_SENSORS_DS620 is not set -# CONFIG_SENSORS_DS1621 is not set -# CONFIG_SENSORS_I5K_AMB is not set -# CONFIG_SENSORS_F71805F is not set -# CONFIG_SENSORS_F71882FG is not set -# CONFIG_SENSORS_F75375S is not set -# CONFIG_SENSORS_FTSTEUTATES is not set -# CONFIG_SENSORS_GL518SM is not set -# CONFIG_SENSORS_GL520SM is not set -# CONFIG_SENSORS_G760A is not set -# CONFIG_SENSORS_G762 is not set -# CONFIG_SENSORS_GPIO_FAN is not set -# CONFIG_SENSORS_HIH6130 is not set -# CONFIG_SENSORS_IIO_HWMON is not set -# CONFIG_SENSORS_IT87 is not set -# CONFIG_SENSORS_JC42 is not set -# CONFIG_SENSORS_POWR1220 is not set -# CONFIG_SENSORS_LINEAGE is not set -# CONFIG_SENSORS_LTC2945 is not set -# CONFIG_SENSORS_LTC2947_I2C is not set -# CONFIG_SENSORS_LTC2947_SPI is not set -# CONFIG_SENSORS_LTC2990 is not set -# CONFIG_SENSORS_LTC2992 is not set -# CONFIG_SENSORS_LTC4151 is not set -# CONFIG_SENSORS_LTC4215 is not set -# CONFIG_SENSORS_LTC4222 is not set -# CONFIG_SENSORS_LTC4245 is not set -# CONFIG_SENSORS_LTC4260 is not set -# CONFIG_SENSORS_LTC4261 is not set -# CONFIG_SENSORS_MAX1111 is not set -# CONFIG_SENSORS_MAX127 is not set -# CONFIG_SENSORS_MAX16065 is not set -# CONFIG_SENSORS_MAX1619 is not set -# CONFIG_SENSORS_MAX1668 is not set -# CONFIG_SENSORS_MAX197 is not set -# CONFIG_SENSORS_MAX31722 is not set -# CONFIG_SENSORS_MAX31730 is not set -# CONFIG_SENSORS_MAX31760 is not set -# CONFIG_MAX31827 is not set -# CONFIG_SENSORS_MAX6620 is not set -# CONFIG_SENSORS_MAX6621 is not set -# CONFIG_SENSORS_MAX6639 is not set -# CONFIG_SENSORS_MAX6642 is not set -# CONFIG_SENSORS_MAX6650 is not set -# CONFIG_SENSORS_MAX6697 is not set -# CONFIG_SENSORS_MAX31790 is not set -# CONFIG_SENSORS_MC34VR500 is not set -# CONFIG_SENSORS_MCP3021 is not set -# CONFIG_SENSORS_TC654 is not set -# CONFIG_SENSORS_TPS23861 is not set -# CONFIG_SENSORS_MR75203 is not set -# CONFIG_SENSORS_ADCXX is not set -# CONFIG_SENSORS_LM63 is not set -# CONFIG_SENSORS_LM70 is not set -# CONFIG_SENSORS_LM73 is not set -# CONFIG_SENSORS_LM75 is not set -# CONFIG_SENSORS_LM77 is not set -# CONFIG_SENSORS_LM78 is not set -# CONFIG_SENSORS_LM80 is not set -# CONFIG_SENSORS_LM83 is not set -# CONFIG_SENSORS_LM85 is not set -# CONFIG_SENSORS_LM87 is not set -# CONFIG_SENSORS_LM90 is not set -# CONFIG_SENSORS_LM92 is not set -# CONFIG_SENSORS_LM93 is not set -# CONFIG_SENSORS_LM95234 is not set -# CONFIG_SENSORS_LM95241 is not set -# CONFIG_SENSORS_LM95245 is not set -# CONFIG_SENSORS_PC87360 is not set -# CONFIG_SENSORS_PC87427 is not set -# CONFIG_SENSORS_NTC_THERMISTOR is not set -# CONFIG_SENSORS_NCT6683 is not set -# CONFIG_SENSORS_NCT6775 is not set -# CONFIG_SENSORS_NCT6775_I2C is not set -# CONFIG_SENSORS_NCT7802 is not set -# CONFIG_SENSORS_NCT7904 is not set -# CONFIG_SENSORS_NPCM7XX is not set -# CONFIG_SENSORS_NZXT_KRAKEN2 is not set -# CONFIG_SENSORS_NZXT_SMART2 is not set -# CONFIG_SENSORS_OCC_P8_I2C is not set -# CONFIG_SENSORS_PCF8591 is not set -# CONFIG_PMBUS is not set -# CONFIG_SENSORS_SBTSI is not set -# CONFIG_SENSORS_SBRMI is not set -# CONFIG_SENSORS_SHT15 is not set -# CONFIG_SENSORS_SHT21 is not set -# CONFIG_SENSORS_SHT3x is not set -# CONFIG_SENSORS_SHT4x is not set -# CONFIG_SENSORS_SHTC1 is not set -# CONFIG_SENSORS_SIS5595 is not set -# CONFIG_SENSORS_DME1737 is not set -# CONFIG_SENSORS_EMC1403 is not set -# CONFIG_SENSORS_EMC2103 is not set -# CONFIG_SENSORS_EMC2305 is not set -# CONFIG_SENSORS_EMC6W201 is not set -# CONFIG_SENSORS_SMSC47M1 is not set -# CONFIG_SENSORS_SMSC47M192 is not set -# CONFIG_SENSORS_SMSC47B397 is not set -# CONFIG_SENSORS_SCH5627 is not set -# CONFIG_SENSORS_SCH5636 is not set -# CONFIG_SENSORS_STTS751 is not set -# CONFIG_SENSORS_SFCTEMP is not set -# CONFIG_SENSORS_SMM665 is not set -# CONFIG_SENSORS_ADC128D818 is not set -# CONFIG_SENSORS_ADS7828 is not set -# CONFIG_SENSORS_ADS7871 is not set -# CONFIG_SENSORS_AMC6821 is not set -# CONFIG_SENSORS_INA209 is not set -# CONFIG_SENSORS_INA2XX is not set -# CONFIG_SENSORS_INA238 is not set -# CONFIG_SENSORS_INA3221 is not set -# CONFIG_SENSORS_TC74 is not set -# CONFIG_SENSORS_THMC50 is not set -# CONFIG_SENSORS_TMP102 is not set -# CONFIG_SENSORS_TMP103 is not set -# CONFIG_SENSORS_TMP108 is not set -# CONFIG_SENSORS_TMP401 is not set -# CONFIG_SENSORS_TMP421 is not set -# CONFIG_SENSORS_TMP464 is not set -# CONFIG_SENSORS_TMP513 is not set -# CONFIG_SENSORS_VIA686A is not set -# CONFIG_SENSORS_VT1211 is not set -# CONFIG_SENSORS_VT8231 is not set -# CONFIG_SENSORS_W83773G is not set -# CONFIG_SENSORS_W83781D is not set -# CONFIG_SENSORS_W83791D is not set -# CONFIG_SENSORS_W83792D is not set -# CONFIG_SENSORS_W83793 is not set -# CONFIG_SENSORS_W83795 is not set -# CONFIG_SENSORS_W83L785TS is not set -# CONFIG_SENSORS_W83L786NG is not set -# CONFIG_SENSORS_W83627HF is not set -# CONFIG_SENSORS_W83627EHF is not set - -# -# ACPI drivers -# -# CONFIG_SENSORS_ACPI_POWER is not set -CONFIG_THERMAL=y -# CONFIG_THERMAL_NETLINK is not set -# CONFIG_THERMAL_STATISTICS is not set -CONFIG_THERMAL_EMERGENCY_POWEROFF_DELAY_MS=0 -CONFIG_THERMAL_HWMON=y -CONFIG_THERMAL_OF=y -# CONFIG_THERMAL_WRITABLE_TRIPS is not set -CONFIG_THERMAL_DEFAULT_GOV_STEP_WISE=y -# CONFIG_THERMAL_DEFAULT_GOV_FAIR_SHARE is not set -# CONFIG_THERMAL_DEFAULT_GOV_USER_SPACE is not set -# CONFIG_THERMAL_GOV_FAIR_SHARE is not set -CONFIG_THERMAL_GOV_STEP_WISE=y -# CONFIG_THERMAL_GOV_BANG_BANG is not set -# CONFIG_THERMAL_GOV_USER_SPACE is not set -# CONFIG_CPU_THERMAL is not set -# CONFIG_THERMAL_EMULATION is not set -# CONFIG_THERMAL_MMIO is not set -# CONFIG_SUN8I_THERMAL is not set -# CONFIG_RCAR_THERMAL is not set -# CONFIG_RCAR_GEN3_THERMAL is not set -# CONFIG_RZG2L_THERMAL is not set -# CONFIG_GENERIC_ADC_THERMAL is not set -CONFIG_WATCHDOG=y -CONFIG_WATCHDOG_CORE=y -# CONFIG_WATCHDOG_NOWAYOUT is not set -CONFIG_WATCHDOG_HANDLE_BOOT_ENABLED=y -CONFIG_WATCHDOG_OPEN_TIMEOUT=0 -# CONFIG_WATCHDOG_SYSFS is not set -# CONFIG_WATCHDOG_HRTIMER_PRETIMEOUT is not set - -# -# Watchdog Pretimeout Governors -# -# CONFIG_WATCHDOG_PRETIMEOUT_GOV is not set - -# -# Watchdog Device Drivers -# -# CONFIG_SOFT_WATCHDOG is not set -# CONFIG_GPIO_WATCHDOG is not set -# CONFIG_WDAT_WDT is not set -# CONFIG_XILINX_WATCHDOG is not set -# CONFIG_ZIIRAVE_WATCHDOG is not set -# CONFIG_CADENCE_WATCHDOG is not set -# CONFIG_DW_WATCHDOG is not set -CONFIG_SUNXI_WATCHDOG=y -# CONFIG_MAX63XX_WATCHDOG is not set -# CONFIG_RENESAS_WDT is not set -# CONFIG_RENESAS_RZAWDT is not set -# CONFIG_RENESAS_RZN1WDT is not set -# CONFIG_RENESAS_RZG2LWDT is not set -# CONFIG_ALIM7101_WDT is not set -# CONFIG_I6300ESB_WDT is not set -# CONFIG_MEN_A21_WDT is not set -CONFIG_STARFIVE_WATCHDOG=y - -# -# PCI-based Watchdog Cards -# -# CONFIG_PCIPCWATCHDOG is not set -# CONFIG_WDTPCI is not set - -# -# USB-based Watchdog Cards -# -# CONFIG_USBPCWATCHDOG is not set -CONFIG_SSB_POSSIBLE=y -# CONFIG_SSB is not set -CONFIG_BCMA_POSSIBLE=y -# CONFIG_BCMA is not set - -# -# Multifunction device drivers -# -# CONFIG_MFD_ACT8945A is not set -# CONFIG_MFD_SUN4I_GPADC is not set -# CONFIG_MFD_AS3711 is not set -# CONFIG_MFD_SMPRO is not set -# CONFIG_MFD_AS3722 is not set -# CONFIG_PMIC_ADP5520 is not set -# CONFIG_MFD_AAT2870_CORE is not set -# CONFIG_MFD_ATMEL_FLEXCOM is not set -# CONFIG_MFD_ATMEL_HLCDC is not set -# CONFIG_MFD_BCM590XX is not set -# CONFIG_MFD_BD9571MWV is not set -# CONFIG_MFD_AXP20X_I2C is not set -# CONFIG_MFD_MADERA is not set -# CONFIG_MFD_MAX5970 is not set -# CONFIG_PMIC_DA903X is not set -# CONFIG_MFD_DA9052_SPI is not set -# CONFIG_MFD_DA9052_I2C is not set -# CONFIG_MFD_DA9055 is not set -# CONFIG_MFD_DA9062 is not set -# CONFIG_MFD_DA9063 is not set -# CONFIG_MFD_DA9150 is not set -# CONFIG_MFD_DLN2 is not set -# CONFIG_MFD_GATEWORKS_GSC is not set -# CONFIG_MFD_MC13XXX_SPI is not set -# CONFIG_MFD_MC13XXX_I2C is not set -# CONFIG_MFD_MP2629 is not set -# CONFIG_MFD_HI6421_PMIC is not set -# CONFIG_LPC_ICH is not set -# CONFIG_LPC_SCH is not set -# CONFIG_MFD_IQS62X is not set -# CONFIG_MFD_JANZ_CMODIO is not set -# CONFIG_MFD_KEMPLD is not set -# CONFIG_MFD_88PM800 is not set -# CONFIG_MFD_88PM805 is not set -# CONFIG_MFD_88PM860X is not set -# CONFIG_MFD_MAX14577 is not set -# CONFIG_MFD_MAX77541 is not set -# CONFIG_MFD_MAX77620 is not set -# CONFIG_MFD_MAX77650 is not set -# CONFIG_MFD_MAX77686 is not set -# CONFIG_MFD_MAX77693 is not set -# CONFIG_MFD_MAX77714 is not set -# CONFIG_MFD_MAX77843 is not set -# CONFIG_MFD_MAX8907 is not set -# CONFIG_MFD_MAX8925 is not set -# CONFIG_MFD_MAX8997 is not set -# CONFIG_MFD_MAX8998 is not set -# CONFIG_MFD_MT6360 is not set -# CONFIG_MFD_MT6370 is not set -# CONFIG_MFD_MT6397 is not set -# CONFIG_MFD_MENF21BMC is not set -# CONFIG_MFD_OCELOT is not set -# CONFIG_EZX_PCAP is not set -# CONFIG_MFD_CPCAP is not set -# CONFIG_MFD_VIPERBOARD is not set -# CONFIG_MFD_NTXEC is not set -# CONFIG_MFD_RETU is not set -# CONFIG_MFD_PCF50633 is not set -# CONFIG_MFD_SY7636A is not set -# CONFIG_MFD_RDC321X is not set -# CONFIG_MFD_RT4831 is not set -# CONFIG_MFD_RT5033 is not set -# CONFIG_MFD_RT5120 is not set -# CONFIG_MFD_RC5T583 is not set -# CONFIG_MFD_RK8XX_I2C is not set -# CONFIG_MFD_RK8XX_SPI is not set -# CONFIG_MFD_RN5T618 is not set -# CONFIG_MFD_SEC_CORE is not set -# CONFIG_MFD_SI476X_CORE is not set -# CONFIG_MFD_SM501 is not set -# CONFIG_MFD_SKY81452 is not set -# CONFIG_RZ_MTU3 is not set -# CONFIG_MFD_STMPE is not set -# CONFIG_MFD_SUN6I_PRCM is not set -CONFIG_MFD_SYSCON=y -# CONFIG_MFD_TI_AM335X_TSCADC is not set -# CONFIG_MFD_LP3943 is not set -# CONFIG_MFD_LP8788 is not set -# CONFIG_MFD_TI_LMU is not set -# CONFIG_MFD_PALMAS is not set -# CONFIG_TPS6105X is not set -# CONFIG_TPS65010 is not set -# CONFIG_TPS6507X is not set -# CONFIG_MFD_TPS65086 is not set -# CONFIG_MFD_TPS65090 is not set -# CONFIG_MFD_TPS65217 is not set -# CONFIG_MFD_TI_LP873X is not set -# CONFIG_MFD_TI_LP87565 is not set -# CONFIG_MFD_TPS65218 is not set -# CONFIG_MFD_TPS65219 is not set -# CONFIG_MFD_TPS6586X is not set -# CONFIG_MFD_TPS65910 is not set -# CONFIG_MFD_TPS65912_I2C is not set -# CONFIG_MFD_TPS65912_SPI is not set -# CONFIG_MFD_TPS6594_I2C is not set -# CONFIG_MFD_TPS6594_SPI is not set -# CONFIG_TWL4030_CORE is not set -# CONFIG_TWL6040_CORE is not set -# CONFIG_MFD_WL1273_CORE is not set -# CONFIG_MFD_LM3533 is not set -# CONFIG_MFD_TC3589X is not set -# CONFIG_MFD_TQMX86 is not set -# CONFIG_MFD_VX855 is not set -# CONFIG_MFD_LOCHNAGAR is not set -# CONFIG_MFD_ARIZONA_I2C is not set -# CONFIG_MFD_ARIZONA_SPI is not set -# CONFIG_MFD_WM8400 is not set -# CONFIG_MFD_WM831X_I2C is not set -# CONFIG_MFD_WM831X_SPI is not set -# CONFIG_MFD_WM8350_I2C is not set -# CONFIG_MFD_WM8994 is not set -# CONFIG_MFD_ROHM_BD718XX is not set -# CONFIG_MFD_ROHM_BD71828 is not set -# CONFIG_MFD_ROHM_BD957XMUF is not set -# CONFIG_MFD_STPMIC1 is not set -# CONFIG_MFD_STMFX is not set -# CONFIG_MFD_ATC260X_I2C is not set -# CONFIG_MFD_QCOM_PM8008 is not set -# CONFIG_MFD_INTEL_M10_BMC_SPI is not set -# CONFIG_MFD_RSMU_I2C is not set -# CONFIG_MFD_RSMU_SPI is not set -# end of Multifunction device drivers - -CONFIG_REGULATOR=y -# CONFIG_REGULATOR_DEBUG is not set -CONFIG_REGULATOR_FIXED_VOLTAGE=y -# CONFIG_REGULATOR_VIRTUAL_CONSUMER is not set -# CONFIG_REGULATOR_USERSPACE_CONSUMER is not set -# CONFIG_REGULATOR_88PG86X is not set -# CONFIG_REGULATOR_ACT8865 is not set -# CONFIG_REGULATOR_AD5398 is not set -# CONFIG_REGULATOR_DA9121 is not set -# CONFIG_REGULATOR_DA9210 is not set -# CONFIG_REGULATOR_DA9211 is not set -# CONFIG_REGULATOR_FAN53555 is not set -# CONFIG_REGULATOR_FAN53880 is not set -# CONFIG_REGULATOR_GPIO is not set -# CONFIG_REGULATOR_ISL9305 is not set -# CONFIG_REGULATOR_ISL6271A is not set -# CONFIG_REGULATOR_LP3971 is not set -# CONFIG_REGULATOR_LP3972 is not set -# CONFIG_REGULATOR_LP872X is not set -# CONFIG_REGULATOR_LP8755 is not set -# CONFIG_REGULATOR_LTC3589 is not set -# CONFIG_REGULATOR_LTC3676 is not set -# CONFIG_REGULATOR_MAX1586 is not set -# CONFIG_REGULATOR_MAX8649 is not set -# CONFIG_REGULATOR_MAX8660 is not set -# CONFIG_REGULATOR_MAX8893 is not set -# CONFIG_REGULATOR_MAX8952 is not set -# CONFIG_REGULATOR_MAX8973 is not set -# CONFIG_REGULATOR_MAX20086 is not set -# CONFIG_REGULATOR_MAX20411 is not set -# CONFIG_REGULATOR_MAX77826 is not set -# CONFIG_REGULATOR_MCP16502 is not set -# CONFIG_REGULATOR_MP5416 is not set -# CONFIG_REGULATOR_MP8859 is not set -# CONFIG_REGULATOR_MP886X is not set -# CONFIG_REGULATOR_MPQ7920 is not set -# CONFIG_REGULATOR_MT6311 is not set -# CONFIG_REGULATOR_PCA9450 is not set -# CONFIG_REGULATOR_PF8X00 is not set -# CONFIG_REGULATOR_PFUZE100 is not set -# CONFIG_REGULATOR_PV88060 is not set -# CONFIG_REGULATOR_PV88080 is not set -# CONFIG_REGULATOR_PV88090 is not set -# CONFIG_REGULATOR_RAA215300 is not set -# CONFIG_REGULATOR_RASPBERRYPI_TOUCHSCREEN_ATTINY is not set -# CONFIG_REGULATOR_RT4801 is not set -# CONFIG_REGULATOR_RT4803 is not set -# CONFIG_REGULATOR_RT5190A is not set -# CONFIG_REGULATOR_RT5739 is not set -# CONFIG_REGULATOR_RT5759 is not set -# CONFIG_REGULATOR_RT6160 is not set -# CONFIG_REGULATOR_RT6190 is not set -# CONFIG_REGULATOR_RT6245 is not set -# CONFIG_REGULATOR_RTQ2134 is not set -# CONFIG_REGULATOR_RTMV20 is not set -# CONFIG_REGULATOR_RTQ6752 is not set -# CONFIG_REGULATOR_SLG51000 is not set -# CONFIG_REGULATOR_SY8106A is not set -# CONFIG_REGULATOR_SY8824X is not set -# CONFIG_REGULATOR_SY8827N is not set -# CONFIG_REGULATOR_TPS51632 is not set -# CONFIG_REGULATOR_TPS62360 is not set -# CONFIG_REGULATOR_TPS6286X is not set -# CONFIG_REGULATOR_TPS6287X is not set -# CONFIG_REGULATOR_TPS65023 is not set -# CONFIG_REGULATOR_TPS6507X is not set -# CONFIG_REGULATOR_TPS65132 is not set -# CONFIG_REGULATOR_TPS6524X is not set -# CONFIG_REGULATOR_VCTRL is not set -# CONFIG_RC_CORE is not set - -# -# CEC support -# -# CONFIG_MEDIA_CEC_SUPPORT is not set -# end of CEC support - -CONFIG_MEDIA_SUPPORT=m -CONFIG_MEDIA_SUPPORT_FILTER=y -CONFIG_MEDIA_SUBDRV_AUTOSELECT=y - -# -# Media device types -# -CONFIG_MEDIA_CAMERA_SUPPORT=y -# CONFIG_MEDIA_ANALOG_TV_SUPPORT is not set -# CONFIG_MEDIA_DIGITAL_TV_SUPPORT is not set -# CONFIG_MEDIA_RADIO_SUPPORT is not set -# CONFIG_MEDIA_SDR_SUPPORT is not set -# CONFIG_MEDIA_PLATFORM_SUPPORT is not set -# CONFIG_MEDIA_TEST_SUPPORT is not set -# end of Media device types - -CONFIG_VIDEO_DEV=m -CONFIG_MEDIA_CONTROLLER=y - -# -# Video4Linux options -# -CONFIG_VIDEO_V4L2_I2C=y -CONFIG_VIDEO_V4L2_SUBDEV_API=y -# CONFIG_VIDEO_ADV_DEBUG is not set -# CONFIG_VIDEO_FIXED_MINOR_RANGES is not set -CONFIG_V4L2_FWNODE=m -CONFIG_V4L2_ASYNC=m -# end of Video4Linux options - -# -# Media controller options -# -# end of Media controller options - -# -# Media drivers -# - -# -# Drivers filtered as selected at 'Filter media drivers' -# - -# -# Media drivers -# -# CONFIG_MEDIA_USB_SUPPORT is not set -# CONFIG_MEDIA_PCI_SUPPORT is not set -CONFIG_UVC_COMMON=m -CONFIG_VIDEOBUF2_CORE=m -CONFIG_VIDEOBUF2_V4L2=m -CONFIG_VIDEOBUF2_MEMOPS=m -CONFIG_VIDEOBUF2_VMALLOC=m -CONFIG_VIDEOBUF2_DMA_SG=m -# end of Media drivers - -# -# Media ancillary drivers -# - -# -# Camera sensor devices -# -# CONFIG_VIDEO_AR0521 is not set -# CONFIG_VIDEO_HI556 is not set -# CONFIG_VIDEO_HI846 is not set -# CONFIG_VIDEO_HI847 is not set -# CONFIG_VIDEO_IMX208 is not set -# CONFIG_VIDEO_IMX214 is not set -CONFIG_VIDEO_IMX219=m -# CONFIG_VIDEO_IMX258 is not set -# CONFIG_VIDEO_IMX274 is not set -# CONFIG_VIDEO_IMX290 is not set -# CONFIG_VIDEO_IMX296 is not set -# CONFIG_VIDEO_IMX319 is not set -# CONFIG_VIDEO_IMX334 is not set -# CONFIG_VIDEO_IMX335 is not set -# CONFIG_VIDEO_IMX355 is not set -# CONFIG_VIDEO_IMX412 is not set -# CONFIG_VIDEO_IMX415 is not set -# CONFIG_VIDEO_MT9M001 is not set -# CONFIG_VIDEO_MT9M111 is not set -# CONFIG_VIDEO_MT9P031 is not set -# CONFIG_VIDEO_MT9T112 is not set -# CONFIG_VIDEO_MT9V011 is not set -# CONFIG_VIDEO_MT9V032 is not set -# CONFIG_VIDEO_MT9V111 is not set -# CONFIG_VIDEO_OG01A1B is not set -# CONFIG_VIDEO_OV01A10 is not set -# CONFIG_VIDEO_OV02A10 is not set -# CONFIG_VIDEO_OV08D10 is not set -# CONFIG_VIDEO_OV08X40 is not set -# CONFIG_VIDEO_OV13858 is not set -# CONFIG_VIDEO_OV13B10 is not set -# CONFIG_VIDEO_OV2640 is not set -# CONFIG_VIDEO_OV2659 is not set -# CONFIG_VIDEO_OV2680 is not set -# CONFIG_VIDEO_OV2685 is not set -# CONFIG_VIDEO_OV2740 is not set -# CONFIG_VIDEO_OV4689 is not set -# CONFIG_VIDEO_OV5640 is not set -# CONFIG_VIDEO_OV5645 is not set -# CONFIG_VIDEO_OV5647 is not set -# CONFIG_VIDEO_OV5648 is not set -# CONFIG_VIDEO_OV5670 is not set -# CONFIG_VIDEO_OV5675 is not set -# CONFIG_VIDEO_OV5693 is not set -# CONFIG_VIDEO_OV5695 is not set -# CONFIG_VIDEO_OV6650 is not set -# CONFIG_VIDEO_OV7251 is not set -# CONFIG_VIDEO_OV7640 is not set -# CONFIG_VIDEO_OV7670 is not set -# CONFIG_VIDEO_OV772X is not set -# CONFIG_VIDEO_OV7740 is not set -# CONFIG_VIDEO_OV8856 is not set -# CONFIG_VIDEO_OV8858 is not set -# CONFIG_VIDEO_OV8865 is not set -# CONFIG_VIDEO_OV9282 is not set -# CONFIG_VIDEO_OV9640 is not set -# CONFIG_VIDEO_OV9650 is not set -# CONFIG_VIDEO_OV9734 is not set -# CONFIG_VIDEO_RDACM20 is not set -# CONFIG_VIDEO_RDACM21 is not set -# CONFIG_VIDEO_RJ54N1 is not set -# CONFIG_VIDEO_S5C73M3 is not set -# CONFIG_VIDEO_S5K5BAF is not set -# CONFIG_VIDEO_S5K6A3 is not set -# CONFIG_VIDEO_ST_VGXY61 is not set -# CONFIG_VIDEO_CCS is not set -# CONFIG_VIDEO_ET8EK8 is not set -# end of Camera sensor devices - -# -# Lens drivers -# -# CONFIG_VIDEO_AD5820 is not set -# CONFIG_VIDEO_AK7375 is not set -# CONFIG_VIDEO_DW9714 is not set -# CONFIG_VIDEO_DW9768 is not set -# CONFIG_VIDEO_DW9807_VCM is not set -# end of Lens drivers - -# -# Flash devices -# -# CONFIG_VIDEO_ADP1653 is not set -# CONFIG_VIDEO_LM3560 is not set -# CONFIG_VIDEO_LM3646 is not set -# end of Flash devices - -# -# Audio decoders, processors and mixers -# -# CONFIG_VIDEO_CS3308 is not set -# CONFIG_VIDEO_CS5345 is not set -# CONFIG_VIDEO_CS53L32A is not set -# CONFIG_VIDEO_MSP3400 is not set -# CONFIG_VIDEO_SONY_BTF_MPX is not set -# CONFIG_VIDEO_TDA7432 is not set -# CONFIG_VIDEO_TDA9840 is not set -# CONFIG_VIDEO_TEA6415C is not set -# CONFIG_VIDEO_TEA6420 is not set -# CONFIG_VIDEO_TLV320AIC23B is not set -# CONFIG_VIDEO_TVAUDIO is not set -# CONFIG_VIDEO_UDA1342 is not set -# CONFIG_VIDEO_VP27SMPX is not set -# CONFIG_VIDEO_WM8739 is not set -# CONFIG_VIDEO_WM8775 is not set -# end of Audio decoders, processors and mixers - -# -# RDS decoders -# -# CONFIG_VIDEO_SAA6588 is not set -# end of RDS decoders - -# -# Video decoders -# -# CONFIG_VIDEO_ADV7180 is not set -# CONFIG_VIDEO_ADV7183 is not set -# CONFIG_VIDEO_ADV748X is not set -# CONFIG_VIDEO_ADV7604 is not set -# CONFIG_VIDEO_ADV7842 is not set -# CONFIG_VIDEO_BT819 is not set -# CONFIG_VIDEO_BT856 is not set -# CONFIG_VIDEO_BT866 is not set -# CONFIG_VIDEO_ISL7998X is not set -# CONFIG_VIDEO_KS0127 is not set -# CONFIG_VIDEO_MAX9286 is not set -# CONFIG_VIDEO_ML86V7667 is not set -# CONFIG_VIDEO_SAA7110 is not set -# CONFIG_VIDEO_SAA711X is not set -# CONFIG_VIDEO_TC358743 is not set -# CONFIG_VIDEO_TC358746 is not set -# CONFIG_VIDEO_TVP514X is not set -# CONFIG_VIDEO_TVP5150 is not set -# CONFIG_VIDEO_TVP7002 is not set -# CONFIG_VIDEO_TW2804 is not set -# CONFIG_VIDEO_TW9903 is not set -# CONFIG_VIDEO_TW9906 is not set -# CONFIG_VIDEO_TW9910 is not set -# CONFIG_VIDEO_VPX3220 is not set - -# -# Video and audio decoders -# -# CONFIG_VIDEO_SAA717X is not set -# CONFIG_VIDEO_CX25840 is not set -# end of Video decoders - -# -# Video encoders -# -# CONFIG_VIDEO_ADV7170 is not set -# CONFIG_VIDEO_ADV7175 is not set -# CONFIG_VIDEO_ADV7343 is not set -# CONFIG_VIDEO_ADV7393 is not set -# CONFIG_VIDEO_ADV7511 is not set -# CONFIG_VIDEO_AK881X is not set -# CONFIG_VIDEO_SAA7127 is not set -# CONFIG_VIDEO_SAA7185 is not set -# CONFIG_VIDEO_THS8200 is not set -# end of Video encoders - -# -# Video improvement chips -# -# CONFIG_VIDEO_UPD64031A is not set -# CONFIG_VIDEO_UPD64083 is not set -# end of Video improvement chips - -# -# Audio/Video compression chips -# -# CONFIG_VIDEO_SAA6752HS is not set -# end of Audio/Video compression chips - -# -# SDR tuner chips -# -# end of SDR tuner chips - -# -# Miscellaneous helper chips -# -# CONFIG_VIDEO_I2C is not set -# CONFIG_VIDEO_M52790 is not set -# CONFIG_VIDEO_ST_MIPID02 is not set -# CONFIG_VIDEO_THS7303 is not set -# end of Miscellaneous helper chips - -# -# Media SPI Adapters -# -# CONFIG_VIDEO_GS1662 is not set -# end of Media SPI Adapters -# end of Media ancillary drivers - -# -# Graphics support -# -CONFIG_APERTURE_HELPERS=y -CONFIG_VIDEO_CMDLINE=y -# CONFIG_DRM is not set -# CONFIG_DRM_DEBUG_MODESET_LOCK is not set - -# -# ARM devices -# -# end of ARM devices - -# -# Frame buffer Devices -# -CONFIG_FB_NOTIFY=y -CONFIG_FB=y -# CONFIG_FIRMWARE_EDID is not set -# CONFIG_FB_FOREIGN_ENDIAN is not set -# CONFIG_FB_MODE_HELPERS is not set -# CONFIG_FB_TILEBLITTING is not set - -# -# Frame buffer hardware drivers -# -# CONFIG_FB_CIRRUS is not set -# CONFIG_FB_PM2 is not set -# CONFIG_FB_CYBER2000 is not set -# CONFIG_FB_ASILIANT is not set -# CONFIG_FB_IMSTT is not set -# CONFIG_FB_EFI is not set -# CONFIG_FB_OPENCORES is not set -# CONFIG_FB_S1D13XXX is not set -# CONFIG_FB_NVIDIA is not set -# CONFIG_FB_RIVA is not set -# CONFIG_FB_I740 is not set -# CONFIG_FB_MATROX is not set -# CONFIG_FB_RADEON is not set -# CONFIG_FB_ATY128 is not set -# CONFIG_FB_ATY is not set -# CONFIG_FB_S3 is not set -# CONFIG_FB_SAVAGE is not set -# CONFIG_FB_SIS is not set -# CONFIG_FB_NEOMAGIC is not set -# CONFIG_FB_KYRO is not set -# CONFIG_FB_3DFX is not set -# CONFIG_FB_VOODOO1 is not set -# CONFIG_FB_VT8623 is not set -# CONFIG_FB_TRIDENT is not set -# CONFIG_FB_ARK is not set -# CONFIG_FB_PM3 is not set -# CONFIG_FB_CARMINE is not set -# CONFIG_FB_SH_MOBILE_LCDC is not set -# CONFIG_FB_SMSCUFX is not set -# CONFIG_FB_UDL is not set -# CONFIG_FB_IBM_GXT4500 is not set -# CONFIG_FB_GOLDFISH is not set -# CONFIG_FB_VIRTUAL is not set -# CONFIG_FB_METRONOME is not set -# CONFIG_FB_MB862XX is not set -# CONFIG_FB_SIMPLE is not set -# CONFIG_FB_SSD1307 is not set -# CONFIG_FB_SM712 is not set -# end of Frame buffer Devices - -# -# Backlight & LCD device support -# -# CONFIG_LCD_CLASS_DEVICE is not set -CONFIG_BACKLIGHT_CLASS_DEVICE=m -# CONFIG_BACKLIGHT_KTD253 is not set -# CONFIG_BACKLIGHT_KTZ8866 is not set -# CONFIG_BACKLIGHT_QCOM_WLED is not set -# CONFIG_BACKLIGHT_ADP8860 is not set -# CONFIG_BACKLIGHT_ADP8870 is not set -# CONFIG_BACKLIGHT_LM3639 is not set -# CONFIG_BACKLIGHT_GPIO is not set -# CONFIG_BACKLIGHT_LV5207LP is not set -# CONFIG_BACKLIGHT_BD6107 is not set -# CONFIG_BACKLIGHT_ARCXCNN is not set -# end of Backlight & LCD device support - -# -# Console display driver support -# -CONFIG_VGA_CONSOLE=y -CONFIG_DUMMY_CONSOLE=y -CONFIG_DUMMY_CONSOLE_COLUMNS=80 -CONFIG_DUMMY_CONSOLE_ROWS=25 -CONFIG_FRAMEBUFFER_CONSOLE=y -# CONFIG_FRAMEBUFFER_CONSOLE_LEGACY_ACCELERATION is not set -CONFIG_FRAMEBUFFER_CONSOLE_DETECT_PRIMARY=y -# CONFIG_FRAMEBUFFER_CONSOLE_ROTATION is not set -# CONFIG_FRAMEBUFFER_CONSOLE_DEFERRED_TAKEOVER is not set -# end of Console display driver support - -# CONFIG_LOGO is not set -# end of Graphics support - -# CONFIG_SOUND is not set -CONFIG_HID_SUPPORT=y -CONFIG_HID=y -# CONFIG_HID_BATTERY_STRENGTH is not set -# CONFIG_HIDRAW is not set -# CONFIG_UHID is not set -CONFIG_HID_GENERIC=y - -# -# Special HID drivers -# -# CONFIG_HID_A4TECH is not set -# CONFIG_HID_ACCUTOUCH is not set -# CONFIG_HID_ACRUX is not set -# CONFIG_HID_APPLEIR is not set -# CONFIG_HID_AUREAL is not set -# CONFIG_HID_BELKIN is not set -# CONFIG_HID_BETOP_FF is not set -# CONFIG_HID_CHERRY is not set -# CONFIG_HID_CHICONY is not set -# CONFIG_HID_COUGAR is not set -# CONFIG_HID_MACALLY is not set -# CONFIG_HID_CMEDIA is not set -# CONFIG_HID_CREATIVE_SB0540 is not set -# CONFIG_HID_CYPRESS is not set -# CONFIG_HID_DRAGONRISE is not set -# CONFIG_HID_EMS_FF is not set -# CONFIG_HID_ELECOM is not set -# CONFIG_HID_ELO is not set -# CONFIG_HID_EVISION is not set -# CONFIG_HID_EZKEY is not set -# CONFIG_HID_GEMBIRD is not set -# CONFIG_HID_GFRM is not set -# CONFIG_HID_GLORIOUS is not set -# CONFIG_HID_HOLTEK is not set -# CONFIG_HID_VIVALDI is not set -# CONFIG_HID_KEYTOUCH is not set -# CONFIG_HID_KYE is not set -# CONFIG_HID_UCLOGIC is not set -# CONFIG_HID_WALTOP is not set -# CONFIG_HID_VIEWSONIC is not set -# CONFIG_HID_VRC2 is not set -# CONFIG_HID_XIAOMI is not set -# CONFIG_HID_GYRATION is not set -# CONFIG_HID_ICADE is not set -# CONFIG_HID_ITE is not set -# CONFIG_HID_JABRA is not set -# CONFIG_HID_TWINHAN is not set -# CONFIG_HID_KENSINGTON is not set -# CONFIG_HID_LCPOWER is not set -# CONFIG_HID_LENOVO is not set -# CONFIG_HID_LETSKETCH is not set -# CONFIG_HID_MAGICMOUSE is not set -# CONFIG_HID_MALTRON is not set -# CONFIG_HID_MAYFLASH is not set -# CONFIG_HID_MEGAWORLD_FF is not set -# CONFIG_HID_REDRAGON is not set -# CONFIG_HID_MICROSOFT is not set -# CONFIG_HID_MONTEREY is not set -# CONFIG_HID_MULTITOUCH is not set -# CONFIG_HID_NTI is not set -# CONFIG_HID_NTRIG is not set -# CONFIG_HID_ORTEK is not set -# CONFIG_HID_PANTHERLORD is not set -# CONFIG_HID_PENMOUNT is not set -# CONFIG_HID_PETALYNX is not set -# CONFIG_HID_PICOLCD is not set -# CONFIG_HID_PLANTRONICS is not set -# CONFIG_HID_PXRC is not set -# CONFIG_HID_RAZER is not set -# CONFIG_HID_PRIMAX is not set -# CONFIG_HID_RETRODE is not set -# CONFIG_HID_ROCCAT is not set -# CONFIG_HID_SAITEK is not set -# CONFIG_HID_SAMSUNG is not set -# CONFIG_HID_SEMITEK is not set -# CONFIG_HID_SIGMAMICRO is not set -# CONFIG_HID_SPEEDLINK is not set -# CONFIG_HID_STEAM is not set -# CONFIG_HID_STEELSERIES is not set -# CONFIG_HID_SUNPLUS is not set -# CONFIG_HID_RMI is not set -# CONFIG_HID_GREENASIA is not set -# CONFIG_HID_SMARTJOYPLUS is not set -# CONFIG_HID_TIVO is not set -# CONFIG_HID_TOPSEED is not set -# CONFIG_HID_TOPRE is not set -# CONFIG_HID_THRUSTMASTER is not set -# CONFIG_HID_UDRAW_PS3 is not set -# CONFIG_HID_WACOM is not set -# CONFIG_HID_XINMO is not set -# CONFIG_HID_ZEROPLUS is not set -# CONFIG_HID_ZYDACRON is not set -# CONFIG_HID_SENSOR_HUB is not set -# CONFIG_HID_ALPS is not set -# CONFIG_HID_MCP2221 is not set -# end of Special HID drivers - -# -# HID-BPF support -# -# end of HID-BPF support - -# -# USB HID support -# -CONFIG_USB_HID=y -# CONFIG_HID_PID is not set -# CONFIG_USB_HIDDEV is not set -# end of USB HID support - -CONFIG_I2C_HID=m -# CONFIG_I2C_HID_ACPI is not set -# CONFIG_I2C_HID_OF is not set -# CONFIG_I2C_HID_OF_ELAN is not set -# CONFIG_I2C_HID_OF_GOODIX is not set -CONFIG_USB_OHCI_LITTLE_ENDIAN=y -CONFIG_USB_SUPPORT=y -CONFIG_USB_COMMON=y -# CONFIG_USB_ULPI_BUS is not set -# CONFIG_USB_CONN_GPIO is not set -CONFIG_USB_ARCH_HAS_HCD=y -CONFIG_USB=y -CONFIG_USB_PCI=y -# CONFIG_USB_ANNOUNCE_NEW_DEVICES is not set - -# -# Miscellaneous USB options -# -CONFIG_USB_DEFAULT_PERSIST=y -# CONFIG_USB_FEW_INIT_RETRIES is not set -# CONFIG_USB_DYNAMIC_MINORS is not set -# CONFIG_USB_OTG is not set -# CONFIG_USB_OTG_PRODUCTLIST is not set -# CONFIG_USB_OTG_DISABLE_EXTERNAL_HUB is not set -CONFIG_USB_AUTOSUSPEND_DELAY=2 -# CONFIG_USB_MON is not set - -# -# USB Host Controller Drivers -# -# CONFIG_USB_C67X00_HCD is not set -CONFIG_USB_XHCI_HCD=y -# CONFIG_USB_XHCI_DBGCAP is not set -CONFIG_USB_XHCI_PCI=y -# CONFIG_USB_XHCI_PCI_RENESAS is not set -CONFIG_USB_XHCI_PLATFORM=y -CONFIG_USB_XHCI_RCAR=y -CONFIG_USB_EHCI_HCD=y -# CONFIG_USB_EHCI_ROOT_HUB_TT is not set -CONFIG_USB_EHCI_TT_NEWSCHED=y -CONFIG_USB_EHCI_PCI=y -# CONFIG_USB_EHCI_FSL is not set -CONFIG_USB_EHCI_HCD_PLATFORM=y -# CONFIG_USB_OXU210HP_HCD is not set -# CONFIG_USB_ISP116X_HCD is not set -# CONFIG_USB_MAX3421_HCD is not set -CONFIG_USB_OHCI_HCD=y -CONFIG_USB_OHCI_HCD_PCI=y -CONFIG_USB_OHCI_HCD_PLATFORM=y -# CONFIG_USB_UHCI_HCD is not set -# CONFIG_USB_SL811_HCD is not set -# CONFIG_USB_R8A66597_HCD is not set -# CONFIG_USB_HCD_TEST_MODE is not set -# CONFIG_USB_RENESAS_USBHS is not set - -# -# USB Device Class drivers -# -# CONFIG_USB_ACM is not set -# CONFIG_USB_PRINTER is not set -# CONFIG_USB_WDM is not set -# CONFIG_USB_TMC is not set - -# -# NOTE: USB_STORAGE depends on SCSI but BLK_DEV_SD may -# - -# -# also be needed; see USB_STORAGE Help for more info -# -CONFIG_USB_STORAGE=y -# CONFIG_USB_STORAGE_DEBUG is not set -# CONFIG_USB_STORAGE_REALTEK is not set -# CONFIG_USB_STORAGE_DATAFAB is not set -# CONFIG_USB_STORAGE_FREECOM is not set -# CONFIG_USB_STORAGE_ISD200 is not set -# CONFIG_USB_STORAGE_USBAT is not set -# CONFIG_USB_STORAGE_SDDR09 is not set -# CONFIG_USB_STORAGE_SDDR55 is not set -# CONFIG_USB_STORAGE_JUMPSHOT is not set -# CONFIG_USB_STORAGE_ALAUDA is not set -# CONFIG_USB_STORAGE_ONETOUCH is not set -# CONFIG_USB_STORAGE_KARMA is not set -# CONFIG_USB_STORAGE_CYPRESS_ATACB is not set -# CONFIG_USB_STORAGE_ENE_UB6250 is not set -CONFIG_USB_UAS=y - -# -# USB Imaging devices -# -# CONFIG_USB_MDC800 is not set -# CONFIG_USB_MICROTEK is not set -# CONFIG_USBIP_CORE is not set - -# -# USB dual-mode controller drivers -# -# CONFIG_USB_CDNS_SUPPORT is not set -CONFIG_USB_MUSB_HDRC=y -# CONFIG_USB_MUSB_HOST is not set -# CONFIG_USB_MUSB_GADGET is not set -CONFIG_USB_MUSB_DUAL_ROLE=y - -# -# Platform Glue Layer -# -CONFIG_USB_MUSB_SUNXI=m -CONFIG_USB_MUSB_POLARFIRE_SOC=y - -# -# MUSB DMA mode -# -# CONFIG_MUSB_PIO_ONLY is not set -# CONFIG_USB_INVENTRA_DMA is not set -# CONFIG_USB_DWC3 is not set -# CONFIG_USB_DWC2 is not set -# CONFIG_USB_CHIPIDEA is not set -# CONFIG_USB_ISP1760 is not set - -# -# USB port drivers -# -# CONFIG_USB_SERIAL is not set - -# -# USB Miscellaneous drivers -# -# CONFIG_USB_EMI62 is not set -# CONFIG_USB_EMI26 is not set -# CONFIG_USB_ADUTUX is not set -# CONFIG_USB_SEVSEG is not set -# CONFIG_USB_LEGOTOWER is not set -# CONFIG_USB_LCD is not set -# CONFIG_USB_CYPRESS_CY7C63 is not set -# CONFIG_USB_CYTHERM is not set -# CONFIG_USB_IDMOUSE is not set -# CONFIG_USB_APPLEDISPLAY is not set -# CONFIG_APPLE_MFI_FASTCHARGE is not set -# CONFIG_USB_SISUSBVGA is not set -# CONFIG_USB_LD is not set -# CONFIG_USB_TRANCEVIBRATOR is not set -# CONFIG_USB_IOWARRIOR is not set -# CONFIG_USB_TEST is not set -# CONFIG_USB_EHSET_TEST_FIXTURE is not set -# CONFIG_USB_ISIGHTFW is not set -# CONFIG_USB_YUREX is not set -# CONFIG_USB_EZUSB_FX2 is not set -# CONFIG_USB_HUB_USB251XB is not set -# CONFIG_USB_HSIC_USB3503 is not set -# CONFIG_USB_HSIC_USB4604 is not set -# CONFIG_USB_LINK_LAYER_TEST is not set -# CONFIG_USB_CHAOSKEY is not set -# CONFIG_USB_ONBOARD_HUB is not set - -# -# USB Physical Layer drivers -# -CONFIG_USB_PHY=y -CONFIG_NOP_USB_XCEIV=y -# CONFIG_USB_GPIO_VBUS is not set -# CONFIG_USB_ISP1301 is not set -# end of USB Physical Layer drivers - -CONFIG_USB_GADGET=y -# CONFIG_USB_GADGET_DEBUG is not set -# CONFIG_USB_GADGET_DEBUG_FILES is not set -# CONFIG_USB_GADGET_DEBUG_FS is not set -CONFIG_USB_GADGET_VBUS_DRAW=2 -CONFIG_USB_GADGET_STORAGE_NUM_BUFFERS=2 -# CONFIG_U_SERIAL_CONSOLE is not set - -# -# USB Peripheral Controller -# -# CONFIG_USB_GR_UDC is not set -# CONFIG_USB_R8A66597 is not set -# CONFIG_USB_RENESAS_USB3 is not set -# CONFIG_USB_RENESAS_USBF is not set -# CONFIG_USB_PXA27X is not set -# CONFIG_USB_MV_UDC is not set -# CONFIG_USB_MV_U3D is not set -# CONFIG_USB_SNP_UDC_PLAT is not set -# CONFIG_USB_M66592 is not set -# CONFIG_USB_BDC_UDC is not set -# CONFIG_USB_AMD5536UDC is not set -# CONFIG_USB_NET2272 is not set -# CONFIG_USB_NET2280 is not set -# CONFIG_USB_GOKU is not set -# CONFIG_USB_EG20T is not set -# CONFIG_USB_GADGET_XILINX is not set -# CONFIG_USB_MAX3420_UDC is not set -# CONFIG_USB_CDNS2_UDC is not set -# CONFIG_USB_DUMMY_HCD is not set -# end of USB Peripheral Controller - -CONFIG_USB_LIBCOMPOSITE=y -CONFIG_USB_F_ACM=y -CONFIG_USB_F_SS_LB=y -CONFIG_USB_U_SERIAL=y -CONFIG_USB_U_ETHER=y -CONFIG_USB_F_SERIAL=y -CONFIG_USB_F_OBEX=y -CONFIG_USB_F_NCM=y -CONFIG_USB_F_ECM=y -CONFIG_USB_F_EEM=y -CONFIG_USB_F_SUBSET=y -CONFIG_USB_F_RNDIS=y -CONFIG_USB_F_MASS_STORAGE=y -CONFIG_USB_F_FS=y -CONFIG_USB_F_UVC=m -CONFIG_USB_F_HID=y -CONFIG_USB_F_PRINTER=y -CONFIG_USB_CONFIGFS=y -CONFIG_USB_CONFIGFS_SERIAL=y -CONFIG_USB_CONFIGFS_ACM=y -CONFIG_USB_CONFIGFS_OBEX=y -CONFIG_USB_CONFIGFS_NCM=y -CONFIG_USB_CONFIGFS_ECM=y -CONFIG_USB_CONFIGFS_ECM_SUBSET=y -CONFIG_USB_CONFIGFS_RNDIS=y -CONFIG_USB_CONFIGFS_EEM=y -CONFIG_USB_CONFIGFS_MASS_STORAGE=y -CONFIG_USB_CONFIGFS_F_LB_SS=y -CONFIG_USB_CONFIGFS_F_FS=y -CONFIG_USB_CONFIGFS_F_HID=y -CONFIG_USB_CONFIGFS_F_UVC=y -CONFIG_USB_CONFIGFS_F_PRINTER=y - -# -# USB Gadget precomposed configurations -# -# CONFIG_USB_ZERO is not set -# CONFIG_USB_ETH is not set -# CONFIG_USB_G_NCM is not set -# CONFIG_USB_GADGETFS is not set -# CONFIG_USB_FUNCTIONFS is not set -# CONFIG_USB_MASS_STORAGE is not set -# CONFIG_USB_G_SERIAL is not set -# CONFIG_USB_G_PRINTER is not set -# CONFIG_USB_CDC_COMPOSITE is not set -# CONFIG_USB_G_ACM_MS is not set -# CONFIG_USB_G_MULTI is not set -# CONFIG_USB_G_HID is not set -# CONFIG_USB_G_DBGP is not set -# CONFIG_USB_G_WEBCAM is not set -# CONFIG_USB_RAW_GADGET is not set -# end of USB Gadget precomposed configurations - -# CONFIG_TYPEC is not set -# CONFIG_USB_ROLE_SWITCH is not set -CONFIG_MMC=y -CONFIG_PWRSEQ_EMMC=y -CONFIG_PWRSEQ_SIMPLE=y -CONFIG_MMC_BLOCK=y -CONFIG_MMC_BLOCK_MINORS=8 -# CONFIG_SDIO_UART is not set -# CONFIG_MMC_TEST is not set - -# -# MMC/SD/SDIO Host Controller Drivers -# -# CONFIG_MMC_DEBUG is not set -CONFIG_MMC_SDHCI=y -CONFIG_MMC_SDHCI_IO_ACCESSORS=y -# CONFIG_MMC_SDHCI_PCI is not set -# CONFIG_MMC_SDHCI_ACPI is not set -CONFIG_MMC_SDHCI_PLTFM=y -# CONFIG_MMC_SDHCI_OF_ARASAN is not set -# CONFIG_MMC_SDHCI_OF_AT91 is not set -# CONFIG_MMC_SDHCI_OF_DWCMSHC is not set -CONFIG_MMC_SDHCI_CADENCE=y -# CONFIG_MMC_SDHCI_F_SDH30 is not set -# CONFIG_MMC_SDHCI_MILBEAUT is not set -# CONFIG_MMC_TIFM_SD is not set -CONFIG_MMC_SPI=y -# CONFIG_MMC_SDHI is not set -# CONFIG_MMC_CB710 is not set -# CONFIG_MMC_VIA_SDMMC is not set -# CONFIG_MMC_DW is not set -# CONFIG_MMC_SH_MMCIF is not set -# CONFIG_MMC_VUB300 is not set -# CONFIG_MMC_USHC is not set -# CONFIG_MMC_USDHI6ROL0 is not set -CONFIG_MMC_SUNXI=y -# CONFIG_MMC_CQHCI is not set -# CONFIG_MMC_HSQ is not set -# CONFIG_MMC_TOSHIBA_PCI is not set -# CONFIG_MMC_MTK is not set -# CONFIG_MMC_SDHCI_XENON is not set -# CONFIG_MMC_SDHCI_OMAP is not set -# CONFIG_MMC_SDHCI_AM654 is not set -# CONFIG_SCSI_UFSHCD is not set -# CONFIG_MEMSTICK is not set -# CONFIG_NEW_LEDS is not set -# CONFIG_ACCESSIBILITY is not set -# CONFIG_INFINIBAND is not set -CONFIG_EDAC_SUPPORT=y -CONFIG_RTC_LIB=y -CONFIG_RTC_CLASS=y -CONFIG_RTC_HCTOSYS=y -CONFIG_RTC_HCTOSYS_DEVICE="rtc0" -CONFIG_RTC_SYSTOHC=y -CONFIG_RTC_SYSTOHC_DEVICE="rtc0" -# CONFIG_RTC_DEBUG is not set -CONFIG_RTC_NVMEM=y - -# -# RTC interfaces -# -CONFIG_RTC_INTF_SYSFS=y -CONFIG_RTC_INTF_PROC=y -CONFIG_RTC_INTF_DEV=y -# CONFIG_RTC_INTF_DEV_UIE_EMUL is not set -# CONFIG_RTC_DRV_TEST is not set - -# -# I2C RTC drivers -# -# CONFIG_RTC_DRV_ABB5ZES3 is not set -# CONFIG_RTC_DRV_ABEOZ9 is not set -# CONFIG_RTC_DRV_ABX80X is not set -# CONFIG_RTC_DRV_DS1307 is not set -# CONFIG_RTC_DRV_DS1374 is not set -# CONFIG_RTC_DRV_DS1672 is not set -# CONFIG_RTC_DRV_HYM8563 is not set -# CONFIG_RTC_DRV_MAX6900 is not set -# CONFIG_RTC_DRV_NCT3018Y is not set -# CONFIG_RTC_DRV_RS5C372 is not set -# CONFIG_RTC_DRV_ISL1208 is not set -# CONFIG_RTC_DRV_ISL12022 is not set -# CONFIG_RTC_DRV_ISL12026 is not set -# CONFIG_RTC_DRV_X1205 is not set -# CONFIG_RTC_DRV_PCF8523 is not set -# CONFIG_RTC_DRV_PCF85063 is not set -# CONFIG_RTC_DRV_PCF85363 is not set -# CONFIG_RTC_DRV_PCF8563 is not set -# CONFIG_RTC_DRV_PCF8583 is not set -# CONFIG_RTC_DRV_M41T80 is not set -# CONFIG_RTC_DRV_BQ32K is not set -# CONFIG_RTC_DRV_S35390A is not set -# CONFIG_RTC_DRV_FM3130 is not set -# CONFIG_RTC_DRV_RX8010 is not set -# CONFIG_RTC_DRV_RX8581 is not set -# CONFIG_RTC_DRV_RX8025 is not set -# CONFIG_RTC_DRV_EM3027 is not set -# CONFIG_RTC_DRV_RV3028 is not set -# CONFIG_RTC_DRV_RV3032 is not set -# CONFIG_RTC_DRV_RV8803 is not set -# CONFIG_RTC_DRV_SD3078 is not set - -# -# SPI RTC drivers -# -# CONFIG_RTC_DRV_M41T93 is not set -# CONFIG_RTC_DRV_M41T94 is not set -# CONFIG_RTC_DRV_DS1302 is not set -# CONFIG_RTC_DRV_DS1305 is not set -# CONFIG_RTC_DRV_DS1343 is not set -# CONFIG_RTC_DRV_DS1347 is not set -# CONFIG_RTC_DRV_DS1390 is not set -# CONFIG_RTC_DRV_MAX6916 is not set -# CONFIG_RTC_DRV_R9701 is not set -# CONFIG_RTC_DRV_RX4581 is not set -# CONFIG_RTC_DRV_RS5C348 is not set -# CONFIG_RTC_DRV_MAX6902 is not set -# CONFIG_RTC_DRV_PCF2123 is not set -# CONFIG_RTC_DRV_MCP795 is not set -CONFIG_RTC_I2C_AND_SPI=y - -# -# SPI and I2C RTC drivers -# -# CONFIG_RTC_DRV_DS3232 is not set -# CONFIG_RTC_DRV_PCF2127 is not set -# CONFIG_RTC_DRV_RV3029C2 is not set -# CONFIG_RTC_DRV_RX6110 is not set - -# -# Platform RTC drivers -# -# CONFIG_RTC_DRV_DS1286 is not set -# CONFIG_RTC_DRV_DS1511 is not set -# CONFIG_RTC_DRV_DS1553 is not set -# CONFIG_RTC_DRV_DS1685_FAMILY is not set -# CONFIG_RTC_DRV_DS1742 is not set -# CONFIG_RTC_DRV_DS2404 is not set -# CONFIG_RTC_DRV_EFI is not set -# CONFIG_RTC_DRV_STK17TA8 is not set -# CONFIG_RTC_DRV_M48T86 is not set -# CONFIG_RTC_DRV_M48T35 is not set -# CONFIG_RTC_DRV_M48T59 is not set -# CONFIG_RTC_DRV_MSM6242 is not set -# CONFIG_RTC_DRV_BQ4802 is not set -# CONFIG_RTC_DRV_RP5C01 is not set -# CONFIG_RTC_DRV_ZYNQMP is not set - -# -# on-CPU RTC drivers -# -# CONFIG_RTC_DRV_SH is not set -CONFIG_RTC_DRV_SUN6I=y -# CONFIG_RTC_DRV_CADENCE is not set -# CONFIG_RTC_DRV_FTRTC010 is not set -# CONFIG_RTC_DRV_R7301 is not set - -# -# HID Sensor RTC drivers -# -CONFIG_RTC_DRV_GOLDFISH=y -# CONFIG_RTC_DRV_POLARFIRE_SOC is not set -CONFIG_DMADEVICES=y -# CONFIG_DMADEVICES_DEBUG is not set - -# -# DMA Devices -# -CONFIG_DMA_ENGINE=y -CONFIG_DMA_VIRTUAL_CHANNELS=m -CONFIG_DMA_ACPI=y -CONFIG_DMA_OF=y -# CONFIG_ALTERA_MSGDMA is not set -CONFIG_DMA_SUN6I=m -# CONFIG_DW_AXI_DMAC is not set -# CONFIG_FSL_EDMA is not set -# CONFIG_INTEL_IDMA64 is not set -# CONFIG_PLX_DMA is not set -# CONFIG_XILINX_XDMA is not set -# CONFIG_XILINX_ZYNQMP_DPDMA is not set -# CONFIG_QCOM_HIDMA_MGMT is not set -# CONFIG_QCOM_HIDMA is not set -# CONFIG_DW_DMAC is not set -# CONFIG_DW_DMAC_PCI is not set -# CONFIG_DW_EDMA is not set -# CONFIG_SF_PDMA is not set -# CONFIG_RCAR_DMAC is not set -# CONFIG_RENESAS_USB_DMAC is not set -# CONFIG_RZ_DMAC is not set - -# -# DMA Clients -# -# CONFIG_ASYNC_TX_DMA is not set -# CONFIG_DMATEST is not set - -# -# DMABUF options -# -CONFIG_SYNC_FILE=y -# CONFIG_SW_SYNC is not set -# CONFIG_UDMABUF is not set -# CONFIG_DMABUF_MOVE_NOTIFY is not set -# CONFIG_DMABUF_DEBUG is not set -# CONFIG_DMABUF_SELFTESTS is not set -# CONFIG_DMABUF_HEAPS is not set -# CONFIG_DMABUF_SYSFS_STATS is not set -# end of DMABUF options - -# CONFIG_AUXDISPLAY is not set -# CONFIG_UIO is not set -# CONFIG_VFIO is not set -# CONFIG_VIRT_DRIVERS is not set -CONFIG_VIRTIO_ANCHOR=y -CONFIG_VIRTIO=y -CONFIG_VIRTIO_PCI_LIB=y -CONFIG_VIRTIO_PCI_LIB_LEGACY=y -CONFIG_VIRTIO_MENU=y -CONFIG_VIRTIO_PCI=y -CONFIG_VIRTIO_PCI_LEGACY=y -# CONFIG_VIRTIO_PMEM is not set -CONFIG_VIRTIO_BALLOON=y -CONFIG_VIRTIO_INPUT=y -CONFIG_VIRTIO_MMIO=y -# CONFIG_VIRTIO_MMIO_CMDLINE_DEVICES is not set -# CONFIG_VDPA is not set -CONFIG_VHOST_MENU=y -# CONFIG_VHOST_NET is not set -# CONFIG_VHOST_CROSS_ENDIAN_LEGACY is not set - -# -# Microsoft Hyper-V guest support -# -# end of Microsoft Hyper-V guest support - -# CONFIG_GREYBUS is not set -# CONFIG_COMEDI is not set -# CONFIG_STAGING is not set -CONFIG_GOLDFISH=y -# CONFIG_GOLDFISH_PIPE is not set -CONFIG_HAVE_CLK=y -CONFIG_HAVE_CLK_PREPARE=y -CONFIG_COMMON_CLK=y -# CONFIG_LMK04832 is not set -# CONFIG_COMMON_CLK_MAX9485 is not set -# CONFIG_COMMON_CLK_SI5341 is not set -# CONFIG_COMMON_CLK_SI5351 is not set -# CONFIG_COMMON_CLK_SI514 is not set -# CONFIG_COMMON_CLK_SI544 is not set -# CONFIG_COMMON_CLK_SI570 is not set -# CONFIG_COMMON_CLK_CDCE706 is not set -# CONFIG_COMMON_CLK_CDCE925 is not set -# CONFIG_COMMON_CLK_CS2000_CP is not set -# CONFIG_COMMON_CLK_AXI_CLKGEN is not set -# CONFIG_COMMON_CLK_RS9_PCIE is not set -# CONFIG_COMMON_CLK_SI521XX is not set -# CONFIG_COMMON_CLK_VC5 is not set -# CONFIG_COMMON_CLK_VC7 is not set -# CONFIG_COMMON_CLK_FIXED_MMIO is not set -CONFIG_CLK_ANALOGBITS_WRPLL_CLN28HPC=y -CONFIG_MCHP_CLK_MPFS=y -CONFIG_CLK_RENESAS=y -CONFIG_CLK_R9A07G043=y -# CONFIG_CLK_RCAR_USB2_CLOCK_SEL is not set -CONFIG_CLK_RZG2L=y -CONFIG_CLK_SIFIVE=y -CONFIG_CLK_SIFIVE_PRCI=y -CONFIG_CLK_STARFIVE_JH71X0=y -CONFIG_CLK_STARFIVE_JH7100=y -CONFIG_CLK_STARFIVE_JH7100_AUDIO=m -CONFIG_CLK_STARFIVE_JH7110_SYS=y -CONFIG_CLK_STARFIVE_JH7110_AON=m -CONFIG_SUNXI_CCU=y -CONFIG_SUN20I_D1_CCU=y -CONFIG_SUN20I_D1_R_CCU=y -CONFIG_SUN6I_RTC_CCU=y -CONFIG_SUN8I_DE2_CCU=m -# CONFIG_XILINX_VCU is not set -# CONFIG_COMMON_CLK_XLNX_CLKWZRD is not set -# CONFIG_HWSPINLOCK is not set - -# -# Clock Source drivers -# -CONFIG_TIMER_OF=y -CONFIG_TIMER_PROBE=y -CONFIG_CLKSRC_MMIO=y -CONFIG_SUN4I_TIMER=y -# CONFIG_RENESAS_OSTM is not set -CONFIG_RISCV_TIMER=y -# end of Clock Source drivers - -CONFIG_MAILBOX=y -# CONFIG_PLATFORM_MHU is not set -# CONFIG_PCC is not set -# CONFIG_ALTERA_MBOX is not set -# CONFIG_MAILBOX_TEST is not set -CONFIG_POLARFIRE_SOC_MAILBOX=y -# CONFIG_SUN6I_MSGBOX is not set -CONFIG_IOMMU_API=y -CONFIG_IOMMU_SUPPORT=y - -# -# Generic IOMMU Pagetable Support -# -# end of Generic IOMMU Pagetable Support - -# CONFIG_IOMMU_DEBUGFS is not set -CONFIG_IOMMU_DEFAULT_DMA_STRICT=y -# CONFIG_IOMMU_DEFAULT_DMA_LAZY is not set -# CONFIG_IOMMU_DEFAULT_PASSTHROUGH is not set -CONFIG_OF_IOMMU=y -# CONFIG_IOMMUFD is not set -CONFIG_SUN50I_IOMMU=y - -# -# Remoteproc drivers -# -CONFIG_REMOTEPROC=y -CONFIG_REMOTEPROC_CDEV=y -# CONFIG_RCAR_REMOTEPROC is not set -# end of Remoteproc drivers - -# -# Rpmsg drivers -# -CONFIG_RPMSG=y -CONFIG_RPMSG_CHAR=y -CONFIG_RPMSG_CTRL=y -CONFIG_RPMSG_NS=y -# CONFIG_RPMSG_QCOM_GLINK_RPM is not set -CONFIG_RPMSG_VIRTIO=y -# end of Rpmsg drivers - -# CONFIG_SOUNDWIRE is not set - -# -# SOC (System On Chip) specific Drivers -# - -# -# Amlogic SoC drivers -# -# end of Amlogic SoC drivers - -# -# Broadcom SoC drivers -# -# end of Broadcom SoC drivers - -# -# NXP/Freescale QorIQ SoC drivers -# -# end of NXP/Freescale QorIQ SoC drivers - -# -# fujitsu SoC drivers -# -# end of fujitsu SoC drivers - -# -# i.MX SoC drivers -# -# end of i.MX SoC drivers - -# -# Enable LiteX SoC Builder specific drivers -# -# CONFIG_LITEX_SOC_CONTROLLER is not set -# end of Enable LiteX SoC Builder specific drivers - -CONFIG_POLARFIRE_SOC_SYS_CTRL=y -# CONFIG_WPCM450_SOC is not set - -# -# Qualcomm SoC drivers -# -# end of Qualcomm SoC drivers - -CONFIG_SOC_RENESAS=y -CONFIG_ARCH_RZG2L=y -CONFIG_ARCH_R9A07G043=y -# CONFIG_SIFIVE_CCACHE is not set -CONFIG_JH71XX_PMU=y -CONFIG_SUNXI_SRAM=y -# CONFIG_SUN20I_PPU is not set -# CONFIG_SOC_TI is not set - -# -# Xilinx SoC drivers -# -# end of Xilinx SoC drivers -# end of SOC (System On Chip) specific Drivers - -# CONFIG_PM_DEVFREQ is not set -CONFIG_EXTCON=y - -# -# Extcon Device Drivers -# -# CONFIG_EXTCON_ADC_JACK is not set -# CONFIG_EXTCON_FSA9480 is not set -# CONFIG_EXTCON_GPIO is not set -# CONFIG_EXTCON_MAX3355 is not set -# CONFIG_EXTCON_PTN5150 is not set -# CONFIG_EXTCON_RT8973A is not set -# CONFIG_EXTCON_SM5502 is not set -# CONFIG_EXTCON_USB_GPIO is not set -# CONFIG_MEMORY is not set -CONFIG_IIO=m -# CONFIG_IIO_BUFFER is not set -# CONFIG_IIO_CONFIGFS is not set -# CONFIG_IIO_TRIGGER is not set -# CONFIG_IIO_SW_DEVICE is not set -# CONFIG_IIO_SW_TRIGGER is not set -# CONFIG_IIO_TRIGGERED_EVENT is not set - -# -# Accelerometers -# -# CONFIG_ADIS16201 is not set -# CONFIG_ADIS16209 is not set -# CONFIG_ADXL313_I2C is not set -# CONFIG_ADXL313_SPI is not set -# CONFIG_ADXL345_I2C is not set -# CONFIG_ADXL345_SPI is not set -# CONFIG_ADXL355_I2C is not set -# CONFIG_ADXL355_SPI is not set -# CONFIG_ADXL367_SPI is not set -# CONFIG_ADXL367_I2C is not set -# CONFIG_ADXL372_SPI is not set -# CONFIG_ADXL372_I2C is not set -# CONFIG_BMA180 is not set -# CONFIG_BMA220 is not set -# CONFIG_BMA400 is not set -# CONFIG_BMC150_ACCEL is not set -# CONFIG_BMI088_ACCEL is not set -# CONFIG_DA280 is not set -# CONFIG_DA311 is not set -# CONFIG_DMARD06 is not set -# CONFIG_DMARD09 is not set -# CONFIG_DMARD10 is not set -# CONFIG_FXLS8962AF_I2C is not set -# CONFIG_FXLS8962AF_SPI is not set -# CONFIG_IIO_ST_ACCEL_3AXIS is not set -# CONFIG_IIO_KX022A_SPI is not set -# CONFIG_IIO_KX022A_I2C is not set -# CONFIG_KXSD9 is not set -# CONFIG_KXCJK1013 is not set -# CONFIG_MC3230 is not set -# CONFIG_MMA7455_I2C is not set -# CONFIG_MMA7455_SPI is not set -# CONFIG_MMA7660 is not set -# CONFIG_MMA8452 is not set -# CONFIG_MMA9551 is not set -# CONFIG_MMA9553 is not set -# CONFIG_MSA311 is not set -# CONFIG_MXC4005 is not set -# CONFIG_MXC6255 is not set -# CONFIG_SCA3000 is not set -# CONFIG_SCA3300 is not set -# CONFIG_STK8312 is not set -# CONFIG_STK8BA50 is not set -# end of Accelerometers - -# -# Analog to digital converters -# -# CONFIG_AD4130 is not set -# CONFIG_AD7091R5 is not set -# CONFIG_AD7124 is not set -# CONFIG_AD7192 is not set -# CONFIG_AD7266 is not set -# CONFIG_AD7280 is not set -# CONFIG_AD7291 is not set -# CONFIG_AD7292 is not set -# CONFIG_AD7298 is not set -# CONFIG_AD7476 is not set -# CONFIG_AD7606_IFACE_PARALLEL is not set -# CONFIG_AD7606_IFACE_SPI is not set -# CONFIG_AD7766 is not set -# CONFIG_AD7768_1 is not set -# CONFIG_AD7780 is not set -# CONFIG_AD7791 is not set -# CONFIG_AD7793 is not set -# CONFIG_AD7887 is not set -# CONFIG_AD7923 is not set -# CONFIG_AD7949 is not set -# CONFIG_AD799X is not set -# CONFIG_ADI_AXI_ADC is not set -# CONFIG_CC10001_ADC is not set -# CONFIG_ENVELOPE_DETECTOR is not set -# CONFIG_HI8435 is not set -# CONFIG_HX711 is not set -# CONFIG_INA2XX_ADC is not set -# CONFIG_LTC2471 is not set -# CONFIG_LTC2485 is not set -# CONFIG_LTC2496 is not set -# CONFIG_LTC2497 is not set -# CONFIG_MAX1027 is not set -# CONFIG_MAX11100 is not set -# CONFIG_MAX1118 is not set -# CONFIG_MAX11205 is not set -# CONFIG_MAX11410 is not set -# CONFIG_MAX1241 is not set -# CONFIG_MAX1363 is not set -# CONFIG_MAX9611 is not set -# CONFIG_MCP320X is not set -# CONFIG_MCP3422 is not set -# CONFIG_MCP3911 is not set -# CONFIG_NAU7802 is not set -# CONFIG_RICHTEK_RTQ6056 is not set -# CONFIG_RZG2L_ADC is not set -# CONFIG_SD_ADC_MODULATOR is not set -# CONFIG_TI_ADC081C is not set -# CONFIG_TI_ADC0832 is not set -# CONFIG_TI_ADC084S021 is not set -# CONFIG_TI_ADC12138 is not set -# CONFIG_TI_ADC108S102 is not set -# CONFIG_TI_ADC128S052 is not set -# CONFIG_TI_ADC161S626 is not set -# CONFIG_TI_ADS1015 is not set -# CONFIG_TI_ADS7924 is not set -# CONFIG_TI_ADS1100 is not set -# CONFIG_TI_ADS7950 is not set -# CONFIG_TI_ADS8344 is not set -# CONFIG_TI_ADS8688 is not set -# CONFIG_TI_ADS124S08 is not set -# CONFIG_TI_ADS131E08 is not set -# CONFIG_TI_LMP92064 is not set -# CONFIG_TI_TLC4541 is not set -# CONFIG_TI_TSC2046 is not set -# CONFIG_VF610_ADC is not set -# CONFIG_XILINX_XADC is not set -# end of Analog to digital converters - -# -# Analog to digital and digital to analog converters -# -# CONFIG_AD74115 is not set -# CONFIG_AD74413R is not set -# end of Analog to digital and digital to analog converters - -# -# Analog Front Ends -# -# CONFIG_IIO_RESCALE is not set -# end of Analog Front Ends - -# -# Amplifiers -# -# CONFIG_AD8366 is not set -# CONFIG_ADA4250 is not set -# CONFIG_HMC425 is not set -# end of Amplifiers - -# -# Capacitance to digital converters -# -# CONFIG_AD7150 is not set -# CONFIG_AD7746 is not set -# end of Capacitance to digital converters - -# -# Chemical Sensors -# -# CONFIG_ATLAS_PH_SENSOR is not set -# CONFIG_ATLAS_EZO_SENSOR is not set -# CONFIG_BME680 is not set -# CONFIG_CCS811 is not set -# CONFIG_IAQCORE is not set -# CONFIG_SCD30_CORE is not set -# CONFIG_SCD4X is not set -# CONFIG_SENSIRION_SGP30 is not set -# CONFIG_SENSIRION_SGP40 is not set -# CONFIG_SPS30_I2C is not set -# CONFIG_SENSEAIR_SUNRISE_CO2 is not set -# CONFIG_VZ89X is not set -# end of Chemical Sensors - -# -# Hid Sensor IIO Common -# -# end of Hid Sensor IIO Common - -# -# IIO SCMI Sensors -# -# end of IIO SCMI Sensors - -# -# SSP Sensor Common -# -# CONFIG_IIO_SSP_SENSORHUB is not set -# end of SSP Sensor Common - -# -# Digital to analog converters -# -# CONFIG_AD3552R is not set -# CONFIG_AD5064 is not set -# CONFIG_AD5360 is not set -# CONFIG_AD5380 is not set -# CONFIG_AD5421 is not set -# CONFIG_AD5446 is not set -# CONFIG_AD5449 is not set -# CONFIG_AD5592R is not set -# CONFIG_AD5593R is not set -# CONFIG_AD5504 is not set -# CONFIG_AD5624R_SPI is not set -# CONFIG_LTC2688 is not set -# CONFIG_AD5686_SPI is not set -# CONFIG_AD5696_I2C is not set -# CONFIG_AD5755 is not set -# CONFIG_AD5758 is not set -# CONFIG_AD5761 is not set -# CONFIG_AD5764 is not set -# CONFIG_AD5766 is not set -# CONFIG_AD5770R is not set -# CONFIG_AD5791 is not set -# CONFIG_AD7293 is not set -# CONFIG_AD7303 is not set -# CONFIG_AD8801 is not set -# CONFIG_DPOT_DAC is not set -# CONFIG_DS4424 is not set -# CONFIG_LTC1660 is not set -# CONFIG_LTC2632 is not set -# CONFIG_M62332 is not set -# CONFIG_MAX517 is not set -# CONFIG_MAX5522 is not set -# CONFIG_MAX5821 is not set -# CONFIG_MCP4725 is not set -# CONFIG_MCP4922 is not set -# CONFIG_TI_DAC082S085 is not set -# CONFIG_TI_DAC5571 is not set -# CONFIG_TI_DAC7311 is not set -# CONFIG_TI_DAC7612 is not set -# CONFIG_VF610_DAC is not set -# end of Digital to analog converters - -# -# IIO dummy driver -# -# end of IIO dummy driver - -# -# Filters -# -# CONFIG_ADMV8818 is not set -# end of Filters - -# -# Frequency Synthesizers DDS/PLL -# - -# -# Clock Generator/Distribution -# -# CONFIG_AD9523 is not set -# end of Clock Generator/Distribution - -# -# Phase-Locked Loop (PLL) frequency synthesizers -# -# CONFIG_ADF4350 is not set -# CONFIG_ADF4371 is not set -# CONFIG_ADF4377 is not set -# CONFIG_ADMV1013 is not set -# CONFIG_ADMV1014 is not set -# CONFIG_ADMV4420 is not set -# CONFIG_ADRF6780 is not set -# end of Phase-Locked Loop (PLL) frequency synthesizers -# end of Frequency Synthesizers DDS/PLL - -# -# Digital gyroscope sensors -# -# CONFIG_ADIS16080 is not set -# CONFIG_ADIS16130 is not set -# CONFIG_ADIS16136 is not set -# CONFIG_ADIS16260 is not set -# CONFIG_ADXRS290 is not set -# CONFIG_ADXRS450 is not set -# CONFIG_BMG160 is not set -# CONFIG_FXAS21002C is not set -# CONFIG_MPU3050_I2C is not set -# CONFIG_IIO_ST_GYRO_3AXIS is not set -# CONFIG_ITG3200 is not set -# end of Digital gyroscope sensors - -# -# Health Sensors -# - -# -# Heart Rate Monitors -# -# CONFIG_AFE4403 is not set -# CONFIG_AFE4404 is not set -# CONFIG_MAX30100 is not set -# CONFIG_MAX30102 is not set -# end of Heart Rate Monitors -# end of Health Sensors - -# -# Humidity sensors -# -# CONFIG_AM2315 is not set -# CONFIG_DHT11 is not set -# CONFIG_HDC100X is not set -# CONFIG_HDC2010 is not set -# CONFIG_HTS221 is not set -# CONFIG_HTU21 is not set -# CONFIG_SI7005 is not set -# CONFIG_SI7020 is not set -# end of Humidity sensors - -# -# Inertial measurement units -# -# CONFIG_ADIS16400 is not set -# CONFIG_ADIS16460 is not set -# CONFIG_ADIS16475 is not set -# CONFIG_ADIS16480 is not set -# CONFIG_BMI160_I2C is not set -# CONFIG_BMI160_SPI is not set -# CONFIG_BOSCH_BNO055_I2C is not set -# CONFIG_FXOS8700_I2C is not set -# CONFIG_FXOS8700_SPI is not set -# CONFIG_KMX61 is not set -# CONFIG_INV_ICM42600_I2C is not set -# CONFIG_INV_ICM42600_SPI is not set -# CONFIG_INV_MPU6050_I2C is not set -# CONFIG_INV_MPU6050_SPI is not set -# CONFIG_IIO_ST_LSM6DSX is not set -# CONFIG_IIO_ST_LSM9DS0 is not set -# end of Inertial measurement units - -# -# Light sensors -# -# CONFIG_ACPI_ALS is not set -# CONFIG_ADJD_S311 is not set -# CONFIG_ADUX1020 is not set -# CONFIG_AL3010 is not set -# CONFIG_AL3320A is not set -# CONFIG_APDS9300 is not set -# CONFIG_APDS9960 is not set -# CONFIG_AS73211 is not set -# CONFIG_BH1750 is not set -# CONFIG_BH1780 is not set -# CONFIG_CM32181 is not set -# CONFIG_CM3232 is not set -# CONFIG_CM3323 is not set -# CONFIG_CM3605 is not set -# CONFIG_CM36651 is not set -# CONFIG_GP2AP002 is not set -# CONFIG_GP2AP020A00F is not set -# CONFIG_SENSORS_ISL29018 is not set -# CONFIG_SENSORS_ISL29028 is not set -# CONFIG_ISL29125 is not set -# CONFIG_JSA1212 is not set -# CONFIG_ROHM_BU27008 is not set -# CONFIG_ROHM_BU27034 is not set -# CONFIG_RPR0521 is not set -# CONFIG_LTR501 is not set -# CONFIG_LTRF216A is not set -# CONFIG_LV0104CS is not set -# CONFIG_MAX44000 is not set -# CONFIG_MAX44009 is not set -# CONFIG_NOA1305 is not set -# CONFIG_OPT3001 is not set -# CONFIG_OPT4001 is not set -# CONFIG_PA12203001 is not set -# CONFIG_SI1133 is not set -# CONFIG_SI1145 is not set -# CONFIG_STK3310 is not set -# CONFIG_ST_UVIS25 is not set -# CONFIG_TCS3414 is not set -# CONFIG_TCS3472 is not set -# CONFIG_SENSORS_TSL2563 is not set -# CONFIG_TSL2583 is not set -# CONFIG_TSL2591 is not set -# CONFIG_TSL2772 is not set -# CONFIG_TSL4531 is not set -# CONFIG_US5182D is not set -# CONFIG_VCNL4000 is not set -# CONFIG_VCNL4035 is not set -# CONFIG_VEML6030 is not set -# CONFIG_VEML6070 is not set -# CONFIG_VL6180 is not set -# CONFIG_ZOPT2201 is not set -# end of Light sensors - -# -# Magnetometer sensors -# -# CONFIG_AK8974 is not set -# CONFIG_AK8975 is not set -# CONFIG_AK09911 is not set -# CONFIG_BMC150_MAGN_I2C is not set -# CONFIG_BMC150_MAGN_SPI is not set -# CONFIG_MAG3110 is not set -# CONFIG_MMC35240 is not set -# CONFIG_IIO_ST_MAGN_3AXIS is not set -# CONFIG_SENSORS_HMC5843_I2C is not set -# CONFIG_SENSORS_HMC5843_SPI is not set -# CONFIG_SENSORS_RM3100_I2C is not set -# CONFIG_SENSORS_RM3100_SPI is not set -# CONFIG_TI_TMAG5273 is not set -# CONFIG_YAMAHA_YAS530 is not set -# end of Magnetometer sensors - -# -# Multiplexers -# -# CONFIG_IIO_MUX is not set -# end of Multiplexers - -# -# Inclinometer sensors -# -# end of Inclinometer sensors - -# -# Linear and angular position sensors -# -# end of Linear and angular position sensors - -# -# Digital potentiometers -# -# CONFIG_AD5110 is not set -# CONFIG_AD5272 is not set -# CONFIG_DS1803 is not set -# CONFIG_MAX5432 is not set -# CONFIG_MAX5481 is not set -# CONFIG_MAX5487 is not set -# CONFIG_MCP4018 is not set -# CONFIG_MCP4131 is not set -# CONFIG_MCP4531 is not set -# CONFIG_MCP41010 is not set -# CONFIG_TPL0102 is not set -# CONFIG_X9250 is not set -# end of Digital potentiometers - -# -# Digital potentiostats -# -# CONFIG_LMP91000 is not set -# end of Digital potentiostats - -# -# Pressure sensors -# -# CONFIG_ABP060MG is not set -# CONFIG_BMP280 is not set -# CONFIG_DLHL60D is not set -# CONFIG_DPS310 is not set -# CONFIG_HP03 is not set -# CONFIG_ICP10100 is not set -# CONFIG_MPL115_I2C is not set -# CONFIG_MPL115_SPI is not set -# CONFIG_MPL3115 is not set -# CONFIG_MPRLS0025PA is not set -# CONFIG_MS5611 is not set -# CONFIG_MS5637 is not set -# CONFIG_IIO_ST_PRESS is not set -# CONFIG_T5403 is not set -# CONFIG_HP206C is not set -# CONFIG_ZPA2326 is not set -# end of Pressure sensors - -# -# Lightning sensors -# -# CONFIG_AS3935 is not set -# end of Lightning sensors - -# -# Proximity and distance sensors -# -# CONFIG_ISL29501 is not set -# CONFIG_LIDAR_LITE_V2 is not set -# CONFIG_MB1232 is not set -# CONFIG_PING is not set -# CONFIG_RFD77402 is not set -# CONFIG_SRF04 is not set -# CONFIG_SX9310 is not set -# CONFIG_SX9324 is not set -# CONFIG_SX9360 is not set -# CONFIG_SX9500 is not set -# CONFIG_SRF08 is not set -# CONFIG_VCNL3020 is not set -# CONFIG_VL53L0X_I2C is not set -# end of Proximity and distance sensors - -# -# Resolver to digital converters -# -# CONFIG_AD2S90 is not set -# CONFIG_AD2S1200 is not set -# end of Resolver to digital converters - -# -# Temperature sensors -# -# CONFIG_LTC2983 is not set -# CONFIG_MAXIM_THERMOCOUPLE is not set -# CONFIG_MLX90614 is not set -# CONFIG_MLX90632 is not set -# CONFIG_TMP006 is not set -# CONFIG_TMP007 is not set -# CONFIG_TMP117 is not set -# CONFIG_TSYS01 is not set -# CONFIG_TSYS02D is not set -# CONFIG_MAX30208 is not set -# CONFIG_MAX31856 is not set -# CONFIG_MAX31865 is not set -# end of Temperature sensors - -# CONFIG_NTB is not set -# CONFIG_PWM is not set - -# -# IRQ chip support -# -CONFIG_IRQCHIP=y -# CONFIG_AL_FIC is not set -CONFIG_RENESAS_RZG2L_IRQC=y -# CONFIG_XILINX_INTC is not set -CONFIG_RISCV_INTC=y -CONFIG_SIFIVE_PLIC=y -# end of IRQ chip support - -# CONFIG_IPACK_BUS is not set -CONFIG_RESET_CONTROLLER=y -CONFIG_RESET_POLARFIRE_SOC=y -# CONFIG_RESET_RZG2L_USBPHY_CTRL is not set -CONFIG_RESET_SIMPLE=y -CONFIG_RESET_SUNXI=y -# CONFIG_RESET_TI_SYSCON is not set -# CONFIG_RESET_TI_TPS380X is not set -CONFIG_RESET_STARFIVE_JH71X0=y -CONFIG_RESET_STARFIVE_JH7100=y -CONFIG_RESET_STARFIVE_JH7110=y - -# -# PHY Subsystem -# -CONFIG_GENERIC_PHY=y -CONFIG_GENERIC_PHY_MIPI_DPHY=y -# CONFIG_PHY_CAN_TRANSCEIVER is not set -CONFIG_PHY_SUN4I_USB=m -CONFIG_PHY_SUN6I_MIPI_DPHY=m -# CONFIG_PHY_SUN9I_USB is not set -# CONFIG_PHY_SUN50I_USB3 is not set - -# -# PHY drivers for Broadcom platforms -# -# CONFIG_BCM_KONA_USB2_PHY is not set -# end of PHY drivers for Broadcom platforms - -# CONFIG_PHY_CADENCE_TORRENT is not set -# CONFIG_PHY_CADENCE_DPHY is not set -# CONFIG_PHY_CADENCE_DPHY_RX is not set -# CONFIG_PHY_CADENCE_SIERRA is not set -# CONFIG_PHY_CADENCE_SALVO is not set -# CONFIG_PHY_PXA_28NM_HSIC is not set -# CONFIG_PHY_PXA_28NM_USB2 is not set -# CONFIG_PHY_LAN966X_SERDES is not set -# CONFIG_PHY_CPCAP_USB is not set -# CONFIG_PHY_MAPPHONE_MDM6600 is not set -# CONFIG_PHY_OCELOT_SERDES is not set -# CONFIG_PHY_R8A779F0_ETHERNET_SERDES is not set -# CONFIG_PHY_RCAR_GEN2 is not set -# CONFIG_PHY_RCAR_GEN3_PCIE is not set -# CONFIG_PHY_RCAR_GEN3_USB2 is not set -# CONFIG_PHY_RCAR_GEN3_USB3 is not set -# end of PHY Subsystem - -# CONFIG_POWERCAP is not set -# CONFIG_MCB is not set - -# -# Performance monitor support -# -CONFIG_RISCV_PMU=y -CONFIG_RISCV_PMU_LEGACY=y -CONFIG_RISCV_PMU_SBI=y -# end of Performance monitor support - -# CONFIG_RAS is not set -# CONFIG_USB4 is not set - -# -# Android -# -# CONFIG_ANDROID_BINDER_IPC is not set -# end of Android - -CONFIG_LIBNVDIMM=y -CONFIG_BLK_DEV_PMEM=y -CONFIG_ND_CLAIM=y -CONFIG_ND_BTT=y -CONFIG_BTT=y -CONFIG_OF_PMEM=y -CONFIG_DAX=y -CONFIG_NVMEM=y -CONFIG_NVMEM_SYSFS=y - -# -# Layout Types -# -# CONFIG_NVMEM_LAYOUT_SL28_VPD is not set -# CONFIG_NVMEM_LAYOUT_ONIE_TLV is not set -# end of Layout Types - -# CONFIG_NVMEM_RMEM is not set -CONFIG_NVMEM_SUNXI_SID=y - -# -# HW tracing support -# -# CONFIG_STM is not set -# CONFIG_INTEL_TH is not set -# end of HW tracing support - -# CONFIG_FPGA is not set -# CONFIG_FSI is not set -# CONFIG_SIOX is not set -# CONFIG_SLIMBUS is not set -# CONFIG_INTERCONNECT is not set -# CONFIG_COUNTER is not set -# CONFIG_MOST is not set -# CONFIG_PECI is not set -# CONFIG_HTE is not set -# end of Device Drivers - -# -# File systems -# -# CONFIG_VALIDATE_FS_PARSER is not set -CONFIG_FS_IOMAP=y -CONFIG_LEGACY_DIRECT_IO=y -# CONFIG_EXT2_FS is not set -# CONFIG_EXT3_FS is not set -CONFIG_EXT4_FS=y -CONFIG_EXT4_USE_FOR_EXT2=y -CONFIG_EXT4_FS_POSIX_ACL=y -CONFIG_EXT4_FS_SECURITY=y -# CONFIG_EXT4_DEBUG is not set -CONFIG_JBD2=y -# CONFIG_JBD2_DEBUG is not set -CONFIG_FS_MBCACHE=y -# CONFIG_REISERFS_FS is not set -# CONFIG_JFS_FS is not set -# CONFIG_XFS_FS is not set -# CONFIG_GFS2_FS is not set -# CONFIG_OCFS2_FS is not set -CONFIG_BTRFS_FS=m -CONFIG_BTRFS_FS_POSIX_ACL=y -# CONFIG_BTRFS_FS_CHECK_INTEGRITY is not set -# CONFIG_BTRFS_FS_RUN_SANITY_TESTS is not set -# CONFIG_BTRFS_DEBUG is not set -# CONFIG_BTRFS_ASSERT is not set -# CONFIG_BTRFS_FS_REF_VERIFY is not set -# CONFIG_NILFS2_FS is not set -# CONFIG_F2FS_FS is not set -CONFIG_FS_POSIX_ACL=y -CONFIG_EXPORTFS=y -# CONFIG_EXPORTFS_BLOCK_OPS is not set -CONFIG_FILE_LOCKING=y -# CONFIG_FS_ENCRYPTION is not set -# CONFIG_FS_VERITY is not set -CONFIG_FSNOTIFY=y -CONFIG_DNOTIFY=y -CONFIG_INOTIFY_USER=y -# CONFIG_FANOTIFY is not set -# CONFIG_QUOTA is not set -CONFIG_AUTOFS_FS=y -# CONFIG_FUSE_FS is not set -CONFIG_OVERLAY_FS=m -# CONFIG_OVERLAY_FS_REDIRECT_DIR is not set -CONFIG_OVERLAY_FS_REDIRECT_ALWAYS_FOLLOW=y -# CONFIG_OVERLAY_FS_INDEX is not set -# CONFIG_OVERLAY_FS_XINO_AUTO is not set -# CONFIG_OVERLAY_FS_METACOPY is not set - -# -# Caches -# -CONFIG_NETFS_SUPPORT=y -# CONFIG_NETFS_STATS is not set -# CONFIG_FSCACHE is not set -# end of Caches - -# -# CD-ROM/DVD Filesystems -# -CONFIG_ISO9660_FS=y -CONFIG_JOLIET=y -CONFIG_ZISOFS=y -# CONFIG_UDF_FS is not set -# end of CD-ROM/DVD Filesystems - -# -# DOS/FAT/EXFAT/NT Filesystems -# -CONFIG_FAT_FS=y -CONFIG_MSDOS_FS=y -CONFIG_VFAT_FS=y -CONFIG_FAT_DEFAULT_CODEPAGE=437 -CONFIG_FAT_DEFAULT_IOCHARSET="iso8859-1" -# CONFIG_FAT_DEFAULT_UTF8 is not set -# CONFIG_EXFAT_FS is not set -# CONFIG_NTFS_FS is not set -# CONFIG_NTFS3_FS is not set -# end of DOS/FAT/EXFAT/NT Filesystems - -# -# Pseudo filesystems -# -CONFIG_PROC_FS=y -# CONFIG_PROC_KCORE is not set -CONFIG_PROC_SYSCTL=y -CONFIG_PROC_PAGE_MONITOR=y -CONFIG_PROC_CHILDREN=y -CONFIG_KERNFS=y -CONFIG_SYSFS=y -CONFIG_TMPFS=y -CONFIG_TMPFS_POSIX_ACL=y -CONFIG_TMPFS_XATTR=y -# CONFIG_TMPFS_INODE64 is not set -CONFIG_ARCH_SUPPORTS_HUGETLBFS=y -CONFIG_HUGETLBFS=y -CONFIG_HUGETLB_PAGE=y -CONFIG_HUGETLB_PAGE_OPTIMIZE_VMEMMAP=y -# CONFIG_HUGETLB_PAGE_OPTIMIZE_VMEMMAP_DEFAULT_ON is not set -CONFIG_MEMFD_CREATE=y -CONFIG_ARCH_HAS_GIGANTIC_PAGE=y -CONFIG_CONFIGFS_FS=y -CONFIG_EFIVAR_FS=m -# end of Pseudo filesystems - -CONFIG_MISC_FILESYSTEMS=y -# CONFIG_ORANGEFS_FS is not set -# CONFIG_ADFS_FS is not set -# CONFIG_AFFS_FS is not set -# CONFIG_ECRYPT_FS is not set -# CONFIG_HFS_FS is not set -# CONFIG_HFSPLUS_FS is not set -# CONFIG_BEFS_FS is not set -# CONFIG_BFS_FS is not set -# CONFIG_EFS_FS is not set -# CONFIG_CRAMFS is not set -# CONFIG_SQUASHFS is not set -# CONFIG_VXFS_FS is not set -# CONFIG_MINIX_FS is not set -# CONFIG_OMFS_FS is not set -# CONFIG_HPFS_FS is not set -# CONFIG_QNX4FS_FS is not set -# CONFIG_QNX6FS_FS is not set -# CONFIG_ROMFS_FS is not set -# CONFIG_PSTORE is not set -# CONFIG_SYSV_FS is not set -# CONFIG_UFS_FS is not set -# CONFIG_EROFS_FS is not set -CONFIG_NETWORK_FILESYSTEMS=y -CONFIG_NFS_FS=y -CONFIG_NFS_V2=y -CONFIG_NFS_V3=y -# CONFIG_NFS_V3_ACL is not set -CONFIG_NFS_V4=y -# CONFIG_NFS_SWAP is not set -CONFIG_NFS_V4_1=y -CONFIG_NFS_V4_2=y -CONFIG_PNFS_FILE_LAYOUT=y -CONFIG_PNFS_BLOCK=y -CONFIG_PNFS_FLEXFILE_LAYOUT=y -CONFIG_NFS_V4_1_IMPLEMENTATION_ID_DOMAIN="kernel.org" -# CONFIG_NFS_V4_1_MIGRATION is not set -CONFIG_NFS_V4_SECURITY_LABEL=y -CONFIG_ROOT_NFS=y -# CONFIG_NFS_USE_LEGACY_DNS is not set -CONFIG_NFS_USE_KERNEL_DNS=y -CONFIG_NFS_DISABLE_UDP_SUPPORT=y -# CONFIG_NFS_V4_2_READ_PLUS is not set -# CONFIG_NFSD is not set -CONFIG_GRACE_PERIOD=y -CONFIG_LOCKD=y -CONFIG_LOCKD_V4=y -CONFIG_NFS_COMMON=y -CONFIG_NFS_V4_2_SSC_HELPER=y -CONFIG_SUNRPC=y -CONFIG_SUNRPC_GSS=y -CONFIG_SUNRPC_BACKCHANNEL=y -CONFIG_RPCSEC_GSS_KRB5=y -# CONFIG_SUNRPC_DEBUG is not set -# CONFIG_CEPH_FS is not set -# CONFIG_CIFS is not set -# CONFIG_SMB_SERVER is not set -# CONFIG_CODA_FS is not set -# CONFIG_AFS_FS is not set -CONFIG_9P_FS=y -# CONFIG_9P_FS_POSIX_ACL is not set -# CONFIG_9P_FS_SECURITY is not set -CONFIG_NLS=y -CONFIG_NLS_DEFAULT="iso8859-1" -CONFIG_NLS_CODEPAGE_437=y -# CONFIG_NLS_CODEPAGE_737 is not set -# CONFIG_NLS_CODEPAGE_775 is not set -# CONFIG_NLS_CODEPAGE_850 is not set -# CONFIG_NLS_CODEPAGE_852 is not set -# CONFIG_NLS_CODEPAGE_855 is not set -# CONFIG_NLS_CODEPAGE_857 is not set -# CONFIG_NLS_CODEPAGE_860 is not set -# CONFIG_NLS_CODEPAGE_861 is not set -# CONFIG_NLS_CODEPAGE_862 is not set -# CONFIG_NLS_CODEPAGE_863 is not set -# CONFIG_NLS_CODEPAGE_864 is not set -# CONFIG_NLS_CODEPAGE_865 is not set -# CONFIG_NLS_CODEPAGE_866 is not set -# CONFIG_NLS_CODEPAGE_869 is not set -# CONFIG_NLS_CODEPAGE_936 is not set -# CONFIG_NLS_CODEPAGE_950 is not set -# CONFIG_NLS_CODEPAGE_932 is not set -# CONFIG_NLS_CODEPAGE_949 is not set -# CONFIG_NLS_CODEPAGE_874 is not set -# CONFIG_NLS_ISO8859_8 is not set -# CONFIG_NLS_CODEPAGE_1250 is not set -# CONFIG_NLS_CODEPAGE_1251 is not set -# CONFIG_NLS_ASCII is not set -CONFIG_NLS_ISO8859_1=y -# CONFIG_NLS_ISO8859_2 is not set -# CONFIG_NLS_ISO8859_3 is not set -# CONFIG_NLS_ISO8859_4 is not set -# CONFIG_NLS_ISO8859_5 is not set -# CONFIG_NLS_ISO8859_6 is not set -# CONFIG_NLS_ISO8859_7 is not set -# CONFIG_NLS_ISO8859_9 is not set -# CONFIG_NLS_ISO8859_13 is not set -# CONFIG_NLS_ISO8859_14 is not set -# CONFIG_NLS_ISO8859_15 is not set -# CONFIG_NLS_KOI8_R is not set -# CONFIG_NLS_KOI8_U is not set -# CONFIG_NLS_MAC_ROMAN is not set -# CONFIG_NLS_MAC_CELTIC is not set -# CONFIG_NLS_MAC_CENTEURO is not set -# CONFIG_NLS_MAC_CROATIAN is not set -# CONFIG_NLS_MAC_CYRILLIC is not set -# CONFIG_NLS_MAC_GAELIC is not set -# CONFIG_NLS_MAC_GREEK is not set -# CONFIG_NLS_MAC_ICELAND is not set -# CONFIG_NLS_MAC_INUIT is not set -# CONFIG_NLS_MAC_ROMANIAN is not set -# CONFIG_NLS_MAC_TURKISH is not set -# CONFIG_NLS_UTF8 is not set -# CONFIG_DLM is not set -# CONFIG_UNICODE is not set -CONFIG_IO_WQ=y -# end of File systems - -# -# Security options -# -CONFIG_KEYS=y -# CONFIG_KEYS_REQUEST_CACHE is not set -# CONFIG_PERSISTENT_KEYRINGS is not set -# CONFIG_TRUSTED_KEYS is not set -# CONFIG_ENCRYPTED_KEYS is not set -# CONFIG_KEY_DH_OPERATIONS is not set -# CONFIG_SECURITY_DMESG_RESTRICT is not set -CONFIG_SECURITY=y -CONFIG_SECURITYFS=y -CONFIG_SECURITY_NETWORK=y -# CONFIG_SECURITY_NETWORK_XFRM is not set -CONFIG_SECURITY_PATH=y -CONFIG_LSM_MMAP_MIN_ADDR=65536 -# CONFIG_HARDENED_USERCOPY is not set -# CONFIG_FORTIFY_SOURCE is not set -# CONFIG_STATIC_USERMODEHELPER is not set -CONFIG_SECURITY_SELINUX=y -# CONFIG_SECURITY_SELINUX_BOOTPARAM is not set -CONFIG_SECURITY_SELINUX_DEVELOP=y -CONFIG_SECURITY_SELINUX_AVC_STATS=y -CONFIG_SECURITY_SELINUX_SIDTAB_HASH_BITS=9 -CONFIG_SECURITY_SELINUX_SID2STR_CACHE_SIZE=256 -# CONFIG_SECURITY_SMACK is not set -# CONFIG_SECURITY_TOMOYO is not set -CONFIG_SECURITY_APPARMOR=y -# CONFIG_SECURITY_APPARMOR_DEBUG is not set -CONFIG_SECURITY_APPARMOR_INTROSPECT_POLICY=y -CONFIG_SECURITY_APPARMOR_HASH=y -CONFIG_SECURITY_APPARMOR_HASH_DEFAULT=y -CONFIG_SECURITY_APPARMOR_EXPORT_BINARY=y -CONFIG_SECURITY_APPARMOR_PARANOID_LOAD=y -# CONFIG_SECURITY_LOADPIN is not set -# CONFIG_SECURITY_YAMA is not set -# CONFIG_SECURITY_SAFESETID is not set -# CONFIG_SECURITY_LOCKDOWN_LSM is not set -# CONFIG_SECURITY_LANDLOCK is not set -CONFIG_INTEGRITY=y -# CONFIG_INTEGRITY_SIGNATURE is not set -CONFIG_INTEGRITY_AUDIT=y -# CONFIG_IMA is not set -# CONFIG_EVM is not set -# CONFIG_DEFAULT_SECURITY_SELINUX is not set -# CONFIG_DEFAULT_SECURITY_APPARMOR is not set -CONFIG_DEFAULT_SECURITY_DAC=y -CONFIG_LSM="landlock,lockdown,yama,loadpin,safesetid,bpf" - -# -# Kernel hardening options -# - -# -# Memory initialization -# -CONFIG_INIT_STACK_NONE=y -# CONFIG_GCC_PLUGIN_STRUCTLEAK_USER is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF is not set -# CONFIG_GCC_PLUGIN_STRUCTLEAK_BYREF_ALL is not set -# CONFIG_INIT_ON_ALLOC_DEFAULT_ON is not set -# CONFIG_INIT_ON_FREE_DEFAULT_ON is not set -CONFIG_CC_HAS_ZERO_CALL_USED_REGS=y -# CONFIG_ZERO_CALL_USED_REGS is not set -# end of Memory initialization - -CONFIG_RANDSTRUCT_NONE=y -# CONFIG_RANDSTRUCT_FULL is not set -# CONFIG_RANDSTRUCT_PERFORMANCE is not set -# end of Kernel hardening options -# end of Security options - -CONFIG_XOR_BLOCKS=m -CONFIG_CRYPTO=y - -# -# Crypto core or helper -# -CONFIG_CRYPTO_ALGAPI=y -CONFIG_CRYPTO_ALGAPI2=y -CONFIG_CRYPTO_AEAD=y -CONFIG_CRYPTO_AEAD2=y -CONFIG_CRYPTO_SIG2=y -CONFIG_CRYPTO_SKCIPHER=y -CONFIG_CRYPTO_SKCIPHER2=y -CONFIG_CRYPTO_HASH=y -CONFIG_CRYPTO_HASH2=y -CONFIG_CRYPTO_RNG=m -CONFIG_CRYPTO_RNG2=y -CONFIG_CRYPTO_RNG_DEFAULT=m -CONFIG_CRYPTO_AKCIPHER2=y -CONFIG_CRYPTO_AKCIPHER=y -CONFIG_CRYPTO_KPP2=y -CONFIG_CRYPTO_ACOMP2=y -CONFIG_CRYPTO_MANAGER=y -CONFIG_CRYPTO_MANAGER2=y -# CONFIG_CRYPTO_USER is not set -CONFIG_CRYPTO_MANAGER_DISABLE_TESTS=y -CONFIG_CRYPTO_NULL=m -CONFIG_CRYPTO_NULL2=m -# CONFIG_CRYPTO_PCRYPT is not set -# CONFIG_CRYPTO_CRYPTD is not set -CONFIG_CRYPTO_AUTHENC=m -# CONFIG_CRYPTO_TEST is not set -CONFIG_CRYPTO_ENGINE=y -# end of Crypto core or helper - -# -# Public-key cryptography -# -CONFIG_CRYPTO_RSA=y -# CONFIG_CRYPTO_DH is not set -# CONFIG_CRYPTO_ECDH is not set -# CONFIG_CRYPTO_ECDSA is not set -# CONFIG_CRYPTO_ECRDSA is not set -# CONFIG_CRYPTO_SM2 is not set -# CONFIG_CRYPTO_CURVE25519 is not set -# end of Public-key cryptography - -# -# Block ciphers -# -CONFIG_CRYPTO_AES=m -# CONFIG_CRYPTO_AES_TI is not set -# CONFIG_CRYPTO_ANUBIS is not set -# CONFIG_CRYPTO_ARIA is not set -# CONFIG_CRYPTO_BLOWFISH is not set -# CONFIG_CRYPTO_CAMELLIA is not set -# CONFIG_CRYPTO_CAST5 is not set -# CONFIG_CRYPTO_CAST6 is not set -# CONFIG_CRYPTO_DES is not set -# CONFIG_CRYPTO_FCRYPT is not set -# CONFIG_CRYPTO_KHAZAD is not set -# CONFIG_CRYPTO_SEED is not set -# CONFIG_CRYPTO_SERPENT is not set -# CONFIG_CRYPTO_SM4_GENERIC is not set -# CONFIG_CRYPTO_TEA is not set -# CONFIG_CRYPTO_TWOFISH is not set -# end of Block ciphers - -# -# Length-preserving ciphers and modes -# -# CONFIG_CRYPTO_ADIANTUM is not set -# CONFIG_CRYPTO_ARC4 is not set -# CONFIG_CRYPTO_CHACHA20 is not set -CONFIG_CRYPTO_CBC=m -# CONFIG_CRYPTO_CFB is not set -CONFIG_CRYPTO_CTR=m -# CONFIG_CRYPTO_CTS is not set -# CONFIG_CRYPTO_ECB is not set -# CONFIG_CRYPTO_HCTR2 is not set -# CONFIG_CRYPTO_KEYWRAP is not set -# CONFIG_CRYPTO_LRW is not set -# CONFIG_CRYPTO_OFB is not set -# CONFIG_CRYPTO_PCBC is not set -# CONFIG_CRYPTO_XTS is not set -# end of Length-preserving ciphers and modes - -# -# AEAD (authenticated encryption with associated data) ciphers -# -# CONFIG_CRYPTO_AEGIS128 is not set -# CONFIG_CRYPTO_CHACHA20POLY1305 is not set -# CONFIG_CRYPTO_CCM is not set -CONFIG_CRYPTO_GCM=m -CONFIG_CRYPTO_GENIV=m -CONFIG_CRYPTO_SEQIV=m -CONFIG_CRYPTO_ECHAINIV=m -# CONFIG_CRYPTO_ESSIV is not set -# end of AEAD (authenticated encryption with associated data) ciphers - -# -# Hashes, digests, and MACs -# -CONFIG_CRYPTO_BLAKE2B=m -# CONFIG_CRYPTO_CMAC is not set -CONFIG_CRYPTO_GHASH=m -CONFIG_CRYPTO_HMAC=m -# CONFIG_CRYPTO_MD4 is not set -# CONFIG_CRYPTO_MD5 is not set -# CONFIG_CRYPTO_MICHAEL_MIC is not set -# CONFIG_CRYPTO_POLY1305 is not set -# CONFIG_CRYPTO_RMD160 is not set -CONFIG_CRYPTO_SHA1=y -CONFIG_CRYPTO_SHA256=m -CONFIG_CRYPTO_SHA512=m -CONFIG_CRYPTO_SHA3=m -# CONFIG_CRYPTO_SM3_GENERIC is not set -# CONFIG_CRYPTO_STREEBOG is not set -# CONFIG_CRYPTO_VMAC is not set -# CONFIG_CRYPTO_WP512 is not set -# CONFIG_CRYPTO_XCBC is not set -CONFIG_CRYPTO_XXHASH=m -# end of Hashes, digests, and MACs - -# -# CRCs (cyclic redundancy checks) -# -CONFIG_CRYPTO_CRC32C=y -# CONFIG_CRYPTO_CRC32 is not set -# CONFIG_CRYPTO_CRCT10DIF is not set -# end of CRCs (cyclic redundancy checks) - -# -# Compression -# -# CONFIG_CRYPTO_DEFLATE is not set -# CONFIG_CRYPTO_LZO is not set -# CONFIG_CRYPTO_842 is not set -# CONFIG_CRYPTO_LZ4 is not set -# CONFIG_CRYPTO_LZ4HC is not set -# CONFIG_CRYPTO_ZSTD is not set -# end of Compression - -# -# Random number generation -# -# CONFIG_CRYPTO_ANSI_CPRNG is not set -CONFIG_CRYPTO_DRBG_MENU=m -CONFIG_CRYPTO_DRBG_HMAC=y -# CONFIG_CRYPTO_DRBG_HASH is not set -# CONFIG_CRYPTO_DRBG_CTR is not set -CONFIG_CRYPTO_DRBG=m -CONFIG_CRYPTO_JITTERENTROPY=m -# CONFIG_CRYPTO_JITTERENTROPY_TESTINTERFACE is not set -# end of Random number generation - -# -# Userspace interface -# -CONFIG_CRYPTO_USER_API=y -CONFIG_CRYPTO_USER_API_HASH=y -# CONFIG_CRYPTO_USER_API_SKCIPHER is not set -# CONFIG_CRYPTO_USER_API_RNG is not set -# CONFIG_CRYPTO_USER_API_AEAD is not set -CONFIG_CRYPTO_USER_API_ENABLE_OBSOLETE=y -# end of Userspace interface - -CONFIG_CRYPTO_HW=y -CONFIG_CRYPTO_DEV_ALLWINNER=y -# CONFIG_CRYPTO_DEV_SUN4I_SS is not set -# CONFIG_CRYPTO_DEV_SUN8I_CE is not set -# CONFIG_CRYPTO_DEV_SUN8I_SS is not set -# CONFIG_CRYPTO_DEV_ATMEL_ECC is not set -# CONFIG_CRYPTO_DEV_ATMEL_SHA204A is not set -# CONFIG_CRYPTO_DEV_NITROX_CNN55XX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCC is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXX is not set -# CONFIG_CRYPTO_DEV_QAT_C62X is not set -# CONFIG_CRYPTO_DEV_QAT_4XXX is not set -# CONFIG_CRYPTO_DEV_QAT_DH895xCCVF is not set -# CONFIG_CRYPTO_DEV_QAT_C3XXXVF is not set -# CONFIG_CRYPTO_DEV_QAT_C62XVF is not set -CONFIG_CRYPTO_DEV_VIRTIO=y -# CONFIG_CRYPTO_DEV_SAFEXCEL is not set -# CONFIG_CRYPTO_DEV_CCREE is not set -# CONFIG_CRYPTO_DEV_AMLOGIC_GXL is not set -# CONFIG_CRYPTO_DEV_JH7110 is not set -# CONFIG_ASYMMETRIC_KEY_TYPE is not set - -# -# Certificates for signature checking -# -# CONFIG_SYSTEM_BLACKLIST_KEYRING is not set -# end of Certificates for signature checking - -CONFIG_BINARY_PRINTF=y - -# -# Library routines -# -CONFIG_RAID6_PQ=m -CONFIG_RAID6_PQ_BENCHMARK=y -CONFIG_LINEAR_RANGES=y -# CONFIG_PACKING is not set -CONFIG_BITREVERSE=y -CONFIG_GENERIC_STRNCPY_FROM_USER=y -CONFIG_GENERIC_STRNLEN_USER=y -CONFIG_GENERIC_NET_UTILS=y -# CONFIG_CORDIC is not set -# CONFIG_PRIME_NUMBERS is not set -CONFIG_RATIONAL=y -CONFIG_GENERIC_PCI_IOMAP=y - -# -# Crypto library routines -# -CONFIG_CRYPTO_LIB_UTILS=y -CONFIG_CRYPTO_LIB_AES=m -CONFIG_CRYPTO_LIB_GF128MUL=m -CONFIG_CRYPTO_LIB_BLAKE2S_GENERIC=y -# CONFIG_CRYPTO_LIB_CHACHA is not set -# CONFIG_CRYPTO_LIB_CURVE25519 is not set -CONFIG_CRYPTO_LIB_POLY1305_RSIZE=1 -# CONFIG_CRYPTO_LIB_POLY1305 is not set -# CONFIG_CRYPTO_LIB_CHACHA20POLY1305 is not set -CONFIG_CRYPTO_LIB_SHA1=y -CONFIG_CRYPTO_LIB_SHA256=m -# end of Crypto library routines - -CONFIG_CRC_CCITT=m -CONFIG_CRC16=y -# CONFIG_CRC_T10DIF is not set -# CONFIG_CRC64_ROCKSOFT is not set -CONFIG_CRC_ITU_T=y -CONFIG_CRC32=y -# CONFIG_CRC32_SELFTEST is not set -CONFIG_CRC32_SLICEBY8=y -# CONFIG_CRC32_SLICEBY4 is not set -# CONFIG_CRC32_SARWATE is not set -# CONFIG_CRC32_BIT is not set -# CONFIG_CRC64 is not set -# CONFIG_CRC4 is not set -CONFIG_CRC7=y -CONFIG_LIBCRC32C=m -# CONFIG_CRC8 is not set -CONFIG_XXHASH=y -CONFIG_AUDIT_GENERIC=y -# CONFIG_RANDOM32_SELFTEST is not set -CONFIG_ZLIB_INFLATE=y -CONFIG_ZLIB_DEFLATE=m -CONFIG_LZO_COMPRESS=m -CONFIG_LZO_DECOMPRESS=y -CONFIG_LZ4_DECOMPRESS=y -CONFIG_ZSTD_COMMON=y -CONFIG_ZSTD_COMPRESS=y -CONFIG_ZSTD_DECOMPRESS=y -CONFIG_XZ_DEC=y -CONFIG_XZ_DEC_X86=y -CONFIG_XZ_DEC_POWERPC=y -CONFIG_XZ_DEC_IA64=y -CONFIG_XZ_DEC_ARM=y -CONFIG_XZ_DEC_ARMTHUMB=y -CONFIG_XZ_DEC_SPARC=y -# CONFIG_XZ_DEC_MICROLZMA is not set -CONFIG_XZ_DEC_BCJ=y -# CONFIG_XZ_DEC_TEST is not set -CONFIG_DECOMPRESS_GZIP=y -CONFIG_DECOMPRESS_BZIP2=y -CONFIG_DECOMPRESS_LZMA=y -CONFIG_DECOMPRESS_XZ=y -CONFIG_DECOMPRESS_LZO=y -CONFIG_DECOMPRESS_LZ4=y -CONFIG_DECOMPRESS_ZSTD=y -CONFIG_GENERIC_ALLOCATOR=y -CONFIG_INTERVAL_TREE=y -CONFIG_ASSOCIATIVE_ARRAY=y -CONFIG_HAS_IOMEM=y -CONFIG_HAS_IOPORT=y -CONFIG_HAS_IOPORT_MAP=y -CONFIG_HAS_DMA=y -CONFIG_NEED_DMA_MAP_STATE=y -CONFIG_ARCH_DMA_ADDR_T_64BIT=y -CONFIG_DMA_DECLARE_COHERENT=y -CONFIG_ARCH_HAS_SETUP_DMA_OPS=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_DEVICE=y -CONFIG_ARCH_HAS_SYNC_DMA_FOR_CPU=y -CONFIG_ARCH_HAS_DMA_PREP_COHERENT=y -CONFIG_ARCH_DMA_DEFAULT_COHERENT=y -CONFIG_SWIOTLB=y -# CONFIG_DMA_RESTRICTED_POOL is not set -CONFIG_DMA_NONCOHERENT_MMAP=y -CONFIG_DMA_COHERENT_POOL=y -CONFIG_DMA_DIRECT_REMAP=y -# CONFIG_DMA_API_DEBUG is not set -# CONFIG_DMA_MAP_BENCHMARK is not set -CONFIG_SGL_ALLOC=y -# CONFIG_CPUMASK_OFFSTACK is not set -# CONFIG_FORCE_NR_CPUS is not set -CONFIG_CPU_RMAP=y -CONFIG_DQL=y -CONFIG_GLOB=y -# CONFIG_GLOB_SELFTEST is not set -CONFIG_NLATTR=y -CONFIG_CLZ_TAB=y -# CONFIG_IRQ_POLL is not set -CONFIG_MPILIB=y -CONFIG_LIBFDT=y -CONFIG_OID_REGISTRY=y -CONFIG_UCS2_STRING=y -CONFIG_HAVE_GENERIC_VDSO=y -CONFIG_GENERIC_GETTIMEOFDAY=y -CONFIG_GENERIC_VDSO_TIME_NS=y -CONFIG_FONT_SUPPORT=y -# CONFIG_FONTS is not set -CONFIG_FONT_8x8=y -CONFIG_FONT_8x16=y -CONFIG_SG_POOL=y -CONFIG_ARCH_HAS_PMEM_API=y -CONFIG_MEMREGION=y -CONFIG_ARCH_STACKWALK=y -CONFIG_STACKDEPOT=y -CONFIG_SBITMAP=y -# end of Library routines - -CONFIG_GENERIC_IOREMAP=y -CONFIG_GENERIC_LIB_DEVMEM_IS_ALLOWED=y - -# -# Kernel hacking -# - -# -# printk and dmesg options -# -CONFIG_PRINTK_TIME=y -# CONFIG_PRINTK_CALLER is not set -# CONFIG_STACKTRACE_BUILD_ID is not set -CONFIG_CONSOLE_LOGLEVEL_DEFAULT=7 -CONFIG_CONSOLE_LOGLEVEL_QUIET=4 -CONFIG_MESSAGE_LOGLEVEL_DEFAULT=4 -# CONFIG_BOOT_PRINTK_DELAY is not set -# CONFIG_DYNAMIC_DEBUG is not set -# CONFIG_DYNAMIC_DEBUG_CORE is not set -CONFIG_SYMBOLIC_ERRNAME=y -CONFIG_DEBUG_BUGVERBOSE=y -# end of printk and dmesg options - -CONFIG_DEBUG_KERNEL=y -CONFIG_DEBUG_MISC=y - -# -# Compile-time checks and compiler options -# -CONFIG_DEBUG_INFO_NONE=y -# CONFIG_DEBUG_INFO_DWARF_TOOLCHAIN_DEFAULT is not set -# CONFIG_DEBUG_INFO_DWARF4 is not set -# CONFIG_DEBUG_INFO_DWARF5 is not set -CONFIG_FRAME_WARN=2048 -# CONFIG_STRIP_ASM_SYMS is not set -# CONFIG_READABLE_ASM is not set -# CONFIG_HEADERS_INSTALL is not set -# CONFIG_DEBUG_SECTION_MISMATCH is not set -CONFIG_SECTION_MISMATCH_WARN_ONLY=y -CONFIG_ARCH_WANT_FRAME_POINTERS=y -CONFIG_FRAME_POINTER=y -# CONFIG_VMLINUX_MAP is not set -# CONFIG_DEBUG_FORCE_WEAK_PER_CPU is not set -# end of Compile-time checks and compiler options - -# -# Generic Kernel Debugging Instruments -# -# CONFIG_MAGIC_SYSRQ is not set -CONFIG_DEBUG_FS=y -CONFIG_DEBUG_FS_ALLOW_ALL=y -# CONFIG_DEBUG_FS_DISALLOW_MOUNT is not set -# CONFIG_DEBUG_FS_ALLOW_NONE is not set -CONFIG_HAVE_ARCH_KGDB=y -CONFIG_HAVE_ARCH_KGDB_QXFER_PKT=y -# CONFIG_KGDB is not set -CONFIG_ARCH_HAS_UBSAN_SANITIZE_ALL=y -# CONFIG_UBSAN is not set -CONFIG_HAVE_KCSAN_COMPILER=y -# end of Generic Kernel Debugging Instruments - -# -# Networking Debugging -# -# CONFIG_NET_DEV_REFCNT_TRACKER is not set -# CONFIG_NET_NS_REFCNT_TRACKER is not set -# CONFIG_DEBUG_NET is not set -# end of Networking Debugging - -# -# Memory Debugging -# -# CONFIG_PAGE_EXTENSION is not set -CONFIG_DEBUG_PAGEALLOC=y -# CONFIG_DEBUG_PAGEALLOC_ENABLE_DEFAULT is not set -CONFIG_SLUB_DEBUG=y -# CONFIG_SLUB_DEBUG_ON is not set -# CONFIG_PAGE_OWNER is not set -# CONFIG_PAGE_POISONING is not set -# CONFIG_DEBUG_RODATA_TEST is not set -CONFIG_ARCH_HAS_DEBUG_WX=y -# CONFIG_DEBUG_WX is not set -CONFIG_GENERIC_PTDUMP=y -# CONFIG_PTDUMP_DEBUGFS is not set -CONFIG_HAVE_DEBUG_KMEMLEAK=y -# CONFIG_DEBUG_KMEMLEAK is not set -# CONFIG_PER_VMA_LOCK_STATS is not set -# CONFIG_DEBUG_OBJECTS is not set -# CONFIG_SHRINKER_DEBUG is not set -# CONFIG_DEBUG_STACK_USAGE is not set -CONFIG_SCHED_STACK_END_CHECK=y -CONFIG_ARCH_HAS_DEBUG_VM_PGTABLE=y -CONFIG_DEBUG_VM_IRQSOFF=y -CONFIG_DEBUG_VM=y -# CONFIG_DEBUG_VM_MAPLE_TREE is not set -# CONFIG_DEBUG_VM_RB is not set -CONFIG_DEBUG_VM_PGFLAGS=y -CONFIG_DEBUG_VM_PGTABLE=y -CONFIG_ARCH_HAS_DEBUG_VIRTUAL=y -# CONFIG_DEBUG_VIRTUAL is not set -CONFIG_DEBUG_MEMORY_INIT=y -CONFIG_DEBUG_PER_CPU_MAPS=y -CONFIG_HAVE_ARCH_KASAN=y -CONFIG_HAVE_ARCH_KASAN_VMALLOC=y -CONFIG_CC_HAS_KASAN_GENERIC=y -CONFIG_CC_HAS_WORKING_NOSANITIZE_ADDRESS=y -# CONFIG_KASAN is not set -CONFIG_HAVE_ARCH_KFENCE=y -# CONFIG_KFENCE is not set -# end of Memory Debugging - -# CONFIG_DEBUG_SHIRQ is not set - -# -# Debug Oops, Lockups and Hangs -# -# CONFIG_PANIC_ON_OOPS is not set -CONFIG_PANIC_ON_OOPS_VALUE=0 -CONFIG_PANIC_TIMEOUT=0 -CONFIG_LOCKUP_DETECTOR=y -CONFIG_SOFTLOCKUP_DETECTOR=y -# CONFIG_BOOTPARAM_SOFTLOCKUP_PANIC is not set -CONFIG_HAVE_HARDLOCKUP_DETECTOR_BUDDY=y -# CONFIG_HARDLOCKUP_DETECTOR is not set -CONFIG_DETECT_HUNG_TASK=y -CONFIG_DEFAULT_HUNG_TASK_TIMEOUT=120 -# CONFIG_BOOTPARAM_HUNG_TASK_PANIC is not set -CONFIG_WQ_WATCHDOG=y -# CONFIG_WQ_CPU_INTENSIVE_REPORT is not set -# CONFIG_TEST_LOCKUP is not set -# end of Debug Oops, Lockups and Hangs - -# -# Scheduler Debugging -# -CONFIG_SCHED_DEBUG=y -# CONFIG_SCHEDSTATS is not set -# end of Scheduler Debugging - -CONFIG_DEBUG_TIMEKEEPING=y - -# -# Lock Debugging (spinlocks, mutexes, etc...) -# -CONFIG_LOCK_DEBUGGING_SUPPORT=y -# CONFIG_PROVE_LOCKING is not set -# CONFIG_LOCK_STAT is not set -CONFIG_DEBUG_RT_MUTEXES=y -CONFIG_DEBUG_SPINLOCK=y -CONFIG_DEBUG_MUTEXES=y -# CONFIG_DEBUG_WW_MUTEX_SLOWPATH is not set -CONFIG_DEBUG_RWSEMS=y -# CONFIG_DEBUG_LOCK_ALLOC is not set -CONFIG_DEBUG_ATOMIC_SLEEP=y -# CONFIG_DEBUG_LOCKING_API_SELFTESTS is not set -# CONFIG_LOCK_TORTURE_TEST is not set -# CONFIG_WW_MUTEX_SELFTEST is not set -# CONFIG_SCF_TORTURE_TEST is not set -# CONFIG_CSD_LOCK_WAIT_DEBUG is not set -# end of Lock Debugging (spinlocks, mutexes, etc...) - -# CONFIG_DEBUG_IRQFLAGS is not set -CONFIG_STACKTRACE=y -# CONFIG_WARN_ALL_UNSEEDED_RANDOM is not set -# CONFIG_DEBUG_KOBJECT is not set - -# -# Debug kernel data structures -# -CONFIG_DEBUG_LIST=y -CONFIG_DEBUG_PLIST=y -CONFIG_DEBUG_SG=y -# CONFIG_DEBUG_NOTIFIERS is not set -# CONFIG_BUG_ON_DATA_CORRUPTION is not set -# CONFIG_DEBUG_MAPLE_TREE is not set -# end of Debug kernel data structures - -# CONFIG_DEBUG_CREDENTIALS is not set - -# -# RCU Debugging -# -# CONFIG_RCU_SCALE_TEST is not set -# CONFIG_RCU_TORTURE_TEST is not set -# CONFIG_RCU_REF_SCALE_TEST is not set -CONFIG_RCU_CPU_STALL_TIMEOUT=21 -CONFIG_RCU_EXP_CPU_STALL_TIMEOUT=0 -# CONFIG_RCU_CPU_STALL_CPUTIME is not set -# CONFIG_RCU_TRACE is not set -CONFIG_RCU_EQS_DEBUG=y -# end of RCU Debugging - -# CONFIG_DEBUG_WQ_FORCE_RR_CPU is not set -# CONFIG_CPU_HOTPLUG_STATE_CONTROL is not set -# CONFIG_LATENCYTOP is not set -CONFIG_HAVE_RETHOOK=y -CONFIG_HAVE_FUNCTION_TRACER=y -CONFIG_HAVE_FUNCTION_GRAPH_TRACER=y -CONFIG_HAVE_FUNCTION_GRAPH_RETVAL=y -CONFIG_HAVE_DYNAMIC_FTRACE=y -CONFIG_HAVE_DYNAMIC_FTRACE_WITH_REGS=y -CONFIG_HAVE_FTRACE_MCOUNT_RECORD=y -CONFIG_HAVE_SYSCALL_TRACEPOINTS=y -CONFIG_TRACING_SUPPORT=y -# CONFIG_FTRACE is not set -# CONFIG_SAMPLES is not set -# CONFIG_STRICT_DEVMEM is not set - -# -# riscv Debugging -# -# end of riscv Debugging - -# -# Kernel Testing and Coverage -# -# CONFIG_KUNIT is not set -# CONFIG_NOTIFIER_ERROR_INJECTION is not set -# CONFIG_FAULT_INJECTION is not set -CONFIG_ARCH_HAS_KCOV=y -CONFIG_CC_HAS_SANCOV_TRACE_PC=y -# CONFIG_KCOV is not set -# CONFIG_RUNTIME_TESTING_MENU is not set -CONFIG_ARCH_USE_MEMTEST=y -CONFIG_MEMTEST=y -# end of Kernel Testing and Coverage - -# -# Rust hacking -# -# end of Rust hacking -# end of Kernel hacking diff --git a/patches/linux/mainline/dts/mpfs-beaglev-fire-fabric.dtsi b/patches/linux/mainline/dts/mpfs-beaglev-fire-fabric.dtsi deleted file mode 100644 index 1069134..0000000 --- a/patches/linux/mainline/dts/mpfs-beaglev-fire-fabric.dtsi +++ /dev/null @@ -1,71 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/ { - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs-icicle-kit", - "microchip,mpfs"; - - core_pwm0: pwm@40000000 { - compatible = "microchip,corepwm-rtl-v4"; - reg = <0x0 0x40000000 0x0 0xF0>; - microchip,sync-update-mask = /bits/ 32 <0>; - #pwm-cells = <3>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - status = "disabled"; - }; - - i2c2: i2c@40000200 { - compatible = "microchip,corei2c-rtl-v7"; - reg = <0x0 0x40000200 0x0 0x100>; - #address-cells = <1>; - #size-cells = <0>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT3>; - interrupt-parent = <&plic>; - interrupts = <122>; - clock-frequency = <100000>; - status = "disabled"; - }; - - pcie: pcie@3000000000 { - compatible = "microchip,pcie-host-1.0"; - #address-cells = <0x3>; - #interrupt-cells = <0x1>; - #size-cells = <0x2>; - device_type = "pci"; - reg = <0x30 0x0 0x0 0x8000000>, <0x0 0x43000000 0x0 0x10000>; - reg-names = "cfg", "apb"; - bus-range = <0x0 0x7f>; - interrupt-parent = <&plic>; - interrupts = <119>; - interrupt-map = <0 0 0 1 &pcie_intc 0>, - <0 0 0 2 &pcie_intc 1>, - <0 0 0 3 &pcie_intc 2>, - <0 0 0 4 &pcie_intc 3>; - interrupt-map-mask = <0 0 0 7>; - clocks = <&ccc_nw CLK_CCC_PLL0_OUT1>, <&ccc_nw CLK_CCC_PLL0_OUT3>; - clock-names = "fic1", "fic3"; - ranges = <0x3000000 0x0 0x8000000 0x30 0x8000000 0x0 0x80000000>; - dma-ranges = <0x02000000 0x0 0x00000000 0x0 0x00000000 0x1 0x00000000>; - msi-parent = <&pcie>; - msi-controller; - status = "disabled"; - pcie_intc: interrupt-controller { - #address-cells = <0>; - #interrupt-cells = <1>; - interrupt-controller; - }; - }; - - refclk_ccc: cccrefclk { - compatible = "fixed-clock"; - #clock-cells = <0>; - }; -}; - -&ccc_nw { - clocks = <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, <&refclk_ccc>, - <&refclk_ccc>, <&refclk_ccc>; - clock-names = "pll0_ref0", "pll0_ref1", "pll1_ref0", "pll1_ref1", - "dll0_ref", "dll1_ref"; - status = "okay"; -}; diff --git a/patches/linux/mainline/dts/mpfs-beaglev-fire.dts b/patches/linux/mainline/dts/mpfs-beaglev-fire.dts deleted file mode 100644 index c811d50..0000000 --- a/patches/linux/mainline/dts/mpfs-beaglev-fire.dts +++ /dev/null @@ -1,323 +0,0 @@ -// SPDX-License-Identifier: (GPL-2.0 OR MIT) -/* Copyright (c) 2020-2021 Microchip Technology Inc */ - -/dts-v1/; - -#include "mpfs.dtsi" -#include "mpfs-beaglev-fire-fabric.dtsi" -#include -#include - -/* Clock frequency (in Hz) of the rtcclk */ -#define RTCCLK_FREQ 1000000 - -/ { - #address-cells = <2>; - #size-cells = <2>; - model = "BeagleBoard BeagleV-Fire"; - compatible = "microchip,mpfs-icicle-reference-rtlv2210", "microchip,mpfs"; - - aliases { - mmc0 = &mmc; - ethernet0 = &mac1; - serial0 = &mmuart0; - serial1 = &mmuart1; - serial2 = &mmuart2; - serial3 = &mmuart3; - serial4 = &mmuart4; - }; - - chosen { - stdout-path = "serial0:115200n8"; - }; - - cpus { - timebase-frequency = ; - }; - - ddrc_cache_lo: memory@80000000 { - device_type = "memory"; - reg = <0x0 0x80000000 0x0 0x40000000>; - status = "okay"; - }; - - ddrc_cache_hi: memory@1040000000 { - device_type = "memory"; - reg = <0x10 0x40000000 0x0 0x40000000>; - status = "okay"; - }; - - reserved-memory { - #address-cells = <2>; - #size-cells = <2>; - ranges; - - hss_payload: region@BFC00000 { - reg = <0x0 0xBFC00000 0x0 0x400000>; - no-map; - }; - }; - - imx219_vana: fixedregulator@0 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vana"; - regulator-min-microvolt = <2800000>; - regulator-max-microvolt = <2800000>; - }; - imx219_vdig: fixedregulator@1 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vdig"; - regulator-min-microvolt = <1800000>; - regulator-max-microvolt = <1800000>; - }; - imx219_vddl: fixedregulator@2 { - compatible = "regulator-fixed"; - regulator-name = "imx219_vddl"; - regulator-min-microvolt = <1200000>; - regulator-max-microvolt = <1200000>; - }; - - imx219_clk: camera-clk { - compatible = "fixed-clock"; - #clock-cells = <0>; - clock-frequency = <24000000>; - }; -}; - -&gpio0 { - ngpios=<14>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", "", "", "SD_CARD_CS", "USER_BUTTON"; - status = "okay"; - - sd_card_cs { - gpio-hog; - gpios = <12 12>; - output_high; - line-name = "SD_CARD_CS"; - }; - - user_button { - gpio-hog; - gpios = <13 13>; - input; - line-name = "USER_BUTTON"; - }; -}; - -&gpio1 { - ngpios=<24>; - gpio-line-names = "", "", "", "", "", "", "", "", "", "", - "", "", "", "", "", "", "", "", "", "", - "ADC_IRQn", "", "", "USB_OCn"; - status = "okay"; - - adc_irqn { - gpio-hog; - gpios = <20 20>; - input; - line-name = "ADC_IRQn"; - }; - - user_button { - gpio-hog; - gpios = <23 23>; - input; - line-name = "USB_OCn"; - }; - -}; - -&gpio2 { - interrupts = <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>, - <53>, <53>, <53>, <53>; - gpio-line-names = "P8_PIN3_USER_LED_0", "P8_PIN4_USER_LED_1", "P8_PIN5_USER_LED_2", - "P8_PIN6_USER_LED_3", "P8_PIN7_USER_LED_4", "P8_PIN8_USER_LED_5", - "P8_PIN9_USER_LED_6", "P8_PIN10_USER_LED_7", "P8_PIN11_USER_LED_8", - "P8_PIN12_USER_LED_9", "P8_PIN13_USER_LED_10", "P8_PIN14_USER_LED_11", - "P8_PIN15", "P8_PIN16", "P8_PIN17", "P8_PIN18", "P8_PIN19", - "P8_PIN20", "P8_PIN21", "P8_PIN22", "P8_PIN23", "P8_PIN24", - "P8_PIN25", "P8_PIN26", "P8_PIN27", "P8_PIN28", "P8_PIN29", - "P8_PIN30", - "M2_W_DISABLE1", "M2_W_DISABLE2", - "VIO_ENABLE", "SD_DET"; - status = "okay"; - - vio_enable { - gpio-hog; - gpios = <30 30>; - output_high; - line-name = "VIO_ENABLE"; - }; - - sd_det { - gpio-hog; - gpios = <31 31>; - input; - line-name = "SD_DET"; - }; -}; - -&i2c0 { - status = "okay"; -}; - -&i2c1 { - status = "okay"; - eeprom: eeprom@50 { - compatible = "at,24c32"; - reg = <0x50>; - }; - - imx219: sensor@10 { - compatible = "sony,imx219"; - reg = <0x10>; - clocks = <&imx219_clk>; - VANA-supply = <&imx219_vana>; /* 2.8v */ - VDIG-supply = <&imx219_vdig>; /* 1.8v */ - VDDL-supply = <&imx219_vddl>; /* 1.2v */ - - port { - imx219_0: endpoint { -// remote-endpoint = <&csi1_ep>; - data-lanes = <1 2>; - clock-noncontinuous; - link-frequencies = /bits/ 64 <456000000>; - }; - }; - }; -}; - -&mac0 { - phy-mode = "sgmii"; - phy-handle = <&phy0>; - status = "okay"; - - phy0: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mac1 { - phy-mode = "sgmii"; - phy-handle = <&phy1>; - status = "okay"; - - phy1: ethernet-phy@0 { - reg = <0>; - }; -}; - -&mbox { - status = "okay"; -}; - -//&mmc { -// status = "okay"; -// bus-width = <8>; -// disable-wp; -// cap-mmc-highspeed; -// mmc-ddr-1_8v; -// mmc-hs200-1_8v; -//}; - -&mmc { - //dma-noncoherent; - bus-width = <4>; - disable-wp; - cap-sd-highspeed; - cap-mmc-highspeed; - mmc-ddr-1_8v; - mmc-hs200-1_8v; - sd-uhs-sdr12; - sd-uhs-sdr25; - sd-uhs-sdr50; - sd-uhs-sdr104; - status = "okay"; -}; - - -&mmuart0 { - status = "okay"; -}; - -&mmuart1 { - status = "okay"; -}; - -//&mmuart2 { -// status = "okay"; -//}; - -//&mmuart3 //{ -// statu//s = "okay"; -//};// -// -//&mmuart4 { -// status = "okay"; -//}; - -//&pcie { -// status = "okay"; -//}; - -&qspi { - status = "okay"; - cs-gpios = <&gpio1 17 GPIO_ACTIVE_LOW>, <&gpio0 12 GPIO_ACTIVE_LOW>; - num-cs = <2>; - - - mcp3464: mcp3464@0 { - compatible = "microchip,mcp3464r"; - reg = <0>; /* CE0 */ - spi-cpol; - spi-cpha; - spi-max-frequency = <15000000>; - status = "okay"; - microchip,hw-device-address = <1>; - }; - - mmc-slot@1 { - compatible = "mmc-spi-slot"; - reg = <1>; - gpios = <&gpio2 31 1>; - voltage-ranges = <3300 3300>; - spi-max-frequency = <15000000>; - disable-wp; - }; -}; - -&refclk { - clock-frequency = <125000000>; -}; - -&refclk_ccc { - clock-frequency = <50000000>; -}; - -&rtc { - status = "okay"; -}; - -&spi0 { - status = "okay"; -}; - -&spi1 { - status = "okay"; -}; - -&syscontroller { - status = "okay"; -}; - -&usb { - //dma-noncoherent; - status = "okay"; - dr_mode = "otg"; -};