kernel: cleaning up
- No need to keep old cruft Signed-off-by: Lars Randers <lranders@mail.dk>main
parent
7c93e344b1
commit
dc24ad0b35
@ -1,27 +0,0 @@
|
|||||||
From 8911855f7b07ba7f592f73850e551802ae40601d Mon Sep 17 00:00:00 2001
|
|
||||||
From: vauban353 <vauban353@gmail.com>
|
|
||||||
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
|
|
||||||
|
|
@ -1,371 +0,0 @@
|
|||||||
From 37ff4eff8ff033c48aa73526fec7291127326dcb Mon Sep 17 00:00:00 2001
|
|
||||||
From: vauban353 <vauban353@gmail.com>
|
|
||||||
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 <lewis.hanly@microchip.com>
|
|
||||||
+ *
|
|
||||||
+ */
|
|
||||||
+
|
|
||||||
+#include <linux/bitops.h>
|
|
||||||
+#include <linux/clk.h>
|
|
||||||
+#include <linux/device.h>
|
|
||||||
+#include <linux/errno.h>
|
|
||||||
+#include <linux/gpio/driver.h>
|
|
||||||
+#include <linux/init.h>
|
|
||||||
+#include <linux/irq.h>
|
|
||||||
+#include <linux/irqchip/chained_irq.h>
|
|
||||||
+#include <linux/of.h>
|
|
||||||
+#include <linux/of_irq.h>
|
|
||||||
+#include <linux/mod_devicetable.h>
|
|
||||||
+#include <linux/platform_device.h>
|
|
||||||
+#include <linux/spinlock.h>
|
|
||||||
+
|
|
||||||
+#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
|
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
@ -1,275 +0,0 @@
|
|||||||
From 0eeed461b7b86e3b822984b1c266316ac70ccf69 Mon Sep 17 00:00:00 2001
|
|
||||||
From: vauban353 <vauban353@gmail.com>
|
|
||||||
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
|
|
||||||
|
|
@ -1,45 +0,0 @@
|
|||||||
From 747c6d5984cccf7c3e48c2cdb4dd1d626889096e Mon Sep 17 00:00:00 2001
|
|
||||||
From: vauban353 <vauban353@gmail.com>
|
|
||||||
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
|
|
||||||
|
|
@ -1,66 +0,0 @@
|
|||||||
From e9aea028119afd0858e77989dd1a4ecc21d30dc1 Mon Sep 17 00:00:00 2001
|
|
||||||
From: vauban353 <vauban353@gmail.com>
|
|
||||||
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 <asm/unaligned.h>
|
|
||||||
|
|
||||||
+//<CJ>:
|
|
||||||
+#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;
|
|
||||||
+//<CJ> 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
|
|
||||||
|
|
||||||
+//<CJ>:
|
|
||||||
+#undef CONFIG_HAS_DMA
|
|
||||||
+
|
|
||||||
#include <linux/device.h>
|
|
||||||
#include <linux/dma-direction.h>
|
|
||||||
#include <linux/scatterlist.h>
|
|
||||||
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"
|
|
||||||
|
|
||||||
+//<CJ>:
|
|
||||||
+#undef CONFIG_HAS_DMA
|
|
||||||
+
|
|
||||||
static DEFINE_IDR(spi_master_idr);
|
|
||||||
|
|
||||||
static void spidev_release(struct device *dev)
|
|
||||||
--
|
|
||||||
2.39.2
|
|
||||||
|
|
@ -1,100 +0,0 @@
|
|||||||
From 17558b89548b694599af7d6144426f30fe83e2c7 Mon Sep 17 00:00:00 2001
|
|
||||||
From: Robert Nelson <robertcnelson@gmail.com>
|
|
||||||
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 <robertcnelson@gmail.com>
|
|
||||||
---
|
|
||||||
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%|!G<Piwg%%i72^*uiwOpriUFO5Vk*@FR?{(_bMJez_f7p{
|
|
||||||
zviEb(Ip6c+-uGs<m>lth5V7H5c)=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!<FyIePbBeZqC|g5e>4rvQOZ49gbPUz-b#+(P00k_mmI~ZWC|O}EdBNA
|
|
||||||
zQ-o%+jBAn=T$QZhkyHk6NaeASD#9zNGP<b>G}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-<pQOJjIPPb#?31sb
|
|
||||||
zqrD>D<dd#Hj;>F2uXnMpn82xG0h&eXxmZD29LGk<#mN%Qq?E+L63x0qXHufMm8h;#
|
|
||||||
z6>Fs$rps~MUmn59auPR}Y3AiTZY>w#WVuZ1aa>%k<H3rHU6my6t(4#wl^X7;)NyMy
|
|
||||||
zj+4~{&Qz&~Y92pdtzcuE>K!lP=2`;NwK7iCUA(_eJ=5J4*DIkutOSmM=pO44-PcQE
|
|
||||||
zDR4Akr?+QT%zJRP7`TDFduAOmZ(7WM=?*dfckAYu)&qSrLag0p>{rO2`RaX|d9CB$
|
|
||||||
zw@&ktCxuu#P4Q0<lfLHW2Q;e=7QJsr?4q|7Vb#Ag!d#!NCkC7j9*i>QduDd79*(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$Jvy<V$MyT~(5!--A@_GM-znB(yJ`qW
|
|
||||||
zbU!8XfARH<%$fFfF!|ed+dsIoZ9B7N=lYyZ?wQlqcCIJT=QDGntY^gc#PZSi%w~Ot
|
|
||||||
za~h7*cf0K$>tJ(!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-%l<E5_V(+@!@YAbxef&IVd%!#ooB3RA*7;~Q?fO{XVrO75!n)rF
|
|
||||||
zCd9;|N6l{%)?@zJDSZ#Le!x60JwM`F?^_Z3|7HGu<N5=Cj_2QmHi!8+UhDHbE&nio
|
|
||||||
zXm@Bn+*^(2!S{3_JzJXJoG|rw-6!gw*%96$eZCQ<`9+xCPZq~il=U4{U9V`L&rSE5
|
|
||||||
zJB5eZjOT>YA7y=y>pwjZ*1#IHM|q=rj&P2_r)So|?88DVzD%=)^O`TlwrN(~UWDnc
|
|
||||||
zMfvJ|5mp@>>W6yto0|Rcqqof%edl<DMgJSHY10hsyltJSM+nWw#sa2zvbW>Kf?@WB
|
|
||||||
zww>Z>4X=M(>q8%P{(|_2oG;%c_sEykAy^B~lIA=q#LvZx;y2>BT&@<WJ7EZla2NcT
|
|
||||||
zZAyrvWO-dC<lAbc`U5P2JZyj;kgc2IPEbUjDyV<Lx1gJRPskg|&r|1MSHK^UC)Fp_
|
|
||||||
zQDW5gkI6UH8R*gLb!vesK{wnByGXA~@1^PA7}_H?J^=?loqOMZhu@cg_e?Ee>@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_<d3SQXPO*Y}0;|az=eSustBpse|qMTUI|tbEo`uJC4?LCT5>%Z|`#-
|
|
||||||
z-wm{R{Y20YulK?7c1^^vCh+@?oK<^*S|3+mf$Q}7w&dgBwf&!zXVjFQc}vndn0ZU`
|
|
||||||
zjK2<}<i}@Vc<u~Z@<;N5I-+|rwO%x9Jr}d4F^CrFDc&=>QgROUqL~H#9PE-swNMpc
|
|
||||||
jkn<>J>#Vh%{SRw@IvcW^8c9=jktWSr_Q@6UU$E<czD|wh
|
|
||||||
|
|
||||||
literal 0
|
|
||||||
HcmV?d00001
|
|
||||||
|
|
||||||
diff --git a/firmware/regulatory.db.p7s b/firmware/regulatory.db.p7s
|
|
||||||
new file mode 100644
|
|
||||||
index 0000000000000000000000000000000000000000..9cf3244287f46b9eac8340184eb96ee57708e27c
|
|
||||||
GIT binary patch
|
|
||||||
literal 1182
|
|
||||||
zcmXqLVwuIpsnzDu_MMlJooPW6OSeH2OFI)IqanWmFB@k<n+IbmGYb<VD}w<yLLuXV
|
|
||||||
zCZ-hzO-xG+nizYSI2kte-gjU3^W1Wf7N}v2+(0eDhJptCY|No7%sd>$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;F8<bhezTU
|
|
||||||
zq<y({<o{GzCT2zkM&u9zMgTB`7#Z4`Z+&Vyba#D?i+<bXc%R80JO8nZ?^gV-s_eH)
|
|
||||||
ziAQW_@w&NgHKjKXdxpF3H{L$|%~yxg18zzm7R1h}6khm$$722JJ~sOk+n!`;d@_kq
|
|
||||||
zwl_NPY%Twq^Pwf~#g`ddw{t6nsnpKrT*=oq&pdigF4N7P69HL|B0r0<z1rloHR9i{
|
|
||||||
zi;dw@?>AX=M0{IyM6Wwa{mIf7OHQT7tSL%AoG*M>*R=9_*YmGe6b-ztep`IAGVBw-
|
|
||||||
z!1vk<fs^&!f7E(&wS)?B)%sb>YwQ2f*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<lkAULPXZj#kkFPDe&)vDTJDkht<
|
|
||||||
zXCH_+TxDm=EN8bRGgK$q-oS2Ba``t~*BwhUtJlrB_tw6yqJE{lpo5C4by!P+xb~K-
|
|
||||||
zW?h?hJAQUn+tQx2mF?Cw2GQBky=zK7n<*(a^2r-%SY$2ee*WQF{k#)yrgr=K7s`Gq
|
|
||||||
zdz={m;ACI_y}ldukB<3%o9}jW`~5Bjv27;`n7w|<S<NY$B{nJi+?9jt6IAPD9rT|w
|
|
||||||
zxe9EH-rsRidD2PYaJM6`N-L{3X}ylmxOs8H)sruk`p&d4vnmGeJY&9?<=k?a8?AF@
|
|
||||||
uUq2uHx&QOztIg+Ga$26PIM1C?+wb@FZsq!<DOL&-J9Y2v%KMV}pa}q{6V{FZ
|
|
||||||
|
|
||||||
literal 0
|
|
||||||
HcmV?d00001
|
|
||||||
|
|
||||||
--
|
|
||||||
2.39.2
|
|
||||||
|
|
@ -1,9 +0,0 @@
|
|||||||
# SPDX-License-Identifier: GPL-2.0
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-icicle-kit.dtb
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-icicle-kit-context-a.dtb
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-m100pfsevp.dtb
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-polarberry.dtb
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-video-kit.dtb
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-tysom-m.dtb
|
|
||||||
dtb-$(CONFIG_SOC_MICROCHIP_POLARFIRE) += mpfs-beaglev-fire.dtb
|
|
||||||
obj-$(CONFIG_BUILTIN_DTB) += $(addsuffix .o, $(dtb-y))
|
|
File diff suppressed because it is too large
Load Diff
@ -1,146 +0,0 @@
|
|||||||
// SPDX-License-Identifier: (GPL-2.0 OR MIT)
|
|
||||||
/* Copyright (c) 2020-2021 Microchip Technology Inc */
|
|
||||||
|
|
||||||
#include "dt-bindings/mailbox/miv-ihc.h"
|
|
||||||
|
|
||||||
/ {
|
|
||||||
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>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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 = <IHC_HART1_INT>;
|
|
||||||
microchip,miv-ihc-remote-context-id = <IHC_CONTEXT_B>;
|
|
||||||
#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";
|
|
||||||
};
|
|
@ -1,380 +0,0 @@
|
|||||||
// SPDX-License-Identifier: (GPL-2.0 OR MIT)
|
|
||||||
/* Copyright (c) 2020-2021 Microchip Technology Inc */
|
|
||||||
|
|
||||||
/dts-v1/;
|
|
||||||
|
|
||||||
#include <dt-bindings/gpio/gpio.h>
|
|
||||||
#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 = <RTCCLK_FREQ>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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";
|
|
||||||
};
|
|
@ -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))
|
|
File diff suppressed because it is too large
Load Diff
@ -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;
|
|
||||||
};
|
|
||||||
};
|
|
||||||
};
|
|
@ -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 <dt-bindings/gpio/gpio.h>
|
|
||||||
#include <dt-bindings/leds/common.h>
|
|
||||||
|
|
||||||
/* 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 = <RTCCLK_FREQ>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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";
|
|
||||||
};
|
|
@ -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))
|
|
File diff suppressed because it is too large
Load Diff
@ -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";
|
|
||||||
};
|
|
@ -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 <dt-bindings/gpio/gpio.h>
|
|
||||||
#include <dt-bindings/leds/common.h>
|
|
||||||
|
|
||||||
/* 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 = <RTCCLK_FREQ>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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";
|
|
||||||
};
|
|
@ -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))
|
|
File diff suppressed because it is too large
Load Diff
@ -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";
|
|
||||||
};
|
|
@ -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 <dt-bindings/gpio/gpio.h>
|
|
||||||
#include <dt-bindings/leds/common.h>
|
|
||||||
|
|
||||||
/* 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 = <RTCCLK_FREQ>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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";
|
|
||||||
};
|
|
@ -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))
|
|
File diff suppressed because it is too large
Load Diff
@ -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";
|
|
||||||
};
|
|
@ -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 <dt-bindings/gpio/gpio.h>
|
|
||||||
#include <dt-bindings/leds/common.h>
|
|
||||||
|
|
||||||
/* 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 = <RTCCLK_FREQ>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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";
|
|
||||||
};
|
|
@ -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))
|
|
File diff suppressed because it is too large
Load Diff
@ -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";
|
|
||||||
};
|
|
@ -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 <dt-bindings/gpio/gpio.h>
|
|
||||||
#include <dt-bindings/leds/common.h>
|
|
||||||
|
|
||||||
/* 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 = <RTCCLK_FREQ>;
|
|
||||||
};
|
|
||||||
|
|
||||||
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";
|
|
||||||
};
|
|
Loading…
Reference in New Issue