2018-10-09 18:53:11

by Atish Patra

[permalink] [raw]
Subject: [RFC 0/4] GPIO & PWM support for HiFive Unleashed

This patch series adds GPIO & PWM drivers and DT documentation
for HiFive Unleashed board. The patches are mostly based on
Wesley's patch.

Wesley W. Terpstra (4):
pwm: sifive: Add DT documentation for SiFive PWM Controller.
pwm: sifive: Add a driver for SiFive SoC PWM
gpio: sifive: Add DT documentation for SiFive GPIO.
gpio: sifive: Add GPIO driver for SiFive SoCs

.../devicetree/bindings/gpio/gpio-sifive.txt | 28 ++
.../devicetree/bindings/pwm/pwm-sifive.txt | 32 ++
drivers/gpio/Kconfig | 7 +
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-sifive.c | 326 +++++++++++++++++++++
drivers/pwm/Kconfig | 10 +
drivers/pwm/Makefile | 1 +
drivers/pwm/pwm-sifive.c | 240 +++++++++++++++
8 files changed, 645 insertions(+)
create mode 100644 Documentation/devicetree/bindings/gpio/gpio-sifive.txt
create mode 100644 Documentation/devicetree/bindings/pwm/pwm-sifive.txt
create mode 100644 drivers/gpio/gpio-sifive.c
create mode 100644 drivers/pwm/pwm-sifive.c

--
2.7.4



2018-10-09 18:52:17

by Atish Patra

[permalink] [raw]
Subject: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

From: "Wesley W. Terpstra" <[email protected]>

DT documentation for PWM controller added with updated compatible
string.

Signed-off-by: Wesley W. Terpstra <[email protected]>
[Atish: Compatible string update]
Signed-off-by: Atish Patra <[email protected]>
---
.../devicetree/bindings/pwm/pwm-sifive.txt | 32 ++++++++++++++++++++++
1 file changed, 32 insertions(+)
create mode 100644 Documentation/devicetree/bindings/pwm/pwm-sifive.txt

diff --git a/Documentation/devicetree/bindings/pwm/pwm-sifive.txt b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
new file mode 100644
index 00000000..532b10fc
--- /dev/null
+++ b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
@@ -0,0 +1,32 @@
+SiFive PWM controller
+
+Unlike most other PWM controllers, the SiFive PWM controller currently only
+supports one period for all channels in the PWM. This is set globally in DTS.
+The period also has significant restrictions on the values it can achieve,
+which the driver rounds to the nearest achievable frequency.
+
+Required properties:
+- compatible: should be one of
+ "sifive,fu540-c000-pwm0","sifive,pwm0".
+ PWM controller is HiFive Unleashed specific chip which warrants a
+ specific compatible string. The second string is kept for backward
+ compatibility until a firmware update with latest compatible string.
+- reg: physical base address and length of the controller's registers
+- clocks: The frequency the controller runs at
+- #pwm-cells: Should be 2.
+ The first cell is the PWM channel number
+ The second cell is the PWM polarity
+- sifive,approx-period: the driver will get as close to this period as it can
+- interrupts: one interrupt per PWM channel (currently unused in the driver)
+
+Examples:
+
+pwm: pwm@10020000 {
+ compatible = "sifive,fu540-c000-pwm0","sifive,pwm0";
+ reg = <0x0 0x10020000 0x0 0x1000>;
+ clocks = <&tlclk>;
+ interrupt-parent = <&plic>;
+ interrupts = <42 43 44 45>;
+ #pwm-cells = <2>;
+ sifive,approx-period = <1000000>;
+};
--
2.7.4


2018-10-09 18:52:20

by Atish Patra

[permalink] [raw]
Subject: [RFC 2/4] pwm: sifive: Add a driver for SiFive SoC PWM

From: "Wesley W. Terpstra" <[email protected]>

Adds a PWM driver for PWM chip present in SiFive's HiFive Unleashed SoC.

Signed-off-by: Wesley W. Terpstra <[email protected]>
[Atish: Various fixes and code cleanup]
Signed-off-by: Atish Patra <[email protected]>
---
drivers/pwm/Kconfig | 10 ++
drivers/pwm/Makefile | 1 +
drivers/pwm/pwm-sifive.c | 240 +++++++++++++++++++++++++++++++++++++++++++++++
3 files changed, 251 insertions(+)
create mode 100644 drivers/pwm/pwm-sifive.c

diff --git a/drivers/pwm/Kconfig b/drivers/pwm/Kconfig
index 504d2527..dd12144d 100644
--- a/drivers/pwm/Kconfig
+++ b/drivers/pwm/Kconfig
@@ -378,6 +378,16 @@ config PWM_SAMSUNG
To compile this driver as a module, choose M here: the module
will be called pwm-samsung.

+config PWM_SIFIVE
+ tristate "SiFive PWM support"
+ depends on OF
+ depends on COMMON_CLK
+ help
+ Generic PWM framework driver for SiFive SoCs.
+
+ To compile this driver as a module, choose M here: the module
+ will be called pwm-sifive.
+
config PWM_SPEAR
tristate "STMicroelectronics SPEAr PWM support"
depends on PLAT_SPEAR
diff --git a/drivers/pwm/Makefile b/drivers/pwm/Makefile
index 9c676a0d..30089ca6 100644
--- a/drivers/pwm/Makefile
+++ b/drivers/pwm/Makefile
@@ -37,6 +37,7 @@ obj-$(CONFIG_PWM_RCAR) += pwm-rcar.o
obj-$(CONFIG_PWM_RENESAS_TPU) += pwm-renesas-tpu.o
obj-$(CONFIG_PWM_ROCKCHIP) += pwm-rockchip.o
obj-$(CONFIG_PWM_SAMSUNG) += pwm-samsung.o
+obj-$(CONFIG_PWM_SIFIVE) += pwm-sifive.o
obj-$(CONFIG_PWM_SPEAR) += pwm-spear.o
obj-$(CONFIG_PWM_STI) += pwm-sti.o
obj-$(CONFIG_PWM_STM32) += pwm-stm32.o
diff --git a/drivers/pwm/pwm-sifive.c b/drivers/pwm/pwm-sifive.c
new file mode 100644
index 00000000..99580025
--- /dev/null
+++ b/drivers/pwm/pwm-sifive.c
@@ -0,0 +1,240 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Copyright (C) 2017 SiFive
+ */
+#include <dt-bindings/pwm/pwm.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/pwm.h>
+#include <linux/slab.h>
+#include <linux/clk.h>
+#include <linux/io.h>
+
+#define MAX_PWM 4
+
+/* Register offsets */
+#define REG_PWMCFG 0x0
+#define REG_PWMCOUNT 0x8
+#define REG_PWMS 0x10
+#define REG_PWMCMP0 0x20
+
+/* PWMCFG fields */
+#define BIT_PWM_SCALE 0
+#define BIT_PWM_STICKY 8
+#define BIT_PWM_ZERO_ZMP 9
+#define BIT_PWM_DEGLITCH 10
+#define BIT_PWM_EN_ALWAYS 12
+#define BIT_PWM_EN_ONCE 13
+#define BIT_PWM0_CENTER 16
+#define BIT_PWM0_GANG 24
+#define BIT_PWM0_IP 28
+
+#define SIZE_PWMCMP 4
+#define MASK_PWM_SCALE 0xf
+
+struct sifive_pwm_device {
+ struct pwm_chip chip;
+ struct notifier_block notifier;
+ struct clk *clk;
+ void __iomem *regs;
+ unsigned int approx_period;
+ unsigned int real_period;
+};
+
+static inline struct sifive_pwm_device *to_sifive_pwm_chip(struct pwm_chip *c)
+{
+ return container_of(c, struct sifive_pwm_device, chip);
+}
+
+static int sifive_pwm_apply(struct pwm_chip *chip, struct pwm_device *dev,
+ struct pwm_state *state)
+{
+ struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
+ unsigned int duty_cycle;
+ u32 frac;
+
+ duty_cycle = state->duty_cycle;
+ if (!state->enabled)
+ duty_cycle = 0;
+ if (state->polarity == PWM_POLARITY_NORMAL)
+ duty_cycle = state->period - duty_cycle;
+
+ frac = ((u64)duty_cycle << 16) / state->period;
+ frac = min(frac, 0xFFFFU);
+
+ iowrite32(frac, pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));
+
+ if (state->enabled) {
+ state->period = pwm->real_period;
+ state->duty_cycle = ((u64)frac * pwm->real_period) >> 16;
+ if (state->polarity == PWM_POLARITY_NORMAL)
+ state->duty_cycle = state->period - state->duty_cycle;
+ }
+
+ return 0;
+}
+
+static void sifive_pwm_get_state(struct pwm_chip *chip, struct pwm_device *dev,
+ struct pwm_state *state)
+{
+ struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
+ unsigned long duty;
+
+ duty = ioread32(pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));
+
+ state->period = pwm->real_period;
+ state->duty_cycle = ((u64)duty * pwm->real_period) >> 16;
+ state->polarity = PWM_POLARITY_INVERSED;
+ state->enabled = duty > 0;
+}
+
+static const struct pwm_ops sifive_pwm_ops = {
+ .get_state = sifive_pwm_get_state,
+ .apply = sifive_pwm_apply,
+ .owner = THIS_MODULE,
+};
+
+static struct pwm_device *sifive_pwm_xlate(struct pwm_chip *chip,
+ const struct of_phandle_args *args)
+{
+ struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
+ struct pwm_device *dev;
+
+ if (args->args[0] >= chip->npwm)
+ return ERR_PTR(-EINVAL);
+
+ dev = pwm_request_from_chip(chip, args->args[0], NULL);
+ if (IS_ERR(dev))
+ return dev;
+
+ /* The period cannot be changed on a per-PWM basis */
+ dev->args.period = pwm->real_period;
+ dev->args.polarity = PWM_POLARITY_NORMAL;
+ if (args->args[1] & PWM_POLARITY_INVERTED)
+ dev->args.polarity = PWM_POLARITY_INVERSED;
+
+ return dev;
+}
+
+static void sifive_pwm_update_clock(struct sifive_pwm_device *pwm,
+ unsigned long rate)
+{
+ /* (1 << (16+scale)) * 10^9/rate = real_period */
+ unsigned long scalePow = (pwm->approx_period * (u64)rate) / 1000000000;
+ int scale = ilog2(scalePow) - 16;
+
+ scale = clamp(scale, 0, 0xf);
+ iowrite32((1 << BIT_PWM_EN_ALWAYS) | (scale << BIT_PWM_SCALE),
+ pwm->regs + REG_PWMCFG);
+
+ pwm->real_period = (1000000000ULL << (16 + scale)) / rate;
+}
+
+static int sifive_pwm_clock_notifier(struct notifier_block *nb,
+ unsigned long event, void *data)
+{
+ struct clk_notifier_data *ndata = data;
+ struct sifive_pwm_device *pwm = container_of(nb,
+ struct sifive_pwm_device,
+ notifier);
+
+ if (event == POST_RATE_CHANGE)
+ sifive_pwm_update_clock(pwm, ndata->new_rate);
+
+ return NOTIFY_OK;
+}
+
+static int sifive_pwm_probe(struct platform_device *pdev)
+{
+ struct device *dev = &pdev->dev;
+ struct device_node *node = pdev->dev.of_node;
+ struct sifive_pwm_device *pwm;
+ struct pwm_chip *chip;
+ struct resource *res;
+ int ret;
+
+ pwm = devm_kzalloc(dev, sizeof(*pwm), GFP_KERNEL);
+ if (!pwm)
+ return -ENOMEM;
+
+ chip = &pwm->chip;
+ chip->dev = dev;
+ chip->ops = &sifive_pwm_ops;
+ chip->of_xlate = sifive_pwm_xlate;
+ chip->of_pwm_n_cells = 2;
+ chip->base = -1;
+
+ ret = of_property_read_u32(node, "sifive,npwm", &chip->npwm);
+ if (ret < 0 || chip->npwm > MAX_PWM)
+ chip->npwm = MAX_PWM;
+
+ ret = of_property_read_u32(node, "sifive,approx-period",
+ &pwm->approx_period);
+ if (ret < 0) {
+ dev_err(dev, "Unable to read sifive,approx-period from DTS\n");
+ return -ENOENT;
+ }
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ pwm->regs = devm_ioremap_resource(dev, res);
+ if (IS_ERR(pwm->regs)) {
+ dev_err(dev, "Unable to map IO resources\n");
+ return PTR_ERR(pwm->regs);
+ }
+
+ pwm->clk = devm_clk_get(dev, NULL);
+ if (IS_ERR(pwm->clk)) {
+ dev_err(dev, "Unable to find controller clock\n");
+ return PTR_ERR(pwm->clk);
+ }
+
+ /* Watch for changes to underlying clock frequency */
+ pwm->notifier.notifier_call = sifive_pwm_clock_notifier;
+ clk_notifier_register(pwm->clk, &pwm->notifier);
+
+ /* Initialize PWM config */
+ sifive_pwm_update_clock(pwm, clk_get_rate(pwm->clk));
+
+ /* No interrupt handler needed yet */
+
+ ret = pwmchip_add(chip);
+ if (ret < 0) {
+ dev_err(dev, "cannot register PWM: %d\n", ret);
+ clk_notifier_unregister(pwm->clk, &pwm->notifier);
+ return ret;
+ }
+
+ platform_set_drvdata(pdev, pwm);
+ dev_info(dev, "SiFive PWM chip registered %d PWMs\n", chip->npwm);
+
+ return 0;
+}
+
+static int sifive_pwm_remove(struct platform_device *dev)
+{
+ struct sifive_pwm_device *pwm = platform_get_drvdata(dev);
+ struct pwm_chip *chip = &pwm->chip;
+
+ clk_notifier_unregister(pwm->clk, &pwm->notifier);
+ return pwmchip_remove(chip);
+}
+
+static const struct of_device_id sifive_pwm_of_match[] = {
+ { .compatible = "sifive,pwm0" },
+ { .compatible = "sifive,fu540-c000-pwm0" },
+ {},
+};
+MODULE_DEVICE_TABLE(of, sifive_pwm_of_match);
+
+static struct platform_driver sifive_pwm_driver = {
+ .probe = sifive_pwm_probe,
+ .remove = sifive_pwm_remove,
+ .driver = {
+ .name = "pwm-sifivem",
+ .of_match_table = of_match_ptr(sifive_pwm_of_match),
+ },
+};
+module_platform_driver(sifive_pwm_driver);
+
+MODULE_DESCRIPTION("SiFive PWM driver");
+MODULE_LICENSE("GPL v2");
--
2.7.4


2018-10-09 18:52:25

by Atish Patra

[permalink] [raw]
Subject: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

From: "Wesley W. Terpstra" <[email protected]>

Adds the GPIO driver for SiFive RISC-V SoCs.

Signed-off-by: Wesley W. Terpstra <[email protected]>
[Atish: Various fixes and code cleanup]
Signed-off-by: Atish Patra <[email protected]>
---
drivers/gpio/Kconfig | 7 +
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-sifive.c | 326 +++++++++++++++++++++++++++++++++++++++++++++
3 files changed, 334 insertions(+)
create mode 100644 drivers/gpio/gpio-sifive.c

diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 4f52c3a8..7755f49e 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -439,6 +439,13 @@ config GPIO_REG
A 32-bit single register GPIO fixed in/out implementation. This
can be used to represent any register as a set of GPIO signals.

+config GPIO_SIFIVE
+ bool "SiFive GPIO support"
+ depends on OF_GPIO
+ select GPIOLIB_IRQCHIP
+ help
+ Say yes here to support the GPIO device on SiFive SoCs.
+
config GPIO_SPEAR_SPICS
bool "ST SPEAr13xx SPI Chip Select as GPIO support"
depends on PLAT_SPEAR
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index c256aff6..244a3696 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -111,6 +111,7 @@ obj-$(CONFIG_GPIO_REG) += gpio-reg.o
obj-$(CONFIG_ARCH_SA1100) += gpio-sa1100.o
obj-$(CONFIG_GPIO_SCH) += gpio-sch.o
obj-$(CONFIG_GPIO_SCH311X) += gpio-sch311x.o
+obj-$(CONFIG_GPIO_SIFIVE) += gpio-sifive.o
obj-$(CONFIG_GPIO_SODAVILLE) += gpio-sodaville.o
obj-$(CONFIG_GPIO_SPEAR_SPICS) += gpio-spear-spics.o
obj-$(CONFIG_GPIO_SPRD) += gpio-sprd.o
diff --git a/drivers/gpio/gpio-sifive.c b/drivers/gpio/gpio-sifive.c
new file mode 100644
index 00000000..5af2b405
--- /dev/null
+++ b/drivers/gpio/gpio-sifive.c
@@ -0,0 +1,326 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Copyright (C) 2017 SiFive
+ */
+#include <linux/bitops.h>
+#include <linux/device.h>
+#include <linux/errno.h>
+#include <linux/of_irq.h>
+#include <linux/gpio/driver.h>
+#include <linux/irqchip/chained_irq.h>
+#include <linux/init.h>
+#include <linux/of.h>
+#include <linux/pinctrl/consumer.h>
+#include <linux/platform_device.h>
+#include <linux/pm.h>
+#include <linux/slab.h>
+#include <linux/spinlock.h>
+
+#define GPIO_INPUT_VAL 0x00
+#define GPIO_INPUT_EN 0x04
+#define GPIO_OUTPUT_EN 0x08
+#define GPIO_OUTPUT_VAL 0x0C
+#define GPIO_RISE_IE 0x18
+#define GPIO_RISE_IP 0x1C
+#define GPIO_FALL_IE 0x20
+#define GPIO_FALL_IP 0x24
+#define GPIO_HIGH_IE 0x28
+#define GPIO_HIGH_IP 0x2C
+#define GPIO_LOW_IE 0x30
+#define GPIO_LOW_IP 0x34
+#define GPIO_OUTPUT_XOR 0x40
+
+#define MAX_GPIO 32
+
+struct sifive_gpio {
+ raw_spinlock_t lock;
+ void __iomem *base;
+ struct gpio_chip gc;
+ unsigned long enabled;
+ unsigned int trigger[MAX_GPIO];
+ unsigned int irq_parent[MAX_GPIO];
+ struct sifive_gpio *self_ptr[MAX_GPIO];
+};
+
+static void sifive_assign_bit(void __iomem *ptr, unsigned int offset, int value)
+{
+ /*
+ * It's frustrating that we are not allowed to use the device atomics
+ * which are GUARANTEED to be supported by this device on RISC-V
+ */
+ u32 bit = BIT(offset), old = ioread32(ptr);
+
+ if (value)
+ iowrite32(old | bit, ptr);
+ else
+ iowrite32(old & ~bit, ptr);
+}
+
+static int sifive_direction_input(struct gpio_chip *gc, unsigned int offset)
+{
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+ unsigned long flags;
+
+ if (offset >= gc->ngpio)
+ return -EINVAL;
+
+ raw_spin_lock_irqsave(&chip->lock, flags);
+ sifive_assign_bit(chip->base + GPIO_OUTPUT_EN, offset, 0);
+ sifive_assign_bit(chip->base + GPIO_INPUT_EN, offset, 1);
+ raw_spin_unlock_irqrestore(&chip->lock, flags);
+
+ return 0;
+}
+
+static int sifive_direction_output(struct gpio_chip *gc, unsigned int offset,
+ int value)
+{
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+ unsigned long flags;
+
+ if (offset >= gc->ngpio)
+ return -EINVAL;
+
+ raw_spin_lock_irqsave(&chip->lock, flags);
+ sifive_assign_bit(chip->base + GPIO_INPUT_EN, offset, 0);
+ sifive_assign_bit(chip->base + GPIO_OUTPUT_VAL, offset, value);
+ sifive_assign_bit(chip->base + GPIO_OUTPUT_EN, offset, 1);
+ raw_spin_unlock_irqrestore(&chip->lock, flags);
+
+ return 0;
+}
+
+static int sifive_get_direction(struct gpio_chip *gc, unsigned int offset)
+{
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+
+ if (offset >= gc->ngpio)
+ return -EINVAL;
+
+ return !(ioread32(chip->base + GPIO_OUTPUT_EN) & BIT(offset));
+}
+
+static int sifive_get_value(struct gpio_chip *gc, unsigned int offset)
+{
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+
+ if (offset >= gc->ngpio)
+ return -EINVAL;
+
+ return !!(ioread32(chip->base + GPIO_INPUT_VAL) & BIT(offset));
+}
+
+static void sifive_set_value(struct gpio_chip *gc, unsigned int offset,
+ int value)
+{
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+ unsigned long flags;
+
+ if (offset >= gc->ngpio)
+ return;
+
+ raw_spin_lock_irqsave(&chip->lock, flags);
+ sifive_assign_bit(chip->base + GPIO_OUTPUT_VAL, offset, value);
+ raw_spin_unlock_irqrestore(&chip->lock, flags);
+}
+
+static void sifive_set_ie(struct sifive_gpio *chip, unsigned int offset)
+{
+ unsigned long flags;
+ unsigned int trigger;
+
+ raw_spin_lock_irqsave(&chip->lock, flags);
+ trigger = (chip->enabled & BIT(offset)) ? chip->trigger[offset] : 0;
+ sifive_assign_bit(chip->base + GPIO_RISE_IE, offset,
+ trigger & IRQ_TYPE_EDGE_RISING);
+ sifive_assign_bit(chip->base + GPIO_FALL_IE, offset,
+ trigger & IRQ_TYPE_EDGE_FALLING);
+ sifive_assign_bit(chip->base + GPIO_HIGH_IE, offset,
+ trigger & IRQ_TYPE_LEVEL_HIGH);
+ sifive_assign_bit(chip->base + GPIO_LOW_IE, offset,
+ trigger & IRQ_TYPE_LEVEL_LOW);
+ raw_spin_unlock_irqrestore(&chip->lock, flags);
+}
+
+static int sifive_irq_set_type(struct irq_data *d, unsigned int trigger)
+{
+ struct gpio_chip *gc = irq_data_get_irq_chip_data(d);
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+ int offset = irqd_to_hwirq(d);
+
+ if (offset < 0 || offset >= gc->ngpio)
+ return -EINVAL;
+
+ chip->trigger[offset] = trigger;
+ sifive_set_ie(chip, offset);
+ return 0;
+}
+
+/* chained_irq_{enter,exit} already mask the parent */
+static void sifive_irq_mask(struct irq_data *d) { }
+static void sifive_irq_unmask(struct irq_data *d) { }
+
+static void sifive_irq_enable(struct irq_data *d)
+{
+ struct gpio_chip *gc = irq_data_get_irq_chip_data(d);
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+ int offset = irqd_to_hwirq(d) % MAX_GPIO; // must not fail
+ u32 bit = BIT(offset);
+
+ /* Switch to input */
+ sifive_direction_input(gc, offset);
+
+ /* Clear any sticky pending interrupts */
+ iowrite32(bit, chip->base + GPIO_RISE_IP);
+ iowrite32(bit, chip->base + GPIO_FALL_IP);
+ iowrite32(bit, chip->base + GPIO_HIGH_IP);
+ iowrite32(bit, chip->base + GPIO_LOW_IP);
+
+ /* Enable interrupts */
+ assign_bit(offset, &chip->enabled, 1);
+ sifive_set_ie(chip, offset);
+}
+
+static void sifive_irq_disable(struct irq_data *d)
+{
+ struct gpio_chip *gc = irq_data_get_irq_chip_data(d);
+ struct sifive_gpio *chip = gpiochip_get_data(gc);
+ int offset = irqd_to_hwirq(d) % MAX_GPIO; // must not fail
+
+ assign_bit(offset, &chip->enabled, 0);
+ sifive_set_ie(chip, offset);
+}
+
+static struct irq_chip sifive_irqchip = {
+ .name = "sifive-gpio",
+ .irq_set_type = sifive_irq_set_type,
+ .irq_mask = sifive_irq_mask,
+ .irq_unmask = sifive_irq_unmask,
+ .irq_enable = sifive_irq_enable,
+ .irq_disable = sifive_irq_disable,
+};
+
+static void sifive_irq_handler(struct irq_desc *desc)
+{
+ struct irq_chip *irqchip = irq_desc_get_chip(desc);
+ struct sifive_gpio **self_ptr = irq_desc_get_handler_data(desc);
+ struct sifive_gpio *chip = *self_ptr;
+ int offset = self_ptr - &chip->self_ptr[0];
+ u32 bit = BIT(offset);
+
+ chained_irq_enter(irqchip, desc);
+
+ /* Re-arm the edge triggers so don't miss the next one */
+ iowrite32(bit, chip->base + GPIO_RISE_IP);
+ iowrite32(bit, chip->base + GPIO_FALL_IP);
+
+ generic_handle_irq(irq_find_mapping(chip->gc.irq.domain, offset));
+
+ /* Re-arm the level triggers after handling to prevent spurious refire */
+ iowrite32(bit, chip->base + GPIO_HIGH_IP);
+ iowrite32(bit, chip->base + GPIO_LOW_IP);
+
+ chained_irq_exit(irqchip, desc);
+}
+
+static int sifive_gpio_probe(struct platform_device *pdev)
+{
+ struct device *dev = &pdev->dev;
+ struct device_node *node = pdev->dev.of_node;
+ struct sifive_gpio *chip;
+ struct resource *res;
+ int gpio, irq, ret, ngpio;
+
+ chip = devm_kzalloc(dev, sizeof(*chip), GFP_KERNEL);
+ if (!chip)
+ return -ENOMEM;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ chip->base = devm_ioremap_resource(dev, res);
+ if (IS_ERR(chip->base)) {
+ dev_err(dev, "failed to allocate device memory\n");
+ return PTR_ERR(chip->base);
+ }
+
+ ngpio = of_irq_count(node);
+ if (ngpio >= MAX_GPIO) {
+ dev_err(dev, "Too many GPIO interrupts (max=%d)\n", MAX_GPIO);
+ return -ENXIO;
+ }
+
+ raw_spin_lock_init(&chip->lock);
+ chip->gc.direction_input = sifive_direction_input;
+ chip->gc.direction_output = sifive_direction_output;
+ chip->gc.get_direction = sifive_get_direction;
+ chip->gc.get = sifive_get_value;
+ chip->gc.set = sifive_set_value;
+ chip->gc.base = -1;
+ chip->gc.ngpio = ngpio;
+ chip->gc.label = dev_name(dev);
+ chip->gc.parent = dev;
+ chip->gc.owner = THIS_MODULE;
+
+ ret = gpiochip_add_data(&chip->gc, chip);
+ if (ret)
+ return ret;
+
+ /* Disable all GPIO interrupts before enabling parent interrupts */
+ iowrite32(0, chip->base + GPIO_RISE_IE);
+ iowrite32(0, chip->base + GPIO_FALL_IE);
+ iowrite32(0, chip->base + GPIO_HIGH_IE);
+ iowrite32(0, chip->base + GPIO_LOW_IE);
+ chip->enabled = 0;
+
+ ret = gpiochip_irqchip_add(&chip->gc, &sifive_irqchip, 0,
+ handle_simple_irq, IRQ_TYPE_NONE);
+ if (ret) {
+ dev_err(dev, "could not add irqchip\n");
+ gpiochip_remove(&chip->gc);
+ return ret;
+ }
+
+ chip->gc.irq.num_parents = ngpio;
+ chip->gc.irq.parents = &chip->irq_parent[0];
+ chip->gc.irq.map = &chip->irq_parent[0];
+
+ for (gpio = 0; gpio < ngpio; ++gpio) {
+ irq = platform_get_irq(pdev, gpio);
+ if (irq < 0) {
+ dev_err(dev, "invalid IRQ\n");
+ gpiochip_remove(&chip->gc);
+ return -ENODEV;
+ }
+
+ chip->irq_parent[gpio] = irq;
+ chip->self_ptr[gpio] = chip;
+ chip->trigger[gpio] = IRQ_TYPE_LEVEL_HIGH;
+ }
+
+ for (gpio = 0; gpio < ngpio; ++gpio) {
+ irq = chip->irq_parent[gpio];
+ irq_set_chained_handler_and_data(irq, sifive_irq_handler,
+ &chip->self_ptr[gpio]);
+ irq_set_parent(irq_find_mapping(chip->gc.irq.domain, gpio),
+ irq);
+ }
+
+ platform_set_drvdata(pdev, chip);
+ dev_info(dev, "SiFive GPIO chip registered %d GPIOs\n", ngpio);
+
+ return 0;
+}
+
+static const struct of_device_id sifive_gpio_match[] = {
+ { .compatible = "sifive,gpio0" },
+ { .compatible = "sifive,fu540-c000-gpio0" },
+ { },
+};
+
+static struct platform_driver sifive_gpio_driver = {
+ .probe = sifive_gpio_probe,
+ .driver = {
+ .name = "sifive_gpio",
+ .of_match_table = of_match_ptr(sifive_gpio_match),
+ },
+};
+builtin_platform_driver(sifive_gpio_driver)
--
2.7.4


2018-10-09 18:52:38

by Atish Patra

[permalink] [raw]
Subject: [RFC 3/4] gpio: sifive: Add DT documentation for SiFive GPIO.

From: "Wesley W. Terpstra" <[email protected]>

DT documentation for GPIO added with updated compatible
string.

Signed-off-by: Wesley W. Terpstra <[email protected]>
[Atish: Compatible string update]
Signed-off-by: Atish Patra <[email protected]>
---
.../devicetree/bindings/gpio/gpio-sifive.txt | 28 ++++++++++++++++++++++
1 file changed, 28 insertions(+)
create mode 100644 Documentation/devicetree/bindings/gpio/gpio-sifive.txt

diff --git a/Documentation/devicetree/bindings/gpio/gpio-sifive.txt b/Documentation/devicetree/bindings/gpio/gpio-sifive.txt
new file mode 100644
index 00000000..781fe4ad
--- /dev/null
+++ b/Documentation/devicetree/bindings/gpio/gpio-sifive.txt
@@ -0,0 +1,28 @@
+SiFive GPIO controller bindings
+
+Required properties:
+- compatible: should be one of
+ "sifive,fu540-c000-gpio0","sifive,gpio0"
+- reg: Physical base address and length of the controller's registers.
+- #gpio-cells : Should be 2
+ - The first cell is the GPIO offset number.
+ - The second cell indicates the polarity of the GPIO
+- gpio-controller : Marks the device node as a GPIO controller.
+- interrupt-controller: Marks the device node as an interrupt controller.
+- #interrupt-cells : Should be 2.
+ - The first cell is the GPIO offset number within the GPIO controller.
+ - The second cell is the edge/level to use for interrupt generation.
+- interrupts: Specify the interrupts, one per GPIO
+
+Example:
+
+gpio: gpio@10060000 {
+ compatible = "sifive,fu540-c000-gpio0","sifive,gpio0";
+ interrupt-parent = <&plic>;
+ interrupts = <7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22>;
+ reg = <0x0 0x10060000 0x0 0x1000>;
+ gpio-controller;
+ #gpio-cells = <2>;
+ interrupt-controller;
+ #interrupt-cells = <2>;
+};
--
2.7.4


2018-10-10 12:36:19

by Linus Walleij

[permalink] [raw]
Subject: Re: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

Hi Atish,

thanks for your patch!

On Tue, Oct 9, 2018 at 8:51 PM Atish Patra <[email protected]> wrote:

> From: "Wesley W. Terpstra" <[email protected]>
>
> Adds the GPIO driver for SiFive RISC-V SoCs.
>
> Signed-off-by: Wesley W. Terpstra <[email protected]>
> [Atish: Various fixes and code cleanup]
> Signed-off-by: Atish Patra <[email protected]>

(...)

> +config GPIO_SIFIVE
> + bool "SiFive GPIO support"
> + depends on OF_GPIO
> + select GPIOLIB_IRQCHIP

I suggest to add
select GPIO_GENERIC as per below.

Maybe select REGMAP_MMIO as well.

> + help
> + Say yes here to support the GPIO device on SiFive SoCs.
> +

> +#include <linux/of_irq.h>
> +#include <linux/irqchip/chained_irq.h>

Do you need these two? I think <linux/gpio/driver.h>
will bring them in for you.

> +#include <linux/pinctrl/consumer.h>

Are you using this?

> +struct sifive_gpio {
> + raw_spinlock_t lock;
> + void __iomem *base;
> + struct gpio_chip gc;
> + unsigned long enabled;

Since max GPIO is 32 why not use an u32 for this?

> + unsigned int trigger[MAX_GPIO];
> + unsigned int irq_parent[MAX_GPIO];
> + struct sifive_gpio *self_ptr[MAX_GPIO];
> +};
> +
> +static void sifive_assign_bit(void __iomem *ptr, unsigned int offset, int value)
> +{
> + /*
> + * It's frustrating that we are not allowed to use the device atomics
> + * which are GUARANTEED to be supported by this device on RISC-V
> + */
> + u32 bit = BIT(offset), old = ioread32(ptr);
> +
> + if (value)
> + iowrite32(old | bit, ptr);
> + else
> + iowrite32(old & ~bit, ptr);
> +}

This looks like a mask and set implementation, you are
essentially reinventing regmap MMIO and the
regmap_update_bits() call. Could you look into
just using regmap MMIO in that case?

If you need examples, look at gpio-mvebu.c that calls
devm_regmap_init_mmio() for example.

> +static int sifive_direction_input(struct gpio_chip *gc, unsigned int offset)
> +static int sifive_direction_output(struct gpio_chip *gc, unsigned int offset,
> +static int sifive_get_direction(struct gpio_chip *gc, unsigned int offset)
> +static int sifive_get_value(struct gpio_chip *gc, unsigned int offset)
> +static void sifive_set_value(struct gpio_chip *gc, unsigned int offset,

These functions look like a typical hardware that can use

GPIOLIB_GENERIC and bgpio_init() to set up the accessors.

See gpio-ftgpio010.c for an example.

As a bonus you will get .get/.set_multiple implemented by
the generic GPIO.

> +static void sifive_irq_enable(struct irq_data *d)
> +static void sifive_irq_disable(struct irq_data *d)
(...)
> +static struct irq_chip sifive_irqchip = {
> + .name = "sifive-gpio",
> + .irq_set_type = sifive_irq_set_type,
> + .irq_mask = sifive_irq_mask,
> + .irq_unmask = sifive_irq_unmask,
> + .irq_enable = sifive_irq_enable,
> + .irq_disable = sifive_irq_disable,

The handling of .irq_enable and .irq_disable has
changed upstream. Please align with the new codebase
as changed by Hans Verkuil:

commit 461c1a7d4733d1dfd5c47b040cf32a5e7eefbc6c
"gpiolib: override irq_enable/disable"
commit 4e9439ddacea06f35acce4d374bf6bd0acf99bc8
"gpiolib: add flag to indicate if the irq is disabled"

You will need to rebase your work on the v4.20-rc1 once it is
out. Right now the changes are on linux-next or my devel
branch.

> + ngpio = of_irq_count(node);
> + if (ngpio >= MAX_GPIO) {
> + dev_err(dev, "Too many GPIO interrupts (max=%d)\n", MAX_GPIO);
> + return -ENXIO;
> + }
(...)
> + for (gpio = 0; gpio < ngpio; ++gpio) {
> + irq = platform_get_irq(pdev, gpio);
> + if (irq < 0) {
> + dev_err(dev, "invalid IRQ\n");
> + gpiochip_remove(&chip->gc);
> + return -ENODEV;
> + }

This is an hierarchical IRQ so it should use an hierarchical
irqdomain.

I am discussing with Thierry to make more generic irq domains
for hierarchical IRQ GPIOs, until then you have to look at
gpio-thunderx.c, gpio-uniphier.c or gpio-xgene-sb.c that all
use hierarchical IRQs.

Yours,
Linus Walleij

2018-10-10 13:02:29

by Andreas Schwab

[permalink] [raw]
Subject: Re: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

On Okt 09 2018, Atish Patra <[email protected]> wrote:

> +static void sifive_set_ie(struct sifive_gpio *chip, unsigned int offset)
> +{
> + unsigned long flags;
> + unsigned int trigger;
> +
> + raw_spin_lock_irqsave(&chip->lock, flags);
> + trigger = (chip->enabled & BIT(offset)) ? chip->trigger[offset] : 0;

This should use test_bit instead.

Andreas.

--
Andreas Schwab, SUSE Labs, [email protected]
GPG Key fingerprint = 0196 BAD8 1CE9 1970 F4BE 1748 E4D4 88E3 0EEA B9D7
"And now for something completely different."

2018-10-10 13:13:00

by Christoph Hellwig

[permalink] [raw]
Subject: Re: [RFC 2/4] pwm: sifive: Add a driver for SiFive SoC PWM

Thanks for getting these drivers submitted upstream!

I don't really know anything about PWM, so just some random nitpicking
below..

> + iowrite32(frac, pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));

* already has a higher precedence than +, so no need for the inner
braces.

> + duty = ioread32(pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));

Same here.

> + /* (1 << (16+scale)) * 10^9/rate = real_period */
unsigned long scalePow = (pwm->approx_period * (u64)rate) / 1000000000;

no camcel case, please.

> + int scale = ilog2(scalePow) - 16;
> +
> + scale = clamp(scale, 0, 0xf);

Why not:

int scale = clamp(ilog2(scale_pow) - 16, 0, 0xf);

> +static int sifive_pwm_clock_notifier(struct notifier_block *nb,
> + unsigned long event, void *data)
> +{
> + struct clk_notifier_data *ndata = data;
> + struct sifive_pwm_device *pwm = container_of(nb,
> + struct sifive_pwm_device,
> + notifier);

I don't think there are any guidlines, but I always prefer to just move
the whole container_of onto a new line:

struct sifive_pwm_device *pwm =
container_of(nb, struct sifive_pwm_device, notifier);

> +static struct platform_driver sifive_pwm_driver = {
> + .probe = sifive_pwm_probe,
> + .remove = sifive_pwm_remove,
> + .driver = {
> + .name = "pwm-sifivem",
> + .of_match_table = of_match_ptr(sifive_pwm_of_match),
> + },
> +};

What about using tabs to align this a little more nicely?

static struct platform_driver sifive_pwm_driver = {
.probe = sifive_pwm_probe,
.remove = sifive_pwm_remove,
.driver = {
.name = "pwm-sifivem",
.of_match_table = of_match_ptr(sifive_pwm_of_match),
},
};

2018-10-10 13:13:53

by Christoph Hellwig

[permalink] [raw]
Subject: Re: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

On Wed, Oct 10, 2018 at 03:01:29PM +0200, Andreas Schwab wrote:
> On Okt 09 2018, Atish Patra <[email protected]> wrote:
>
> > +static void sifive_set_ie(struct sifive_gpio *chip, unsigned int offset)
> > +{
> > + unsigned long flags;
> > + unsigned int trigger;
> > +
> > + raw_spin_lock_irqsave(&chip->lock, flags);
> > + trigger = (chip->enabled & BIT(offset)) ? chip->trigger[offset] : 0;
>
> This should use test_bit instead.

Given that this apparently needs the spinlock for atomciy with more than
just the bitmap test_bit would be rather pointless.

2018-10-10 13:29:34

by Andreas Schwab

[permalink] [raw]
Subject: Re: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

On Okt 10 2018, Christoph Hellwig <[email protected]> wrote:

> On Wed, Oct 10, 2018 at 03:01:29PM +0200, Andreas Schwab wrote:
>> On Okt 09 2018, Atish Patra <[email protected]> wrote:
>>
>> > +static void sifive_set_ie(struct sifive_gpio *chip, unsigned int offset)
>> > +{
>> > + unsigned long flags;
>> > + unsigned int trigger;
>> > +
>> > + raw_spin_lock_irqsave(&chip->lock, flags);
>> > + trigger = (chip->enabled & BIT(offset)) ? chip->trigger[offset] : 0;
>>
>> This should use test_bit instead.
>
> Given that this apparently needs the spinlock for atomciy with more than
> just the bitmap test_bit would be rather pointless.

BIT and test_bit/assign_bit are not compatible.

Andreas.

--
Andreas Schwab, SUSE Labs, [email protected]
GPG Key fingerprint = 0196 BAD8 1CE9 1970 F4BE 1748 E4D4 88E3 0EEA B9D7
"And now for something completely different."

2018-10-10 13:46:24

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 2/4] pwm: sifive: Add a driver for SiFive SoC PWM

On Wed, Oct 10, 2018 at 06:11:29AM -0700, Christoph Hellwig wrote:
[...]
> > +static struct platform_driver sifive_pwm_driver = {
> > + .probe = sifive_pwm_probe,
> > + .remove = sifive_pwm_remove,
> > + .driver = {
> > + .name = "pwm-sifivem",
> > + .of_match_table = of_match_ptr(sifive_pwm_of_match),
> > + },
> > +};
>
> What about using tabs to align this a little more nicely?
>
> static struct platform_driver sifive_pwm_driver = {
> .probe = sifive_pwm_probe,
> .remove = sifive_pwm_remove,
> .driver = {
> .name = "pwm-sifivem",
> .of_match_table = of_match_ptr(sifive_pwm_of_match),
> },
> };

I discourage people from doing that because down the road somebody might
add a field here that's longer than the alignment tabs and then either
it becomes ugly or they either have to realign everything to keep it
pretty. Single spaces around '=' don't have that problem if used
consistently.

Thierry


Attachments:
(No filename) (951.00 B)
signature.asc (849.00 B)
Download all attachments

2018-10-10 13:51:28

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
> From: "Wesley W. Terpstra" <[email protected]>
>
> DT documentation for PWM controller added with updated compatible
> string.
>
> Signed-off-by: Wesley W. Terpstra <[email protected]>
> [Atish: Compatible string update]
> Signed-off-by: Atish Patra <[email protected]>
> ---
> .../devicetree/bindings/pwm/pwm-sifive.txt | 32 ++++++++++++++++++++++
> 1 file changed, 32 insertions(+)
> create mode 100644 Documentation/devicetree/bindings/pwm/pwm-sifive.txt
>
> diff --git a/Documentation/devicetree/bindings/pwm/pwm-sifive.txt b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
> new file mode 100644
> index 00000000..532b10fc
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
> @@ -0,0 +1,32 @@
> +SiFive PWM controller
> +
> +Unlike most other PWM controllers, the SiFive PWM controller currently only
> +supports one period for all channels in the PWM. This is set globally in DTS.
> +The period also has significant restrictions on the values it can achieve,
> +which the driver rounds to the nearest achievable frequency.

What restrictions are these? If "nearest achievable" is too far off the
target period it might be preferable to error out.

> +Required properties:
> +- compatible: should be one of
> + "sifive,fu540-c000-pwm0","sifive,pwm0".

What's the '0' in here? A version number?

> + PWM controller is HiFive Unleashed specific chip which warrants a
> + specific compatible string. The second string is kept for backward
> + compatibility until a firmware update with latest compatible string.
> +- reg: physical base address and length of the controller's registers
> +- clocks: The frequency the controller runs at
> +- #pwm-cells: Should be 2.
> + The first cell is the PWM channel number
> + The second cell is the PWM polarity
> +- sifive,approx-period: the driver will get as close to this period as it can

Given the above comment, maybe "sifive,period"?

Thierry


Attachments:
(No filename) (2.00 kB)
signature.asc (849.00 B)
Download all attachments

2018-10-10 13:51:56

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
[...]
> +- interrupts: one interrupt per PWM channel (currently unused in the driver)

This should probably say what the interrupt is used for. And once you
have that, remove the comment about it being unused in the driver. DT
is OS agnostic, so "driver" is very unspecific and your claim may
actually be false.

Thierry


Attachments:
(No filename) (392.00 B)
signature.asc (849.00 B)
Download all attachments

2018-10-10 14:14:24

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 2/4] pwm: sifive: Add a driver for SiFive SoC PWM

On Tue, Oct 09, 2018 at 11:51:23AM -0700, Atish Patra wrote:
> From: "Wesley W. Terpstra" <[email protected]>
>
> Adds a PWM driver for PWM chip present in SiFive's HiFive Unleashed SoC.
>
> Signed-off-by: Wesley W. Terpstra <[email protected]>
> [Atish: Various fixes and code cleanup]
> Signed-off-by: Atish Patra <[email protected]>
> ---
> drivers/pwm/Kconfig | 10 ++
> drivers/pwm/Makefile | 1 +
> drivers/pwm/pwm-sifive.c | 240 +++++++++++++++++++++++++++++++++++++++++++++++
> 3 files changed, 251 insertions(+)
> create mode 100644 drivers/pwm/pwm-sifive.c
>
> diff --git a/drivers/pwm/Kconfig b/drivers/pwm/Kconfig
> index 504d2527..dd12144d 100644
> --- a/drivers/pwm/Kconfig
> +++ b/drivers/pwm/Kconfig
> @@ -378,6 +378,16 @@ config PWM_SAMSUNG
> To compile this driver as a module, choose M here: the module
> will be called pwm-samsung.
>
> +config PWM_SIFIVE
> + tristate "SiFive PWM support"
> + depends on OF
> + depends on COMMON_CLK
> + help
> + Generic PWM framework driver for SiFive SoCs.
> +
> + To compile this driver as a module, choose M here: the module
> + will be called pwm-sifive.
> +
> config PWM_SPEAR
> tristate "STMicroelectronics SPEAr PWM support"
> depends on PLAT_SPEAR
> diff --git a/drivers/pwm/Makefile b/drivers/pwm/Makefile
> index 9c676a0d..30089ca6 100644
> --- a/drivers/pwm/Makefile
> +++ b/drivers/pwm/Makefile
> @@ -37,6 +37,7 @@ obj-$(CONFIG_PWM_RCAR) += pwm-rcar.o
> obj-$(CONFIG_PWM_RENESAS_TPU) += pwm-renesas-tpu.o
> obj-$(CONFIG_PWM_ROCKCHIP) += pwm-rockchip.o
> obj-$(CONFIG_PWM_SAMSUNG) += pwm-samsung.o
> +obj-$(CONFIG_PWM_SIFIVE) += pwm-sifive.o
> obj-$(CONFIG_PWM_SPEAR) += pwm-spear.o
> obj-$(CONFIG_PWM_STI) += pwm-sti.o
> obj-$(CONFIG_PWM_STM32) += pwm-stm32.o
> diff --git a/drivers/pwm/pwm-sifive.c b/drivers/pwm/pwm-sifive.c
> new file mode 100644
> index 00000000..99580025
> --- /dev/null
> +++ b/drivers/pwm/pwm-sifive.c
> @@ -0,0 +1,240 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * Copyright (C) 2017 SiFive
> + */
> +#include <dt-bindings/pwm/pwm.h>

What do you need this for? Your driver should only be dealing with enum
pwm_polarity, not the defines from the above header. This works but only
because PWM_POLARITY_INVERTED and PWM_POLARITY_INVERSED happen to be the
same value.

> +#include <linux/module.h>
> +#include <linux/platform_device.h>
> +#include <linux/pwm.h>
> +#include <linux/slab.h>
> +#include <linux/clk.h>
> +#include <linux/io.h>

Keep these in alphabetical order, please.

> +
> +#define MAX_PWM 4
> +
> +/* Register offsets */
> +#define REG_PWMCFG 0x0
> +#define REG_PWMCOUNT 0x8
> +#define REG_PWMS 0x10
> +#define REG_PWMCMP0 0x20
> +
> +/* PWMCFG fields */
> +#define BIT_PWM_SCALE 0
> +#define BIT_PWM_STICKY 8
> +#define BIT_PWM_ZERO_ZMP 9
> +#define BIT_PWM_DEGLITCH 10
> +#define BIT_PWM_EN_ALWAYS 12
> +#define BIT_PWM_EN_ONCE 13
> +#define BIT_PWM0_CENTER 16
> +#define BIT_PWM0_GANG 24
> +#define BIT_PWM0_IP 28
> +
> +#define SIZE_PWMCMP 4
> +#define MASK_PWM_SCALE 0xf
> +
> +struct sifive_pwm_device {
> + struct pwm_chip chip;
> + struct notifier_block notifier;
> + struct clk *clk;
> + void __iomem *regs;
> + unsigned int approx_period;
> + unsigned int real_period;
> +};

No need to align these. A single space is enough to separate variable
type and name.

> +
> +static inline struct sifive_pwm_device *to_sifive_pwm_chip(struct pwm_chip *c)
> +{
> + return container_of(c, struct sifive_pwm_device, chip);
> +}
> +
> +static int sifive_pwm_apply(struct pwm_chip *chip, struct pwm_device *dev,
> + struct pwm_state *state)
> +{
> + struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
> + unsigned int duty_cycle;
> + u32 frac;
> +
> + duty_cycle = state->duty_cycle;
> + if (!state->enabled)
> + duty_cycle = 0;
> + if (state->polarity == PWM_POLARITY_NORMAL)
> + duty_cycle = state->period - duty_cycle;

That's not actually polarity inversion. This is "lightweight" inversion
which should be up to the consumer, not the PWM driver, to implement. If
you don't actually have a knob in hardware to switch the polarity, don't
support it.

> +
> + frac = ((u64)duty_cycle << 16) / state->period;
> + frac = min(frac, 0xFFFFU);
> +
> + iowrite32(frac, pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));

writel()?

> +
> + if (state->enabled) {
> + state->period = pwm->real_period;
> + state->duty_cycle = ((u64)frac * pwm->real_period) >> 16;
> + if (state->polarity == PWM_POLARITY_NORMAL)
> + state->duty_cycle = state->period - state->duty_cycle;
> + }
> +
> + return 0;
> +}
> +
> +static void sifive_pwm_get_state(struct pwm_chip *chip, struct pwm_device *dev,
> + struct pwm_state *state)
> +{
> + struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
> + unsigned long duty;
> +
> + duty = ioread32(pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));

readl()? Maybe also change duty to u32, which is what readl() returns.

> +
> + state->period = pwm->real_period;
> + state->duty_cycle = ((u64)duty * pwm->real_period) >> 16;
> + state->polarity = PWM_POLARITY_INVERSED;
> + state->enabled = duty > 0;
> +}
> +
> +static const struct pwm_ops sifive_pwm_ops = {
> + .get_state = sifive_pwm_get_state,
> + .apply = sifive_pwm_apply,
> + .owner = THIS_MODULE,

Again, no need to artificially align these.

> +};
> +
> +static struct pwm_device *sifive_pwm_xlate(struct pwm_chip *chip,
> + const struct of_phandle_args *args)
> +{
> + struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
> + struct pwm_device *dev;
> +
> + if (args->args[0] >= chip->npwm)
> + return ERR_PTR(-EINVAL);
> +
> + dev = pwm_request_from_chip(chip, args->args[0], NULL);
> + if (IS_ERR(dev))
> + return dev;
> +
> + /* The period cannot be changed on a per-PWM basis */
> + dev->args.period = pwm->real_period;
> + dev->args.polarity = PWM_POLARITY_NORMAL;
> + if (args->args[1] & PWM_POLARITY_INVERTED)
> + dev->args.polarity = PWM_POLARITY_INVERSED;
> +
> + return dev;
> +}
> +
> +static void sifive_pwm_update_clock(struct sifive_pwm_device *pwm,
> + unsigned long rate)
> +{
> + /* (1 << (16+scale)) * 10^9/rate = real_period */
> + unsigned long scalePow = (pwm->approx_period * (u64)rate) / 1000000000;
> + int scale = ilog2(scalePow) - 16;
> +
> + scale = clamp(scale, 0, 0xf);
> + iowrite32((1 << BIT_PWM_EN_ALWAYS) | (scale << BIT_PWM_SCALE),
> + pwm->regs + REG_PWMCFG);
> +
> + pwm->real_period = (1000000000ULL << (16 + scale)) / rate;
> +}
> +
> +static int sifive_pwm_clock_notifier(struct notifier_block *nb,
> + unsigned long event, void *data)
> +{
> + struct clk_notifier_data *ndata = data;
> + struct sifive_pwm_device *pwm = container_of(nb,
> + struct sifive_pwm_device,
> + notifier);
> +
> + if (event == POST_RATE_CHANGE)
> + sifive_pwm_update_clock(pwm, ndata->new_rate);
> +
> + return NOTIFY_OK;
> +}

Does this mean that the PWM source clock can be shared with other IP
blocks? What happens if some other user sets a frequency that we can't
support? Or what if the clock rate change results in a real period that
is out of the limits that are considered valid?

> +static int sifive_pwm_probe(struct platform_device *pdev)
> +{
> + struct device *dev = &pdev->dev;
> + struct device_node *node = pdev->dev.of_node;
> + struct sifive_pwm_device *pwm;
> + struct pwm_chip *chip;
> + struct resource *res;
> + int ret;
> +
> + pwm = devm_kzalloc(dev, sizeof(*pwm), GFP_KERNEL);
> + if (!pwm)
> + return -ENOMEM;
> +
> + chip = &pwm->chip;
> + chip->dev = dev;
> + chip->ops = &sifive_pwm_ops;
> + chip->of_xlate = sifive_pwm_xlate;
> + chip->of_pwm_n_cells = 2;
> + chip->base = -1;
> +
> + ret = of_property_read_u32(node, "sifive,npwm", &chip->npwm);
> + if (ret < 0 || chip->npwm > MAX_PWM)
> + chip->npwm = MAX_PWM;

This property is not documented. Also, why is it necessary? Do you
expect the number of PWMs to differ depending on the instance of the IP
block? I would argue that the number of PWMs can be derived from the
compatible string, so it's unnecessary here.

I think you can also remove the MAX_PWM macro, since that's only used in
one location and it's meaning is very clear in the context, so the
symbolic name isn't useful.

> +
> + ret = of_property_read_u32(node, "sifive,approx-period",
> + &pwm->approx_period);
> + if (ret < 0) {
> + dev_err(dev, "Unable to read sifive,approx-period from DTS\n");
> + return -ENOENT;
> + }

Maybe propagate ret instead of always returning -ENOENT?

> +
> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + pwm->regs = devm_ioremap_resource(dev, res);
> + if (IS_ERR(pwm->regs)) {
> + dev_err(dev, "Unable to map IO resources\n");
> + return PTR_ERR(pwm->regs);
> + }
> +
> + pwm->clk = devm_clk_get(dev, NULL);
> + if (IS_ERR(pwm->clk)) {
> + dev_err(dev, "Unable to find controller clock\n");
> + return PTR_ERR(pwm->clk);
> + }
> +
> + /* Watch for changes to underlying clock frequency */
> + pwm->notifier.notifier_call = sifive_pwm_clock_notifier;
> + clk_notifier_register(pwm->clk, &pwm->notifier);

Check for errors from this?

> +
> + /* Initialize PWM config */
> + sifive_pwm_update_clock(pwm, clk_get_rate(pwm->clk));
> +
> + /* No interrupt handler needed yet */

That's not a useful comment.

> +
> + ret = pwmchip_add(chip);
> + if (ret < 0) {
> + dev_err(dev, "cannot register PWM: %d\n", ret);
> + clk_notifier_unregister(pwm->clk, &pwm->notifier);

Might be worth introducing a managed version of clk_notifier_register()
so that we can avoid having to unregister it.

> + return ret;
> + }
> +
> + platform_set_drvdata(pdev, pwm);
> + dev_info(dev, "SiFive PWM chip registered %d PWMs\n", chip->npwm);

Remove this, or at least make it dev_dbg(). This is not noteworthy news,
so no need to bother the user with it.

> +
> + return 0;
> +}
> +
> +static int sifive_pwm_remove(struct platform_device *dev)
> +{
> + struct sifive_pwm_device *pwm = platform_get_drvdata(dev);
> + struct pwm_chip *chip = &pwm->chip;

Not sure that this intermediate variable is useful, might as well use
&pwm->chip in the one location where you need it.

> +
> + clk_notifier_unregister(pwm->clk, &pwm->notifier);
> + return pwmchip_remove(chip);
> +}
> +
> +static const struct of_device_id sifive_pwm_of_match[] = {
> + { .compatible = "sifive,pwm0" },
> + { .compatible = "sifive,fu540-c000-pwm0" },
> + {},
> +};
> +MODULE_DEVICE_TABLE(of, sifive_pwm_of_match);
> +
> +static struct platform_driver sifive_pwm_driver = {
> + .probe = sifive_pwm_probe,
> + .remove = sifive_pwm_remove,
> + .driver = {
> + .name = "pwm-sifivem",

Why does this have the 'm' at the end? I don't see that anywhere else in
the names.

> + .of_match_table = of_match_ptr(sifive_pwm_of_match),

No need for of_match_ptr() here since you depend on OF, so this is
always going to expand to sifive_pwm_of_match.

Thierry


Attachments:
(No filename) (10.99 kB)
signature.asc (849.00 B)
Download all attachments

2018-10-15 22:47:35

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On 10/10/18 6:51 AM, Thierry Reding wrote:
> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
> [...]
>> +- interrupts: one interrupt per PWM channel (currently unused in the driver)
>
> This should probably say what the interrupt is used for. And once you
> have that, remove the comment about it being unused in the driver. DT
> is OS agnostic, so "driver" is very unspecific and your claim may
> actually be false.
>
> Thierry
>
As per my understanding, they are generated by hardware but no usage of
pwm interrupts as of now.

I am not sure if removing the entire entry is a good idea.
What would be the best way to represent that information ?

May be this ?

+-interrupts: one interrupt per PWM channel. No usage in HiFive
Unleashed SoC.

Regards,
Atish

2018-10-15 22:58:21

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On 10/10/18 6:49 AM, Thierry Reding wrote:
> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
>> From: "Wesley W. Terpstra" <[email protected]>
>>
>> DT documentation for PWM controller added with updated compatible
>> string.
>>
>> Signed-off-by: Wesley W. Terpstra <[email protected]>
>> [Atish: Compatible string update]
>> Signed-off-by: Atish Patra <[email protected]>
>> ---
>> .../devicetree/bindings/pwm/pwm-sifive.txt | 32 ++++++++++++++++++++++
>> 1 file changed, 32 insertions(+)
>> create mode 100644 Documentation/devicetree/bindings/pwm/pwm-sifive.txt
>>
>> diff --git a/Documentation/devicetree/bindings/pwm/pwm-sifive.txt b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
>> new file mode 100644
>> index 00000000..532b10fc
>> --- /dev/null
>> +++ b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
>> @@ -0,0 +1,32 @@
>> +SiFive PWM controller
>> +
>> +Unlike most other PWM controllers, the SiFive PWM controller currently only
>> +supports one period for all channels in the PWM. This is set globally in DTS.
>> +The period also has significant restrictions on the values it can achieve,
>> +which the driver rounds to the nearest achievable frequency.
>
> What restrictions are these? If "nearest achievable" is too far off the
> target period it might be preferable to error out.
>

@Wes: Any comments?

>> +Required properties:
>> +- compatible: should be one of
>> + "sifive,fu540-c000-pwm0","sifive,pwm0".
>
> What's the '0' in here? A version number?
>

I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive
Guys decided mark it as version 0.

@Wesly: Please correct me if I am wrong.

>> + PWM controller is HiFive Unleashed specific chip which warrants a
>> + specific compatible string. The second string is kept for backward
>> + compatibility until a firmware update with latest compatible string.
>> +- reg: physical base address and length of the controller's registers
>> +- clocks: The frequency the controller runs at
>> +- #pwm-cells: Should be 2.
>> + The first cell is the PWM channel number
>> + The second cell is the PWM polarity
>> +- sifive,approx-period: the driver will get as close to this period as it can
>
> Given the above comment, maybe "sifive,period"?
>

ok.
In Unleashed board, the DT is loaded by FSBL (first stage boot loader).
Thus, changing device tree entries requires a FSBL update. If we update
this string, we need to update the driver to parse both properties so
that existing devices with older firmware continue to work.

This is probably ok as we anyways do that for compatible strings. Just
wanted to update that here for the record.

Regards,
Atish
> Thierry
>


2018-10-15 23:20:09

by Wesley Terpstra

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Mon, Oct 15, 2018 at 3:57 PM Atish Patra <[email protected]> wrote:
> >> +SiFive PWM controller
> >> +
> >> +Unlike most other PWM controllers, the SiFive PWM controller currently only
> >> +supports one period for all channels in the PWM. This is set globally in DTS.
> >> +The period also has significant restrictions on the values it can achieve,
> >> +which the driver rounds to the nearest achievable frequency.
> >
> > What restrictions are these? If "nearest achievable" is too far off the
> > target period it might be preferable to error out.
> >
>
> @Wes: Any comments?

When I last looked at this driver and hardware, I briefly considered
throwing up my hands and pretending that this PWM device had no period
control at all, only duty-cycle. There are several examples of PWM
controllers in linux already that behave that way.

Most of the uses of this PWM are only going to care about the
duty-cycle, not the period. So failing when the period is unachievable
seems worse to me than just completely eliminating access to period
control.

> I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive
> Guys decided mark it as version 0.
>
> @Wesly: Please correct me if I am wrong.

Correct.

2018-10-16 06:26:56

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 2/4] pwm: sifive: Add a driver for SiFive SoC PWM

On 10/10/18 7:13 AM, Thierry Reding wrote:
> On Tue, Oct 09, 2018 at 11:51:23AM -0700, Atish Patra wrote:
>> From: "Wesley W. Terpstra" <[email protected]>
>>
>> Adds a PWM driver for PWM chip present in SiFive's HiFive Unleashed SoC.
>>
>> Signed-off-by: Wesley W. Terpstra <[email protected]>
>> [Atish: Various fixes and code cleanup]
>> Signed-off-by: Atish Patra <[email protected]>
>> ---
>> drivers/pwm/Kconfig | 10 ++
>> drivers/pwm/Makefile | 1 +
>> drivers/pwm/pwm-sifive.c | 240 +++++++++++++++++++++++++++++++++++++++++++++++
>> 3 files changed, 251 insertions(+)
>> create mode 100644 drivers/pwm/pwm-sifive.c
>>
>> diff --git a/drivers/pwm/Kconfig b/drivers/pwm/Kconfig
>> index 504d2527..dd12144d 100644
>> --- a/drivers/pwm/Kconfig
>> +++ b/drivers/pwm/Kconfig
>> @@ -378,6 +378,16 @@ config PWM_SAMSUNG
>> To compile this driver as a module, choose M here: the module
>> will be called pwm-samsung.
>>
>> +config PWM_SIFIVE
>> + tristate "SiFive PWM support"
>> + depends on OF
>> + depends on COMMON_CLK
>> + help
>> + Generic PWM framework driver for SiFive SoCs.
>> +
>> + To compile this driver as a module, choose M here: the module
>> + will be called pwm-sifive.
>> +
>> config PWM_SPEAR
>> tristate "STMicroelectronics SPEAr PWM support"
>> depends on PLAT_SPEAR
>> diff --git a/drivers/pwm/Makefile b/drivers/pwm/Makefile
>> index 9c676a0d..30089ca6 100644
>> --- a/drivers/pwm/Makefile
>> +++ b/drivers/pwm/Makefile
>> @@ -37,6 +37,7 @@ obj-$(CONFIG_PWM_RCAR) += pwm-rcar.o
>> obj-$(CONFIG_PWM_RENESAS_TPU) += pwm-renesas-tpu.o
>> obj-$(CONFIG_PWM_ROCKCHIP) += pwm-rockchip.o
>> obj-$(CONFIG_PWM_SAMSUNG) += pwm-samsung.o
>> +obj-$(CONFIG_PWM_SIFIVE) += pwm-sifive.o
>> obj-$(CONFIG_PWM_SPEAR) += pwm-spear.o
>> obj-$(CONFIG_PWM_STI) += pwm-sti.o
>> obj-$(CONFIG_PWM_STM32) += pwm-stm32.o
>> diff --git a/drivers/pwm/pwm-sifive.c b/drivers/pwm/pwm-sifive.c
>> new file mode 100644
>> index 00000000..99580025
>> --- /dev/null
>> +++ b/drivers/pwm/pwm-sifive.c
>> @@ -0,0 +1,240 @@
>> +// SPDX-License-Identifier: GPL-2.0
>> +/*
>> + * Copyright (C) 2017 SiFive
>> + */
>> +#include <dt-bindings/pwm/pwm.h>
>
> What do you need this for? Your driver should only be dealing with enum
> pwm_polarity, not the defines from the above header. This works but only
> because PWM_POLARITY_INVERTED and PWM_POLARITY_INVERSED happen to be the
> same value.
>
>> +#include <linux/module.h>
>> +#include <linux/platform_device.h>
>> +#include <linux/pwm.h>
>> +#include <linux/slab.h>
>> +#include <linux/clk.h>
>> +#include <linux/io.h>
>
> Keep these in alphabetical order, please.
>
>> +
>> +#define MAX_PWM 4
>> +
>> +/* Register offsets */
>> +#define REG_PWMCFG 0x0
>> +#define REG_PWMCOUNT 0x8
>> +#define REG_PWMS 0x10
>> +#define REG_PWMCMP0 0x20
>> +
>> +/* PWMCFG fields */
>> +#define BIT_PWM_SCALE 0
>> +#define BIT_PWM_STICKY 8
>> +#define BIT_PWM_ZERO_ZMP 9
>> +#define BIT_PWM_DEGLITCH 10
>> +#define BIT_PWM_EN_ALWAYS 12
>> +#define BIT_PWM_EN_ONCE 13
>> +#define BIT_PWM0_CENTER 16
>> +#define BIT_PWM0_GANG 24
>> +#define BIT_PWM0_IP 28
>> +
>> +#define SIZE_PWMCMP 4
>> +#define MASK_PWM_SCALE 0xf
>> +
>> +struct sifive_pwm_device {
>> + struct pwm_chip chip;
>> + struct notifier_block notifier;
>> + struct clk *clk;
>> + void __iomem *regs;
>> + unsigned int approx_period;
>> + unsigned int real_period;
>> +};
>
> No need to align these. A single space is enough to separate variable
> type and name.
>
>> +
>> +static inline struct sifive_pwm_device *to_sifive_pwm_chip(struct pwm_chip *c)
>> +{
>> + return container_of(c, struct sifive_pwm_device, chip);
>> +}
>> +
>> +static int sifive_pwm_apply(struct pwm_chip *chip, struct pwm_device *dev,
>> + struct pwm_state *state)
>> +{
>> + struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
>> + unsigned int duty_cycle;
>> + u32 frac;
>> +
>> + duty_cycle = state->duty_cycle;
>> + if (!state->enabled)
>> + duty_cycle = 0;
>> + if (state->polarity == PWM_POLARITY_NORMAL)
>> + duty_cycle = state->period - duty_cycle;
>
> That's not actually polarity inversion. This is "lightweight" inversion
> which should be up to the consumer, not the PWM driver, to implement. If
> you don't actually have a knob in hardware to switch the polarity, don't
> support it.
>

I couldn't find anything about polarity support in the spec. Of course,
I might be complete idiot as well :). I will wait for Wesly's confirmation.


>> +
>> + frac = ((u64)duty_cycle << 16) / state->period;
>> + frac = min(frac, 0xFFFFU);
>> +
>> + iowrite32(frac, pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));
>
> writel()?
>


>> +
>> + if (state->enabled) {
>> + state->period = pwm->real_period;
>> + state->duty_cycle = ((u64)frac * pwm->real_period) >> 16;
>> + if (state->polarity == PWM_POLARITY_NORMAL)
>> + state->duty_cycle = state->period - state->duty_cycle;
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static void sifive_pwm_get_state(struct pwm_chip *chip, struct pwm_device *dev,
>> + struct pwm_state *state)
>> +{
>> + struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
>> + unsigned long duty;
>> +
>> + duty = ioread32(pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));
>
> readl()? Maybe also change duty to u32, which is what readl() returns.
>
Sure. I will convert all iowrite/read to readl/writel.

>> +
>> + state->period = pwm->real_period;
>> + state->duty_cycle = ((u64)duty * pwm->real_period) >> 16;
>> + state->polarity = PWM_POLARITY_INVERSED;
>> + state->enabled = duty > 0;
>> +}
>> +
>> +static const struct pwm_ops sifive_pwm_ops = {
>> + .get_state = sifive_pwm_get_state,
>> + .apply = sifive_pwm_apply,
>> + .owner = THIS_MODULE,
>
> Again, no need to artificially align these.
>

Sure. I will fix the other alignment comment as well.

>> +};
>> +
>> +static struct pwm_device *sifive_pwm_xlate(struct pwm_chip *chip,
>> + const struct of_phandle_args *args)
>> +{
>> + struct sifive_pwm_device *pwm = to_sifive_pwm_chip(chip);
>> + struct pwm_device *dev;
>> +
>> + if (args->args[0] >= chip->npwm)
>> + return ERR_PTR(-EINVAL);
>> +
>> + dev = pwm_request_from_chip(chip, args->args[0], NULL);
>> + if (IS_ERR(dev))
>> + return dev;
>> +
>> + /* The period cannot be changed on a per-PWM basis */
>> + dev->args.period = pwm->real_period;
>> + dev->args.polarity = PWM_POLARITY_NORMAL;
>> + if (args->args[1] & PWM_POLARITY_INVERTED)
>> + dev->args.polarity = PWM_POLARITY_INVERSED;
>> +
>> + return dev;
>> +}
>> +
>> +static void sifive_pwm_update_clock(struct sifive_pwm_device *pwm,
>> + unsigned long rate)
>> +{
>> + /* (1 << (16+scale)) * 10^9/rate = real_period */
>> + unsigned long scalePow = (pwm->approx_period * (u64)rate) / 1000000000;
>> + int scale = ilog2(scalePow) - 16;
>> +
>> + scale = clamp(scale, 0, 0xf);
>> + iowrite32((1 << BIT_PWM_EN_ALWAYS) | (scale << BIT_PWM_SCALE),
>> + pwm->regs + REG_PWMCFG);
>> +
>> + pwm->real_period = (1000000000ULL << (16 + scale)) / rate;
>> +}
>> +
>> +static int sifive_pwm_clock_notifier(struct notifier_block *nb,
>> + unsigned long event, void *data)
>> +{
>> + struct clk_notifier_data *ndata = data;
>> + struct sifive_pwm_device *pwm = container_of(nb,
>> + struct sifive_pwm_device,
>> + notifier);
>> +
>> + if (event == POST_RATE_CHANGE)
>> + sifive_pwm_update_clock(pwm, ndata->new_rate);
>> +
>> + return NOTIFY_OK;
>> +}
>
> Does this mean that the PWM source clock can be shared with other IP
> blocks?

PWM clock update is required to be reprogrammed because of single PLL.
It runs at bus clock rate which is half of the PLL rate.
In case of, cpu clock rate change, pwm settings need to be calculated
again to maintain the same rate.


What happens if some other user sets a frequency that we can't
> support? Or what if the clock rate change results in a real period that
> is out of the limits that are considered valid?
>

@Wesley: What should be the expected behavior in these cases ?

>> +static int sifive_pwm_probe(struct platform_device *pdev)
>> +{
>> + struct device *dev = &pdev->dev;
>> + struct device_node *node = pdev->dev.of_node;
>> + struct sifive_pwm_device *pwm;
>> + struct pwm_chip *chip;
>> + struct resource *res;
>> + int ret;
>> +
>> + pwm = devm_kzalloc(dev, sizeof(*pwm), GFP_KERNEL);
>> + if (!pwm)
>> + return -ENOMEM;
>> +
>> + chip = &pwm->chip;
>> + chip->dev = dev;
>> + chip->ops = &sifive_pwm_ops;
>> + chip->of_xlate = sifive_pwm_xlate;
>> + chip->of_pwm_n_cells = 2;
>> + chip->base = -1;
>> +
>> + ret = of_property_read_u32(node, "sifive,npwm", &chip->npwm);
>> + if (ret < 0 || chip->npwm > MAX_PWM)
>> + chip->npwm = MAX_PWM;
>
> This property is not documented. Also, why is it necessary? Do you
> expect the number of PWMs to differ depending on the instance of the IP
> block? I would argue that the number of PWMs can be derived from the
> compatible string, so it's unnecessary here.
>

I think this is left over from old code. Sorry for that.
I will remove it.

> I think you can also remove the MAX_PWM macro, since that's only used in
> one location and it's meaning is very clear in the context, so the
> symbolic name isn't useful.
>

Sure.

>> +
>> + ret = of_property_read_u32(node, "sifive,approx-period",
>> + &pwm->approx_period);
>> + if (ret < 0) {
>> + dev_err(dev, "Unable to read sifive,approx-period from DTS\n");
>> + return -ENOENT;
>> + }
>
> Maybe propagate ret instead of always returning -ENOENT?
>
ok.

>> +
>> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
>> + pwm->regs = devm_ioremap_resource(dev, res);
>> + if (IS_ERR(pwm->regs)) {
>> + dev_err(dev, "Unable to map IO resources\n");
>> + return PTR_ERR(pwm->regs);
>> + }
>> +
>> + pwm->clk = devm_clk_get(dev, NULL);
>> + if (IS_ERR(pwm->clk)) {
>> + dev_err(dev, "Unable to find controller clock\n");
>> + return PTR_ERR(pwm->clk);
>> + }
>> +
>> + /* Watch for changes to underlying clock frequency */
>> + pwm->notifier.notifier_call = sifive_pwm_clock_notifier;
>> + clk_notifier_register(pwm->clk, &pwm->notifier);
>
> Check for errors from this?
>
>> +
>> + /* Initialize PWM config */
>> + sifive_pwm_update_clock(pwm, clk_get_rate(pwm->clk));
>> +
>> + /* No interrupt handler needed yet */
>
> That's not a useful comment.
>
Will remove it.

>> +
>> + ret = pwmchip_add(chip);
>> + if (ret < 0) {
>> + dev_err(dev, "cannot register PWM: %d\n", ret);
>> + clk_notifier_unregister(pwm->clk, &pwm->notifier);
>
> Might be worth introducing a managed version of clk_notifier_register()
> so that we can avoid having to unregister it.
>

If I understand correctly, it should be defined in clk.c as a
devm_clk_notifier_register. I can add it as as a separate patch and
rebase this patch on top of it.


>> + return ret;
>> + }
>> +
>> + platform_set_drvdata(pdev, pwm);
>> + dev_info(dev, "SiFive PWM chip registered %d PWMs\n", chip->npwm);
>
> Remove this, or at least make it dev_dbg(). This is not noteworthy news,
> so no need to bother the user with it.
>

Sure.

>> +
>> + return 0;
>> +}
>> +
>> +static int sifive_pwm_remove(struct platform_device *dev)
>> +{
>> + struct sifive_pwm_device *pwm = platform_get_drvdata(dev);
>> + struct pwm_chip *chip = &pwm->chip;
>
> Not sure that this intermediate variable is useful, might as well use
> &pwm->chip in the one location where you need it.
>

Correct. I will remove it.

>> +
>> + clk_notifier_unregister(pwm->clk, &pwm->notifier);
>> + return pwmchip_remove(chip);
>> +}
>> +
>> +static const struct of_device_id sifive_pwm_of_match[] = {
>> + { .compatible = "sifive,pwm0" },
>> + { .compatible = "sifive,fu540-c000-pwm0" },
>> + {},
>> +};
>> +MODULE_DEVICE_TABLE(of, sifive_pwm_of_match);
>> +
>> +static struct platform_driver sifive_pwm_driver = {
>> + .probe = sifive_pwm_probe,
>> + .remove = sifive_pwm_remove,
>> + .driver = {
>> + .name = "pwm-sifivem",
>
> Why does this have the 'm' at the end? I don't see that anywhere else in
> the names.

My bad. It's a typo.

>
>> + .of_match_table = of_match_ptr(sifive_pwm_of_match),
>
> No need for of_match_ptr() here since you depend on OF, so this is
> always going to expand to sifive_pwm_of_match.
>

ok.

Thanks a lot for reviewing the patch.

Regards,
Atish
> Thierry
>


2018-10-16 06:30:39

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 2/4] pwm: sifive: Add a driver for SiFive SoC PWM

On 10/10/18 6:11 AM, Christoph Hellwig wrote:
> Thanks for getting these drivers submitted upstream!
>
> I don't really know anything about PWM, so just some random nitpicking
> below..
>
>> + iowrite32(frac, pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));
>
> * already has a higher precedence than +, so no need for the inner
> braces.
>
>> + duty = ioread32(pwm->regs + REG_PWMCMP0 + (dev->hwpwm * SIZE_PWMCMP));
>
> Same here.

Will remove the braces in both places.
>
>> + /* (1 << (16+scale)) * 10^9/rate = real_period */
> unsigned long scalePow = (pwm->approx_period * (u64)rate) / 1000000000;
>
> no camcel case, please.

My bad. I will fix that.

>
>> + int scale = ilog2(scalePow) - 16;
>> +
>> + scale = clamp(scale, 0, 0xf);
>
> Why not:
>
> int scale = clamp(ilog2(scale_pow) - 16, 0, 0xf);
>

Sure.

>> +static int sifive_pwm_clock_notifier(struct notifier_block *nb,
>> + unsigned long event, void *data)
>> +{
>> + struct clk_notifier_data *ndata = data;
>> + struct sifive_pwm_device *pwm = container_of(nb,
>> + struct sifive_pwm_device,
>> + notifier);
>
> I don't think there are any guidlines, but I always prefer to just move
> the whole container_of onto a new line:
>
> struct sifive_pwm_device *pwm =
> container_of(nb, struct sifive_pwm_device, notifier);

Done.

Regards,
Atish
>
>> +static struct platform_driver sifive_pwm_driver = {
>> + .probe = sifive_pwm_probe,
>> + .remove = sifive_pwm_remove,
>> + .driver = {
>> + .name = "pwm-sifivem",
>> + .of_match_table = of_match_ptr(sifive_pwm_of_match),
>> + },
>> +};
>
> What about using tabs to align this a little more nicely?
>
> static struct platform_driver sifive_pwm_driver = {
> .probe = sifive_pwm_probe,
> .remove = sifive_pwm_remove,
> .driver = {
> .name = "pwm-sifivem",
> .of_match_table = of_match_ptr(sifive_pwm_of_match),
> },
> };
>


2018-10-16 10:51:55

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Mon, Oct 15, 2018 at 03:45:46PM -0700, Atish Patra wrote:
> On 10/10/18 6:51 AM, Thierry Reding wrote:
> > On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
> > [...]
> > > +- interrupts: one interrupt per PWM channel (currently unused in the driver)
> >
> > This should probably say what the interrupt is used for. And once you
> > have that, remove the comment about it being unused in the driver. DT
> > is OS agnostic, so "driver" is very unspecific and your claim may
> > actually be false.
> >
> > Thierry
> >
> As per my understanding, they are generated by hardware but no usage of pwm
> interrupts as of now.

It might be useful to say when they are generated. Are they generated
once per period? At the beginning or the end of the period? That kind
of thing.

> I am not sure if removing the entire entry is a good idea.
> What would be the best way to represent that information ?
>
> May be this ?
>
> +-interrupts: one interrupt per PWM channel. No usage in HiFive Unleashed
> SoC.

Why do you think you need to say that they are unused? If the hardware
generates these interrupts, then they are "used". If no driver currently
has a use for them, that's driver specific and doesn't belong in the DT
bindings.

Thierry


Attachments:
(No filename) (1.25 kB)
signature.asc (849.00 B)
Download all attachments

2018-10-16 11:03:42

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
> On 10/10/18 6:49 AM, Thierry Reding wrote:
> > On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
> > > From: "Wesley W. Terpstra" <[email protected]>
> > >
> > > DT documentation for PWM controller added with updated compatible
> > > string.
> > >
> > > Signed-off-by: Wesley W. Terpstra <[email protected]>
> > > [Atish: Compatible string update]
> > > Signed-off-by: Atish Patra <[email protected]>
> > > ---
> > > .../devicetree/bindings/pwm/pwm-sifive.txt | 32 ++++++++++++++++++++++
> > > 1 file changed, 32 insertions(+)
> > > create mode 100644 Documentation/devicetree/bindings/pwm/pwm-sifive.txt
> > >
> > > diff --git a/Documentation/devicetree/bindings/pwm/pwm-sifive.txt b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
> > > new file mode 100644
> > > index 00000000..532b10fc
> > > --- /dev/null
> > > +++ b/Documentation/devicetree/bindings/pwm/pwm-sifive.txt
> > > @@ -0,0 +1,32 @@
> > > +SiFive PWM controller
> > > +
> > > +Unlike most other PWM controllers, the SiFive PWM controller currently only
> > > +supports one period for all channels in the PWM. This is set globally in DTS.
> > > +The period also has significant restrictions on the values it can achieve,
> > > +which the driver rounds to the nearest achievable frequency.
> >
> > What restrictions are these? If "nearest achievable" is too far off the
> > target period it might be preferable to error out.
> >
>
> @Wes: Any comments?
>
> > > +Required properties:
> > > +- compatible: should be one of
> > > + "sifive,fu540-c000-pwm0","sifive,pwm0".
> >
> > What's the '0' in here? A version number?
> >
>
> I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
> decided mark it as version 0.
>
> @Wesly: Please correct me if I am wrong.

It seems fairly superfluous to me to have a version number in additon to
the fu540-c000, which already seems to be the core plus some sort of
part number. Do you really expect there to be any changes in the SoC
that would require a different compatible string at this point? If the
SoC has taped out, how will you ever get a different version of the PWM
IP in it?

I would expect any improvements or changes to the PWM IP to show up in a
different SoC generation, at which point it would be something like
"sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
the numbering is.

> > > + PWM controller is HiFive Unleashed specific chip which warrants a
> > > + specific compatible string. The second string is kept for backward
> > > + compatibility until a firmware update with latest compatible string.
> > > +- reg: physical base address and length of the controller's registers
> > > +- clocks: The frequency the controller runs at
> > > +- #pwm-cells: Should be 2.
> > > + The first cell is the PWM channel number
> > > + The second cell is the PWM polarity
> > > +- sifive,approx-period: the driver will get as close to this period as it can
> >
> > Given the above comment, maybe "sifive,period"?
> >
>
> ok.
> In Unleashed board, the DT is loaded by FSBL (first stage boot loader).
> Thus, changing device tree entries requires a FSBL update. If we update this
> string, we need to update the driver to parse both properties so that
> existing devices with older firmware continue to work.
>
> This is probably ok as we anyways do that for compatible strings. Just
> wanted to update that here for the record.

I'm going to defer to Rob on this. He's said in the past that he doesn't
care about existing bindings that haven't been vetted through upstream,
even if that means that bootloaders may have to be updated. I know he's
been fairly strict on this in the past, but let's see if there is room
for exceptions.

Thierry


Attachments:
(No filename) (3.80 kB)
signature.asc (849.00 B)
Download all attachments

2018-10-16 11:14:17

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Mon, Oct 15, 2018 at 04:19:20PM -0700, Wesley Terpstra wrote:
> On Mon, Oct 15, 2018 at 3:57 PM Atish Patra <[email protected]> wrote:
> > >> +SiFive PWM controller
> > >> +
> > >> +Unlike most other PWM controllers, the SiFive PWM controller currently only
> > >> +supports one period for all channels in the PWM. This is set globally in DTS.
> > >> +The period also has significant restrictions on the values it can achieve,
> > >> +which the driver rounds to the nearest achievable frequency.
> > >
> > > What restrictions are these? If "nearest achievable" is too far off the
> > > target period it might be preferable to error out.
> > >
> >
> > @Wes: Any comments?
>
> When I last looked at this driver and hardware, I briefly considered
> throwing up my hands and pretending that this PWM device had no period
> control at all, only duty-cycle. There are several examples of PWM
> controllers in linux already that behave that way.

Can you point those out? So far we've always opted to refuse changing
the period of PWM channels that share a period if it didn't match the
current period.

> Most of the uses of this PWM are only going to care about the
> duty-cycle, not the period. So failing when the period is unachievable
> seems worse to me than just completely eliminating access to period
> control.

I'm not sure we've ever tried to completely take period out of the
picture. You could probably do it if you use only the atomic API because
then you just leave the period untouched. And if you have a post-clock
change you just need to make sure to record the new period and update
the duty cycle so that the ratio remains the same.

I think that could work, but I think it'd be best to be explicit about
it, rather than just handwaving it.

Thierry


Attachments:
(No filename) (1.77 kB)
signature.asc (849.00 B)
Download all attachments

2018-10-16 17:32:26

by Paul Walmsley

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.


On 10/16/18 4:01 AM, Thierry Reding wrote:
> On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
>> On 10/10/18 6:49 AM, Thierry Reding wrote:
>>> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
>>>> +Required properties:
>>>> +- compatible: should be one of
>>>> + "sifive,fu540-c000-pwm0","sifive,pwm0".
>>> What's the '0' in here? A version number?
>>>
>> I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
>> decided mark it as version 0.
>>
>> @Wesly: Please correct me if I am wrong.
> It seems fairly superfluous to me to have a version number in additon to
> the fu540-c000, which already seems to be the core plus some sort of
> part number. Do you really expect there to be any changes in the SoC
> that would require a different compatible string at this point? If the
> SoC has taped out, how will you ever get a different version of the PWM
> IP in it?
>
> I would expect any improvements or changes to the PWM IP to show up in a
> different SoC generation, at which point it would be something like
> "sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
> the numbering is.


The "0" suffix refers to a revision number for the underlying PWM IP block.

It's certainly important to keep that version number on the
"sifive,pwm0" compatible string that doesn't have the chip name
associated with it.

As to whether there could ever be a FU540-C000 part with different IP
block versions on it: FU540-C000 is ultimately a marketing name.? While
theoretically we shouldn't have another "FU540-C000" chip with different
peripheral IP block versions on it, I don't think any engineer can
guarantee that it won't happen.


- Paul


2018-10-16 22:05:33

by Thierry Reding

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Tue, Oct 16, 2018 at 10:31:42AM -0700, Paul Walmsley wrote:
>
> On 10/16/18 4:01 AM, Thierry Reding wrote:
> > On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
> > > On 10/10/18 6:49 AM, Thierry Reding wrote:
> > > > On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
> > > > > +Required properties:
> > > > > +- compatible: should be one of
> > > > > + "sifive,fu540-c000-pwm0","sifive,pwm0".
> > > > What's the '0' in here? A version number?
> > > >
> > > I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
> > > decided mark it as version 0.
> > >
> > > @Wesly: Please correct me if I am wrong.
> > It seems fairly superfluous to me to have a version number in additon to
> > the fu540-c000, which already seems to be the core plus some sort of
> > part number. Do you really expect there to be any changes in the SoC
> > that would require a different compatible string at this point? If the
> > SoC has taped out, how will you ever get a different version of the PWM
> > IP in it?
> >
> > I would expect any improvements or changes to the PWM IP to show up in a
> > different SoC generation, at which point it would be something like
> > "sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
> > the numbering is.
>
>
> The "0" suffix refers to a revision number for the underlying PWM IP block.
>
> It's certainly important to keep that version number on the "sifive,pwm0"
> compatible string that doesn't have the chip name associated with it.

Isn't the hardware identified by "sifive,pwm0" and "sifive,fu540-c000"
effectively identical? Is there a need to have two compatible strings
that refer to the exact same hardware?

> As to whether there could ever be a FU540-C000 part with different IP block
> versions on it: FU540-C000 is ultimately a marketing name.  While
> theoretically we shouldn't have another "FU540-C000" chip with different
> peripheral IP block versions on it, I don't think any engineer can guarantee
> that it won't happen.

I would argue that if at some point there was indeed a chip with the
same name but a different IP block version in it, we can figure out what
to call it. Sure there are no guarantees, but it's still fairly unlikely
in my opinion, so I personally wouldn't worry about this up front.

Anyway, I don't feel strongly either way, I'm just pointing out that
this is somewhat unusual. If you want to keep it, feel free to.

Thierry


Attachments:
(No filename) (2.45 kB)
signature.asc (849.00 B)
Download all attachments

2018-10-16 22:21:34

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On 10/16/18 3:04 PM, Thierry Reding wrote:
> On Tue, Oct 16, 2018 at 10:31:42AM -0700, Paul Walmsley wrote:
>>
>> On 10/16/18 4:01 AM, Thierry Reding wrote:
>>> On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
>>>> On 10/10/18 6:49 AM, Thierry Reding wrote:
>>>>> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
>>>>>> +Required properties:
>>>>>> +- compatible: should be one of
>>>>>> + "sifive,fu540-c000-pwm0","sifive,pwm0".
>>>>> What's the '0' in here? A version number?
>>>>>
>>>> I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
>>>> decided mark it as version 0.
>>>>
>>>> @Wesly: Please correct me if I am wrong.
>>> It seems fairly superfluous to me to have a version number in additon to
>>> the fu540-c000, which already seems to be the core plus some sort of
>>> part number. Do you really expect there to be any changes in the SoC
>>> that would require a different compatible string at this point? If the
>>> SoC has taped out, how will you ever get a different version of the PWM
>>> IP in it?
>>>
>>> I would expect any improvements or changes to the PWM IP to show up in a
>>> different SoC generation, at which point it would be something like
>>> "sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
>>> the numbering is.
>>
>>
>> The "0" suffix refers to a revision number for the underlying PWM IP block.
>>
>> It's certainly important to keep that version number on the "sifive,pwm0"
>> compatible string that doesn't have the chip name associated with it.
>
> Isn't the hardware identified by "sifive,pwm0" and "sifive,fu540-c000"
> effectively identical?

Yes.

Is there a need to have two compatible strings
> that refer to the exact same hardware?
>

The DT in the hardware has only sifive,pwm0. I have added
"sifive,fu540-c000" as that was concluded as the correct compatible
string from platform level interrupt controller patch(PLIC) discussion.

(http://lists.infradead.org/pipermail/linux-riscv/2018-August/001135.html)

"sifive,pwm0" is required to until all the Unleashed SoC gets an updated
firmware with correct compatible string "sifive,fu540-c000". I agree
this is a mess. But we have to carry it until all every DT(corresponding
to each driver) is finalized. I guess SiFive will release a firmware
update that contains all the updated DT once that is done. We can get
rid of all the redundant compatible strings at that time.

Regards,
Atish
>> As to whether there could ever be a FU540-C000 part with different IP block
>> versions on it: FU540-C000 is ultimately a marketing name.  While
>> theoretically we shouldn't have another "FU540-C000" chip with different
>> peripheral IP block versions on it, I don't think any engineer can guarantee
>> that it won't happen.
>
> I would argue that if at some point there was indeed a chip with the
> same name but a different IP block version in it, we can figure out what
> to call it. Sure there are no guarantees, but it's still fairly unlikely
> in my opinion, so I personally wouldn't worry about this up front.
>
> Anyway, I don't feel strongly either way, I'm just pointing out that
> this is somewhat unusual. If you want to keep it, feel free to.
>
> Thierry
>


2018-10-16 22:44:17

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On 10/16/18 3:51 AM, Thierry Reding wrote:
> On Mon, Oct 15, 2018 at 03:45:46PM -0700, Atish Patra wrote:
>> On 10/10/18 6:51 AM, Thierry Reding wrote:
>>> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
>>> [...]
>>>> +- interrupts: one interrupt per PWM channel (currently unused in the driver)
>>>
>>> This should probably say what the interrupt is used for. And once you
>>> have that, remove the comment about it being unused in the driver. DT
>>> is OS agnostic, so "driver" is very unspecific and your claim may
>>> actually be false.
>>>
>>> Thierry
>>>
>> As per my understanding, they are generated by hardware but no usage of pwm
>> interrupts as of now.
>
> It might be useful to say when they are generated. Are they generated
> once per period? At the beginning or the end of the period? That kind
> of thing.
>

Sure. I might have over simplified the statement above.
I could only find this about pwm interrupts in spec.
"The PWM can be configured to provide periodic counter interrupts by
enabling auto-zeroing of the count register when a comparator 0 fires"

I may be wrong here but it looks like we need to configure the hardware
to generate periodic interrupts. I will confirm with Wesly and update it
in v2.

>> I am not sure if removing the entire entry is a good idea.
>> What would be the best way to represent that information ?
>>
>> May be this ?
>>
>> +-interrupts: one interrupt per PWM channel. No usage in HiFive Unleashed
>> SoC.
>
> Why do you think you need to say that they are unused? If the hardware
> generates these interrupts, then they are "used". If no driver currently
> has a use for them, that's driver specific and doesn't belong in the DT
> bindings.
>

Sounds good. I will update accordingly.

Regards,
Atish
> Thierry
>


2018-10-17 01:03:37

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

On 10/10/18 5:35 AM, Linus Walleij wrote:
> Hi Atish,
>
> thanks for your patch!
>
> On Tue, Oct 9, 2018 at 8:51 PM Atish Patra <[email protected]> wrote:
>
>> From: "Wesley W. Terpstra" <[email protected]>
>>
>> Adds the GPIO driver for SiFive RISC-V SoCs.
>>
>> Signed-off-by: Wesley W. Terpstra <[email protected]>
>> [Atish: Various fixes and code cleanup]
>> Signed-off-by: Atish Patra <[email protected]>
>
> (...)
>
>> +config GPIO_SIFIVE
>> + bool "SiFive GPIO support"
>> + depends on OF_GPIO
>> + select GPIOLIB_IRQCHIP
>
> I suggest to add
> select GPIO_GENERIC as per below.
>
> Maybe select REGMAP_MMIO as well.

ok.

>
>> + help
>> + Say yes here to support the GPIO device on SiFive SoCs.
>> +
>
>> +#include <linux/of_irq.h>
>> +#include <linux/irqchip/chained_irq.h>
>
> Do you need these two? I think <linux/gpio/driver.h>
> will bring them in for you.
>

driver.h only brings chained_irq.h. of_irq.h is still required. Right ?

>> +#include <linux/pinctrl/consumer.h>
>
> Are you using this?

My bad. Left over from the old code. I will remove it.

>
>> +struct sifive_gpio {
>> + raw_spinlock_t lock;
>> + void __iomem *base;
>> + struct gpio_chip gc;
>> + unsigned long enabled;
>
> Since max GPIO is 32 why not use an u32 for this?
>

Sure.

>> + unsigned int trigger[MAX_GPIO];
>> + unsigned int irq_parent[MAX_GPIO];
>> + struct sifive_gpio *self_ptr[MAX_GPIO];
>> +};
>> +
>> +static void sifive_assign_bit(void __iomem *ptr, unsigned int offset, int value)
>> +{
>> + /*
>> + * It's frustrating that we are not allowed to use the device atomics
>> + * which are GUARANTEED to be supported by this device on RISC-V
>> + */
>> + u32 bit = BIT(offset), old = ioread32(ptr);
>> +
>> + if (value)
>> + iowrite32(old | bit, ptr);
>> + else
>> + iowrite32(old & ~bit, ptr);
>> +}
>
> This looks like a mask and set implementation, you are
> essentially reinventing regmap MMIO and the
> regmap_update_bits() call. Could you look into
> just using regmap MMIO in that case?
>
> If you need examples, look at gpio-mvebu.c that calls
> devm_regmap_init_mmio() for example.
>

That's really cool. Sorry, for not checking that earlier.
I am pretty new to this.

>> +static int sifive_direction_input(struct gpio_chip *gc, unsigned int offset)
>> +static int sifive_direction_output(struct gpio_chip *gc, unsigned int offset,
>> +static int sifive_get_direction(struct gpio_chip *gc, unsigned int offset)
>> +static int sifive_get_value(struct gpio_chip *gc, unsigned int offset)
>> +static void sifive_set_value(struct gpio_chip *gc, unsigned int offset,
>
> These functions look like a typical hardware that can use
>
> GPIOLIB_GENERIC and bgpio_init() to set up the accessors.
>
> See gpio-ftgpio010.c for an example.
>
> As a bonus you will get .get/.set_multiple implemented by
> the generic GPIO.
>

Great. This will reduce the driver a code by a big factor.
Thanks for the pointer.


>> +static void sifive_irq_enable(struct irq_data *d)
>> +static void sifive_irq_disable(struct irq_data *d)
> (...)
>> +static struct irq_chip sifive_irqchip = {
>> + .name = "sifive-gpio",
>> + .irq_set_type = sifive_irq_set_type,
>> + .irq_mask = sifive_irq_mask,
>> + .irq_unmask = sifive_irq_unmask,
>> + .irq_enable = sifive_irq_enable,
>> + .irq_disable = sifive_irq_disable,
>
> The handling of .irq_enable and .irq_disable has
> changed upstream. Please align with the new codebase
> as changed by Hans Verkuil:
>
> commit 461c1a7d4733d1dfd5c47b040cf32a5e7eefbc6c
> "gpiolib: override irq_enable/disable"
> commit 4e9439ddacea06f35acce4d374bf6bd0acf99bc8
> "gpiolib: add flag to indicate if the irq is disabled"
>
> You will need to rebase your work on the v4.20-rc1 once it is
> out. Right now the changes are on linux-next or my devel
> branch.

Will do.

>
>> + ngpio = of_irq_count(node);
>> + if (ngpio >= MAX_GPIO) {
>> + dev_err(dev, "Too many GPIO interrupts (max=%d)\n", MAX_GPIO);
>> + return -ENXIO;
>> + }
> (...)
>> + for (gpio = 0; gpio < ngpio; ++gpio) {
>> + irq = platform_get_irq(pdev, gpio);
>> + if (irq < 0) {
>> + dev_err(dev, "invalid IRQ\n");
>> + gpiochip_remove(&chip->gc);
>> + return -ENODEV;
>> + }
>
> This is an hierarchical IRQ so it should use an hierarchical
> irqdomain.
>
> I am discussing with Thierry to make more generic irq domains
> for hierarchical IRQ GPIOs, until then you have to look at
> gpio-thunderx.c, gpio-uniphier.c or gpio-xgene-sb.c that all
> use hierarchical IRQs.
>

Thanks. I will convert them to hierarchical IRQ.

Regards,
Atish
> Yours,
> Linus Walleij
>




2018-10-17 15:58:57

by Rob Herring (Arm)

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On Tue, Oct 16, 2018 at 03:20:34PM -0700, Atish Patra wrote:
> On 10/16/18 3:04 PM, Thierry Reding wrote:
> > On Tue, Oct 16, 2018 at 10:31:42AM -0700, Paul Walmsley wrote:
> > >
> > > On 10/16/18 4:01 AM, Thierry Reding wrote:
> > > > On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
> > > > > On 10/10/18 6:49 AM, Thierry Reding wrote:
> > > > > > On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
> > > > > > > +Required properties:
> > > > > > > +- compatible: should be one of
> > > > > > > + "sifive,fu540-c000-pwm0","sifive,pwm0".
> > > > > > What's the '0' in here? A version number?
> > > > > >
> > > > > I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
> > > > > decided mark it as version 0.
> > > > >
> > > > > @Wesly: Please correct me if I am wrong.
> > > > It seems fairly superfluous to me to have a version number in additon to
> > > > the fu540-c000, which already seems to be the core plus some sort of
> > > > part number. Do you really expect there to be any changes in the SoC
> > > > that would require a different compatible string at this point? If the
> > > > SoC has taped out, how will you ever get a different version of the PWM
> > > > IP in it?
> > > >
> > > > I would expect any improvements or changes to the PWM IP to show up in a
> > > > different SoC generation, at which point it would be something like
> > > > "sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
> > > > the numbering is.
> > >
> > >
> > > The "0" suffix refers to a revision number for the underlying PWM IP block.
> > >
> > > It's certainly important to keep that version number on the "sifive,pwm0"
> > > compatible string that doesn't have the chip name associated with it.
> >
> > Isn't the hardware identified by "sifive,pwm0" and "sifive,fu540-c000"
> > effectively identical?
>
> Yes.
>
> Is there a need to have two compatible strings
> > that refer to the exact same hardware?
> >
>
> The DT in the hardware has only sifive,pwm0. I have added
> "sifive,fu540-c000" as that was concluded as the correct compatible string
> from platform level interrupt controller patch(PLIC) discussion.
>
> (http://lists.infradead.org/pipermail/linux-riscv/2018-August/001135.html)
>
> "sifive,pwm0" is required to until all the Unleashed SoC gets an updated
> firmware with correct compatible string "sifive,fu540-c000". I agree this is
> a mess. But we have to carry it until all every DT(corresponding to each
> driver) is finalized. I guess SiFive will release a firmware update that
> contains all the updated DT once that is done. We can get rid of all the
> redundant compatible strings at that time.

I don't want to repeat compatible string discussions on each and every
IP block. I already have to do this with some vendors.

The RiscV vendors' needs and design flow are a bit different from
traditional SoC vendors AIUI for the last discussion. If you need to do
something that doesn't follow normal conventions, that's fine. Just
please document a convention that works for you. This should explain
where the '0' above comes from for example. And I'm not a fan of s/w
folks making up version numbers.

Rob

2018-10-17 21:46:52

by Atish Patra

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.

On 10/17/18 8:58 AM, Rob Herring wrote:
> On Tue, Oct 16, 2018 at 03:20:34PM -0700, Atish Patra wrote:
>> On 10/16/18 3:04 PM, Thierry Reding wrote:
>>> On Tue, Oct 16, 2018 at 10:31:42AM -0700, Paul Walmsley wrote:
>>>>
>>>> On 10/16/18 4:01 AM, Thierry Reding wrote:
>>>>> On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
>>>>>> On 10/10/18 6:49 AM, Thierry Reding wrote:
>>>>>>> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
>>>>>>>> +Required properties:
>>>>>>>> +- compatible: should be one of
>>>>>>>> + "sifive,fu540-c000-pwm0","sifive,pwm0".
>>>>>>> What's the '0' in here? A version number?
>>>>>>>
>>>>>> I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
>>>>>> decided mark it as version 0.
>>>>>>
>>>>>> @Wesly: Please correct me if I am wrong.
>>>>> It seems fairly superfluous to me to have a version number in additon to
>>>>> the fu540-c000, which already seems to be the core plus some sort of
>>>>> part number. Do you really expect there to be any changes in the SoC
>>>>> that would require a different compatible string at this point? If the
>>>>> SoC has taped out, how will you ever get a different version of the PWM
>>>>> IP in it?
>>>>>
>>>>> I would expect any improvements or changes to the PWM IP to show up in a
>>>>> different SoC generation, at which point it would be something like
>>>>> "sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
>>>>> the numbering is.
>>>>
>>>>
>>>> The "0" suffix refers to a revision number for the underlying PWM IP block.
>>>>
>>>> It's certainly important to keep that version number on the "sifive,pwm0"
>>>> compatible string that doesn't have the chip name associated with it.
>>>
>>> Isn't the hardware identified by "sifive,pwm0" and "sifive,fu540-c000"
>>> effectively identical?
>>
>> Yes.
>>
>> Is there a need to have two compatible strings
>>> that refer to the exact same hardware?
>>>
>>
>> The DT in the hardware has only sifive,pwm0. I have added
>> "sifive,fu540-c000" as that was concluded as the correct compatible string
>> from platform level interrupt controller patch(PLIC) discussion.
>>
>> (http://lists.infradead.org/pipermail/linux-riscv/2018-August/001135.html)
>>
>> "sifive,pwm0" is required to until all the Unleashed SoC gets an updated
>> firmware with correct compatible string "sifive,fu540-c000". I agree this is
>> a mess. But we have to carry it until all every DT(corresponding to each
>> driver) is finalized. I guess SiFive will release a firmware update that
>> contains all the updated DT once that is done. We can get rid of all the
>> redundant compatible strings at that time.
>
> I don't want to repeat compatible string discussions on each and every
> IP block. I already have to do this with some vendors.
>



> The RiscV vendors' needs and design flow are a bit different from
> traditional SoC vendors AIUI for the last discussion. If you need to do
> something that doesn't follow normal conventions, that's fine. Just
> please document a convention that works for you. This should explain
> where the '0' above comes from for example. And I'm not a fan of s/w
> folks making up version numbers.
> Sorry for bringing up the same discussion. My aim was just to reiterate
the suggestion you made on the other other thread (i.e. PLIC compatible
strings) and use the same format used in PLIC block. As these IP
blocks(pwm & gpio) are also from SiFive for the same Soc (HiFive
Unleashed board), I was just trying to clarify that this driver also
follows the exact same convention adopted for PLIC IP block.

Regards,
Atish

> Rob
>


2018-11-10 05:40:49

by Paul Walmsley

[permalink] [raw]
Subject: Re: [RFC 1/4] pwm: sifive: Add DT documentation for SiFive PWM Controller.


On 10/16/18 3:04 PM, Thierry Reding wrote:
> On Tue, Oct 16, 2018 at 10:31:42AM -0700, Paul Walmsley wrote:
>> On 10/16/18 4:01 AM, Thierry Reding wrote:
>>> On Mon, Oct 15, 2018 at 03:57:35PM -0700, Atish Patra wrote:
>>>> On 10/10/18 6:49 AM, Thierry Reding wrote:
>>>>> On Tue, Oct 09, 2018 at 11:51:22AM -0700, Atish Patra wrote:
>>>>>> +Required properties:
>>>>>> +- compatible: should be one of
>>>>>> + "sifive,fu540-c000-pwm0","sifive,pwm0".
>>>>> What's the '0' in here? A version number?
>>>>>
>>>> I think yes. Since fu540 is the first Linux capable RISC-V core, SiFive Guys
>>>> decided mark it as version 0.
>>>>
>>>> @Wesly: Please correct me if I am wrong.
>>> It seems fairly superfluous to me to have a version number in additon to
>>> the fu540-c000, which already seems to be the core plus some sort of
>>> part number. Do you really expect there to be any changes in the SoC
>>> that would require a different compatible string at this point? If the
>>> SoC has taped out, how will you ever get a different version of the PWM
>>> IP in it?
>>>
>>> I would expect any improvements or changes to the PWM IP to show up in a
>>> different SoC generation, at which point it would be something like
>>> "sifive,fu640-c000" maybe, or perhaps "sifive,fu540-d000", or whatever
>>> the numbering is.
>>
>> The "0" suffix refers to a revision number for the underlying PWM IP block.
>>
>> It's certainly important to keep that version number on the "sifive,pwm0"
>> compatible string that doesn't have the chip name associated with it.
> Isn't the hardware identified by "sifive,pwm0" and "sifive,fu540-c000"
> effectively identical?


The intention was that the "sifive,pwm0" compatible string specifies a
register interface and programming model that the IP block exposes to
the software, rather than a particular underlying hardware
implementation.  That is in contrast to a string like
"sifive,fu540-c000-pwm" which might activate particular workarounds or
quirks that are specific to the integration of the IP block on a given SoC.


The idea is that, for this and similar open-source hardware IP blocks,
the driver code can just match on a generic "sifive,pwm0" compatible
string.  The SoC DT data would include both the SoC-specific
"sifive,fu540-c000-pwm0" and the common interface "sifive,pwm0".  But
the driver would only need the SoC-specific compatible string if the SoC
wound up needing some SoC-specific quirks.


In the past, some folks have had a problem with that idea, since for
closed-source IP blocks, it's been difficult to determine what changes
went into a specific version of the IP block.  Thus folks generating
data for later SoCs usually specify a compatible string for another,
older, SoC that seems to have the desired behavior.  But since this
particular IP block has open-source RTL, and contains a "sifive,pwmX"
version string in the RTL itself:


https://github.com/sifive/sifive-blocks/blob/master/src/main/scala/devices/pwm/PWM.scala#L74


... it's straightforward to see what interface the hardware exposes to
the software for a given compatible string.


> Is there a need to have two compatible strings
> that refer to the exact same hardware?


There's no intention that "sifive,pwm0" and "sifive,fu540-c000-pwm0"
refer to the same hardware; just the same software interface and
programming model.  Even now, it's usually pretty unlikely that two
different SoCs that refer to (say) "nvidia,tegra20-pwm" contain the same
hardware, since differences in synthesis, place and route, ECOs, and
integration change the actual realization of the hardware.  Some folks
interpreted that compatible string reuse as implying the same "hardware"
is in use on both SoCs, but we're really just identifying a software
interface.


>> As to whether there could ever be a FU540-C000 part with different IP block
>> versions on it: FU540-C000 is ultimately a marketing name.  While
>> theoretically we shouldn't have another "FU540-C000" chip with different
>> peripheral IP block versions on it, I don't think any engineer can guarantee
>> that it won't happen.
> I would argue that if at some point there was indeed a chip with the
> same name but a different IP block version in it, we can figure out what
> to call it. Sure there are no guarantees, but it's still fairly unlikely
> in my opinion, so I personally wouldn't worry about this up front.
>
> Anyway, I don't feel strongly either way, I'm just pointing out that
> this is somewhat unusual. If you want to keep it, feel free to.


Thanks for the review, Thierry -


- Paul


2019-09-18 11:50:43

by Bin Meng

[permalink] [raw]
Subject: Re: [RFC 4/4] gpio: sifive: Add GPIO driver for SiFive SoCs

Hi,

On Wed, Oct 17, 2018 at 9:01 AM Atish Patra <[email protected]> wrote:
>
> On 10/10/18 5:35 AM, Linus Walleij wrote:
> > Hi Atish,
> >
> > thanks for your patch!
> >
> > On Tue, Oct 9, 2018 at 8:51 PM Atish Patra <[email protected]> wrote:
> >
> >> From: "Wesley W. Terpstra" <[email protected]>
> >>
> >> Adds the GPIO driver for SiFive RISC-V SoCs.
> >>
> >> Signed-off-by: Wesley W. Terpstra <[email protected]>
> >> [Atish: Various fixes and code cleanup]
> >> Signed-off-by: Atish Patra <[email protected]>
> >
> > (...)
> >
> >> +config GPIO_SIFIVE
> >> + bool "SiFive GPIO support"
> >> + depends on OF_GPIO
> >> + select GPIOLIB_IRQCHIP
> >
> > I suggest to add
> > select GPIO_GENERIC as per below.
> >
> > Maybe select REGMAP_MMIO as well.
>
> ok.
>
> >
> >> + help
> >> + Say yes here to support the GPIO device on SiFive SoCs.
> >> +
> >
> >> +#include <linux/of_irq.h>
> >> +#include <linux/irqchip/chained_irq.h>
> >
> > Do you need these two? I think <linux/gpio/driver.h>
> > will bring them in for you.
> >
>
> driver.h only brings chained_irq.h. of_irq.h is still required. Right ?
>
> >> +#include <linux/pinctrl/consumer.h>
> >
> > Are you using this?
>
> My bad. Left over from the old code. I will remove it.
>
> >
> >> +struct sifive_gpio {
> >> + raw_spinlock_t lock;
> >> + void __iomem *base;
> >> + struct gpio_chip gc;
> >> + unsigned long enabled;
> >
> > Since max GPIO is 32 why not use an u32 for this?
> >
>
> Sure.
>
> >> + unsigned int trigger[MAX_GPIO];
> >> + unsigned int irq_parent[MAX_GPIO];
> >> + struct sifive_gpio *self_ptr[MAX_GPIO];
> >> +};
> >> +
> >> +static void sifive_assign_bit(void __iomem *ptr, unsigned int offset, int value)
> >> +{
> >> + /*
> >> + * It's frustrating that we are not allowed to use the device atomics
> >> + * which are GUARANTEED to be supported by this device on RISC-V
> >> + */
> >> + u32 bit = BIT(offset), old = ioread32(ptr);
> >> +
> >> + if (value)
> >> + iowrite32(old | bit, ptr);
> >> + else
> >> + iowrite32(old & ~bit, ptr);
> >> +}
> >
> > This looks like a mask and set implementation, you are
> > essentially reinventing regmap MMIO and the
> > regmap_update_bits() call. Could you look into
> > just using regmap MMIO in that case?
> >
> > If you need examples, look at gpio-mvebu.c that calls
> > devm_regmap_init_mmio() for example.
> >
>
> That's really cool. Sorry, for not checking that earlier.
> I am pretty new to this.
>
> >> +static int sifive_direction_input(struct gpio_chip *gc, unsigned int offset)
> >> +static int sifive_direction_output(struct gpio_chip *gc, unsigned int offset,
> >> +static int sifive_get_direction(struct gpio_chip *gc, unsigned int offset)
> >> +static int sifive_get_value(struct gpio_chip *gc, unsigned int offset)
> >> +static void sifive_set_value(struct gpio_chip *gc, unsigned int offset,
> >
> > These functions look like a typical hardware that can use
> >
> > GPIOLIB_GENERIC and bgpio_init() to set up the accessors.
> >
> > See gpio-ftgpio010.c for an example.
> >
> > As a bonus you will get .get/.set_multiple implemented by
> > the generic GPIO.
> >
>
> Great. This will reduce the driver a code by a big factor.
> Thanks for the pointer.
>
>
> >> +static void sifive_irq_enable(struct irq_data *d)
> >> +static void sifive_irq_disable(struct irq_data *d)
> > (...)
> >> +static struct irq_chip sifive_irqchip = {
> >> + .name = "sifive-gpio",
> >> + .irq_set_type = sifive_irq_set_type,
> >> + .irq_mask = sifive_irq_mask,
> >> + .irq_unmask = sifive_irq_unmask,
> >> + .irq_enable = sifive_irq_enable,
> >> + .irq_disable = sifive_irq_disable,
> >
> > The handling of .irq_enable and .irq_disable has
> > changed upstream. Please align with the new codebase
> > as changed by Hans Verkuil:
> >
> > commit 461c1a7d4733d1dfd5c47b040cf32a5e7eefbc6c
> > "gpiolib: override irq_enable/disable"
> > commit 4e9439ddacea06f35acce4d374bf6bd0acf99bc8
> > "gpiolib: add flag to indicate if the irq is disabled"
> >
> > You will need to rebase your work on the v4.20-rc1 once it is
> > out. Right now the changes are on linux-next or my devel
> > branch.
>
> Will do.
>
> >
> >> + ngpio = of_irq_count(node);
> >> + if (ngpio >= MAX_GPIO) {
> >> + dev_err(dev, "Too many GPIO interrupts (max=%d)\n", MAX_GPIO);
> >> + return -ENXIO;
> >> + }
> > (...)
> >> + for (gpio = 0; gpio < ngpio; ++gpio) {
> >> + irq = platform_get_irq(pdev, gpio);
> >> + if (irq < 0) {
> >> + dev_err(dev, "invalid IRQ\n");
> >> + gpiochip_remove(&chip->gc);
> >> + return -ENODEV;
> >> + }
> >
> > This is an hierarchical IRQ so it should use an hierarchical
> > irqdomain.
> >
> > I am discussing with Thierry to make more generic irq domains
> > for hierarchical IRQ GPIOs, until then you have to look at
> > gpio-thunderx.c, gpio-uniphier.c or gpio-xgene-sb.c that all
> > use hierarchical IRQs.
> >
>
> Thanks. I will convert them to hierarchical IRQ.
>

When will this series get respun and upstreamed?

Regards,
Bin