* [PATCH v6 1/3] regmap: add generic macro to define regmap_irq
@ 2015-09-14 16:39 Qipeng Zha
2015-09-14 16:39 ` [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC Qipeng Zha
` (4 more replies)
0 siblings, 5 replies; 14+ messages in thread
From: Qipeng Zha @ 2015-09-14 16:39 UTC (permalink / raw)
To: linux-kernel; +Cc: broonie, lee.jones, samuel.ortiz, qipeng.zha
Add REGMAP_IRQ_REG macro in regmap.h to define regmap_irq
structure easily for other driver module.
Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
---
include/linux/regmap.h | 3 +++
1 file changed, 3 insertions(+)
diff --git a/include/linux/regmap.h b/include/linux/regmap.h
index 116655d..0d1ee0a 100644
--- a/include/linux/regmap.h
+++ b/include/linux/regmap.h
@@ -517,6 +517,9 @@ struct regmap_irq {
unsigned int mask;
};
+#define REGMAP_IRQ_REG(_irq, _off, _mask) \
+ [_irq] = { .reg_offset = (_off), .mask = (_mask) }
+
/**
* Description of a generic regmap irq_chip. This is not intended to
* handle every possible interrupt controller, but it should handle a
--
1.8.3.2
^ permalink raw reply related [flat|nested] 14+ messages in thread
* [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC
2015-09-14 16:39 [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Qipeng Zha
@ 2015-09-14 16:39 ` Qipeng Zha
2015-09-20 4:18 ` Lee Jones
2015-09-22 22:05 ` Lee Jones
2015-09-14 16:39 ` [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver Qipeng Zha
` (3 subsequent siblings)
4 siblings, 2 replies; 14+ messages in thread
From: Qipeng Zha @ 2015-09-14 16:39 UTC (permalink / raw)
To: linux-kernel; +Cc: broonie, lee.jones, samuel.ortiz, qipeng.zha
IRQ control registers of Intel Broxton Whisky Cove PMIC are
separated in two parts, so add secondary IRQ chip.
And the new member of device will be used in PMC IPC regmap APIs.
Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
---
include/linux/mfd/intel_soc_pmic.h | 2 ++
1 file changed, 2 insertions(+)
diff --git a/include/linux/mfd/intel_soc_pmic.h b/include/linux/mfd/intel_soc_pmic.h
index abcbfcf..cf619db 100644
--- a/include/linux/mfd/intel_soc_pmic.h
+++ b/include/linux/mfd/intel_soc_pmic.h
@@ -25,6 +25,8 @@ struct intel_soc_pmic {
int irq;
struct regmap *regmap;
struct regmap_irq_chip_data *irq_chip_data;
+ struct regmap_irq_chip_data *irq_chip_data_level2;
+ struct device *dev;
};
#endif /* __INTEL_SOC_PMIC_H__ */
--
1.8.3.2
^ permalink raw reply related [flat|nested] 14+ messages in thread
* [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver
2015-09-14 16:39 [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Qipeng Zha
2015-09-14 16:39 ` [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC Qipeng Zha
@ 2015-09-14 16:39 ` Qipeng Zha
2015-09-20 4:18 ` Lee Jones
2015-09-22 22:05 ` Lee Jones
2015-09-19 18:22 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Mark Brown
` (2 subsequent siblings)
4 siblings, 2 replies; 14+ messages in thread
From: Qipeng Zha @ 2015-09-14 16:39 UTC (permalink / raw)
To: linux-kernel; +Cc: broonie, lee.jones, samuel.ortiz, qipeng.zha
Add MFD core driver for Intel Broxton Whiskey Cove PMIC,
which is specially accessed by hardware IPC, not a generic
I2C device
Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
---
change in v6
Replace INIT_REGMAP_IRQ with REGMAP_IRQ_REG.
change in v5
Fix issues in code style, espcially make error messages readable;
Put regmap_irq macro in header file and separate into two patch;
Use DEFFINE_RES_IRQ to define irq resource;
Remove default_i2c_addr and use macro directly;
Change platform driver name to make it more readable;
change in v4
Add compile dependency to PMC IPC driver in Makefile, or will
use NULL stubs defined in PMC IPC header file;
change in v3
Implement ipc regmap r/w callback in pmic driver, since there dropped
before patch of implement virtual ipc support in regmap core;
Update some function's comment;
---
drivers/mfd/Makefile | 1 +
drivers/mfd/intel_soc_pmic_bxtwc.c | 478 +++++++++++++++++++++++++++++++++++++
include/linux/mfd/intel_bxtwc.h | 69 ++++++
3 files changed, 548 insertions(+)
create mode 100644 drivers/mfd/intel_soc_pmic_bxtwc.c
create mode 100644 include/linux/mfd/intel_bxtwc.h
diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index 0e5cfeb..8fc894e 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -183,5 +183,6 @@ obj-$(CONFIG_MFD_RT5033) += rt5033.o
obj-$(CONFIG_MFD_SKY81452) += sky81452.o
intel-soc-pmic-objs := intel_soc_pmic_core.o intel_soc_pmic_crc.o
+intel-soc-pmic-$(CONFIG_INTEL_PMC_IPC) += intel_soc_pmic_bxtwc.o
obj-$(CONFIG_INTEL_SOC_PMIC) += intel-soc-pmic.o
obj-$(CONFIG_MFD_MT6397) += mt6397-core.o
diff --git a/drivers/mfd/intel_soc_pmic_bxtwc.c b/drivers/mfd/intel_soc_pmic_bxtwc.c
new file mode 100644
index 0000000..40acaff
--- /dev/null
+++ b/drivers/mfd/intel_soc_pmic_bxtwc.c
@@ -0,0 +1,478 @@
+/*
+ * MFD core driver for Intel Broxton Whiskey Cove PMIC
+ *
+ * Copyright (C) 2015 Intel Corporation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify it
+ * under the terms and conditions of the GNU General Public License,
+ * version 2, as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope it will be useful, but WITHOUT
+ * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+ * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
+ * more details.
+ */
+
+#include <linux/module.h>
+#include <linux/acpi.h>
+#include <linux/err.h>
+#include <linux/delay.h>
+#include <linux/interrupt.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/intel_bxtwc.h>
+#include <asm/intel_pmc_ipc.h>
+
+/* PMIC device registers */
+#define REG_ADDR_MASK 0xFF00
+#define REG_ADDR_SHIFT 8
+#define REG_OFFSET_MASK 0xFF
+
+/* Interrupt Status Registers */
+#define BXTWC_IRQLVL1 0x4E02
+#define BXTWC_PWRBTNIRQ 0x4E03
+
+#define BXTWC_THRM0IRQ 0x4E04
+#define BXTWC_THRM1IRQ 0x4E05
+#define BXTWC_THRM2IRQ 0x4E06
+#define BXTWC_BCUIRQ 0x4E07
+#define BXTWC_ADCIRQ 0x4E08
+#define BXTWC_CHGR0IRQ 0x4E09
+#define BXTWC_CHGR1IRQ 0x4E0A
+#define BXTWC_GPIOIRQ0 0x4E0B
+#define BXTWC_GPIOIRQ1 0x4E0C
+#define BXTWC_CRITIRQ 0x4E0D
+
+/* Interrupt MASK Registers */
+#define BXTWC_MIRQLVL1 0x4E0E
+#define BXTWC_MPWRTNIRQ 0x4E0F
+
+#define BXTWC_MTHRM0IRQ 0x4E12
+#define BXTWC_MTHRM1IRQ 0x4E13
+#define BXTWC_MTHRM2IRQ 0x4E14
+#define BXTWC_MBCUIRQ 0x4E15
+#define BXTWC_MADCIRQ 0x4E16
+#define BXTWC_MCHGR0IRQ 0x4E17
+#define BXTWC_MCHGR1IRQ 0x4E18
+#define BXTWC_MGPIO0IRQ 0x4E19
+#define BXTWC_MGPIO1IRQ 0x4E1A
+#define BXTWC_MCRITIRQ 0x4E1B
+
+/* Whiskey Cove PMIC share same ACPI ID between different platforms */
+#define BROXTON_PMIC_WC_HRV 4
+
+/* Manage in two IRQ chips since mask registers are not consecutive */
+enum bxtwc_irqs {
+ /* Level 1 */
+ BXTWC_PWRBTN_LVL1_IRQ = 0,
+ BXTWC_TMU_LVL1_IRQ,
+ BXTWC_THRM_LVL1_IRQ,
+ BXTWC_BCU_LVL1_IRQ,
+ BXTWC_ADC_LVL1_IRQ,
+ BXTWC_CHGR_LVL1_IRQ,
+ BXTWC_GPIO_LVL1_IRQ,
+ BXTWC_CRIT_LVL1_IRQ,
+
+ /* Level 2 */
+ BXTWC_PWRBTN_IRQ,
+};
+
+enum bxtwc_irqs_level2 {
+ /* Level 2 */
+ BXTWC_THRM0_IRQ = 0,
+ BXTWC_THRM1_IRQ,
+ BXTWC_THRM2_IRQ,
+ BXTWC_BCU_IRQ,
+ BXTWC_ADC_IRQ,
+ BXTWC_CHGR0_IRQ,
+ BXTWC_CHGR1_IRQ,
+ BXTWC_GPIO0_IRQ,
+ BXTWC_GPIO1_IRQ,
+ BXTWC_CRIT_IRQ,
+};
+
+static const struct regmap_irq bxtwc_regmap_irqs[] = {
+ REGMAP_IRQ_REG(BXTWC_PWRBTN_LVL1_IRQ, 0, BIT(0)),
+ REGMAP_IRQ_REG(BXTWC_TMU_LVL1_IRQ, 0, BIT(1)),
+ REGMAP_IRQ_REG(BXTWC_THRM_LVL1_IRQ, 0, BIT(2)),
+ REGMAP_IRQ_REG(BXTWC_BCU_LVL1_IRQ, 0, BIT(3)),
+ REGMAP_IRQ_REG(BXTWC_ADC_LVL1_IRQ, 0, BIT(4)),
+ REGMAP_IRQ_REG(BXTWC_CHGR_LVL1_IRQ, 0, BIT(5)),
+ REGMAP_IRQ_REG(BXTWC_GPIO_LVL1_IRQ, 0, BIT(6)),
+ REGMAP_IRQ_REG(BXTWC_CRIT_LVL1_IRQ, 0, BIT(7)),
+ REGMAP_IRQ_REG(BXTWC_PWRBTN_IRQ, 1, 0x03),
+};
+
+static const struct regmap_irq bxtwc_regmap_irqs_level2[] = {
+ REGMAP_IRQ_REG(BXTWC_THRM0_IRQ, 0, 0xff),
+ REGMAP_IRQ_REG(BXTWC_THRM1_IRQ, 1, 0xbf),
+ REGMAP_IRQ_REG(BXTWC_THRM2_IRQ, 2, 0xff),
+ REGMAP_IRQ_REG(BXTWC_BCU_IRQ, 3, 0x1f),
+ REGMAP_IRQ_REG(BXTWC_ADC_IRQ, 4, 0xff),
+ REGMAP_IRQ_REG(BXTWC_CHGR0_IRQ, 5, 0x1f),
+ REGMAP_IRQ_REG(BXTWC_CHGR1_IRQ, 6, 0x1f),
+ REGMAP_IRQ_REG(BXTWC_GPIO0_IRQ, 7, 0xff),
+ REGMAP_IRQ_REG(BXTWC_GPIO1_IRQ, 8, 0x3f),
+ REGMAP_IRQ_REG(BXTWC_CRIT_IRQ, 9, 0x03),
+};
+
+static struct regmap_irq_chip bxtwc_regmap_irq_chip = {
+ .name = "bxtwc_irq_chip",
+ .status_base = BXTWC_IRQLVL1,
+ .mask_base = BXTWC_MIRQLVL1,
+ .irqs = bxtwc_regmap_irqs,
+ .num_irqs = ARRAY_SIZE(bxtwc_regmap_irqs),
+ .num_regs = 2,
+};
+
+static struct regmap_irq_chip bxtwc_regmap_irq_chip_level2 = {
+ .name = "bxtwc_irq_chip_level2",
+ .status_base = BXTWC_THRM0IRQ,
+ .mask_base = BXTWC_MTHRM0IRQ,
+ .irqs = bxtwc_regmap_irqs_level2,
+ .num_irqs = ARRAY_SIZE(bxtwc_regmap_irqs_level2),
+ .num_regs = 10,
+};
+
+static struct resource gpio_resources[] = {
+ DEFINE_RES_IRQ_NAMED(BXTWC_GPIO0_IRQ, "GPIO0"),
+ DEFINE_RES_IRQ_NAMED(BXTWC_GPIO1_IRQ, "GPIO1"),
+};
+
+static struct resource adc_resources[] = {
+ DEFINE_RES_IRQ_NAMED(BXTWC_ADC_IRQ, "ADC"),
+};
+
+static struct resource charger_resources[] = {
+ DEFINE_RES_IRQ_NAMED(BXTWC_CHGR0_IRQ, "CHARGER"),
+ DEFINE_RES_IRQ_NAMED(BXTWC_CHGR1_IRQ, "CHARGER1"),
+};
+
+static struct resource thermal_resources[] = {
+ DEFINE_RES_IRQ(BXTWC_THRM0_IRQ),
+ DEFINE_RES_IRQ(BXTWC_THRM1_IRQ),
+ DEFINE_RES_IRQ(BXTWC_THRM2_IRQ),
+};
+
+static struct resource bcu_resources[] = {
+ DEFINE_RES_IRQ_NAMED(BXTWC_BCU_IRQ, "BCU"),
+};
+
+static struct mfd_cell bxt_wc_dev[] = {
+ {
+ .name = "bxt_wcove_gpadc",
+ .num_resources = ARRAY_SIZE(adc_resources),
+ .resources = adc_resources,
+ },
+ {
+ .name = "bxt_wcove_thermal",
+ .num_resources = ARRAY_SIZE(thermal_resources),
+ .resources = thermal_resources,
+ },
+ {
+ .name = "bxt_wcove_ext_charger",
+ .num_resources = ARRAY_SIZE(charger_resources),
+ .resources = charger_resources,
+ },
+ {
+ .name = "bxt_wcove_bcu",
+ .num_resources = ARRAY_SIZE(bcu_resources),
+ .resources = bcu_resources,
+ },
+ {
+ .name = "bxt_wcove_gpio",
+ .num_resources = ARRAY_SIZE(gpio_resources),
+ .resources = gpio_resources,
+ },
+ {
+ .name = "bxt_wcove_region",
+ },
+};
+
+static int regmap_ipc_byte_reg_read(void *context, unsigned int reg,
+ unsigned int *val)
+{
+ int ret;
+ int i2c_addr;
+ u8 ipc_in[2];
+ u8 ipc_out[4];
+ struct intel_soc_pmic *pmic = context;
+
+ if (reg & REG_ADDR_MASK)
+ i2c_addr = (reg & REG_ADDR_MASK) >> REG_ADDR_SHIFT;
+ else {
+ i2c_addr = BXTWC_DEVICE1_ADDR;
+ if (!i2c_addr) {
+ dev_err(pmic->dev, "I2C address not set\n");
+ return -EINVAL;
+ }
+ }
+ reg &= REG_OFFSET_MASK;
+
+ ipc_in[0] = reg;
+ ipc_in[1] = i2c_addr;
+ ret = intel_pmc_ipc_command(PMC_IPC_PMIC_ACCESS,
+ PMC_IPC_PMIC_ACCESS_READ,
+ ipc_in, sizeof(ipc_in), (u32 *)ipc_out, 1);
+ if (ret) {
+ dev_err(pmic->dev, "Failed to read from PMIC\n");
+ return ret;
+ }
+ *val = ipc_out[0];
+
+ return 0;
+}
+
+static int regmap_ipc_byte_reg_write(void *context, unsigned int reg,
+ unsigned int val)
+{
+ int ret;
+ int i2c_addr;
+ u8 ipc_in[3];
+ struct intel_soc_pmic *pmic = context;
+
+ if (reg & REG_ADDR_MASK)
+ i2c_addr = (reg & REG_ADDR_MASK) >> REG_ADDR_SHIFT;
+ else {
+ i2c_addr = BXTWC_DEVICE1_ADDR;
+ if (!i2c_addr) {
+ dev_err(pmic->dev, "I2C address not set\n");
+ return -EINVAL;
+ }
+ }
+ reg &= REG_OFFSET_MASK;
+
+ ipc_in[0] = reg;
+ ipc_in[1] = i2c_addr;
+ ipc_in[2] = val;
+ ret = intel_pmc_ipc_command(PMC_IPC_PMIC_ACCESS,
+ PMC_IPC_PMIC_ACCESS_WRITE,
+ ipc_in, sizeof(ipc_in), NULL, 0);
+ if (ret) {
+ dev_err(pmic->dev, "Failed to write to PMIC\n");
+ return ret;
+ }
+
+ return 0;
+}
+
+/* sysfs interfaces to r/w PMIC registers, required by initial script */
+static unsigned long bxtwc_reg_addr;
+static ssize_t bxtwc_reg_show(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "0x%lx\n", bxtwc_reg_addr);
+}
+
+static ssize_t bxtwc_reg_store(struct device *dev,
+ struct device_attribute *attr, const char *buf, size_t count)
+{
+ if (kstrtoul(buf, 0, &bxtwc_reg_addr)) {
+ dev_err(dev, "Invalid register address\n");
+ return -EINVAL;
+ }
+ return (ssize_t)count;
+}
+
+static ssize_t bxtwc_val_show(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ int ret;
+ unsigned int val;
+ struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
+
+ ret = regmap_read(pmic->regmap, bxtwc_reg_addr, &val);
+ if (ret < 0) {
+ dev_err(dev, "Failed to read 0x%lx\n", bxtwc_reg_addr);
+ return -EIO;
+ }
+
+ return sprintf(buf, "0x%02x\n", val);
+}
+
+static ssize_t bxtwc_val_store(struct device *dev,
+ struct device_attribute *attr, const char *buf, size_t count)
+{
+ int ret;
+ unsigned int val;
+ struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
+
+ if (kstrtoul(buf, 0, (unsigned long *)&val)) {
+ dev_err(dev, "Invalid register value\n");
+ return -EINVAL;
+ }
+
+ ret = regmap_write(pmic->regmap, bxtwc_reg_addr, val);
+ if (ret) {
+ dev_err(dev, "Failed to write value 0x%02x to address 0x%lx",
+ val, bxtwc_reg_addr);
+ return -EIO;
+ }
+ return count;
+}
+
+static DEVICE_ATTR(addr, S_IWUSR | S_IRUSR, bxtwc_reg_show, bxtwc_reg_store);
+static DEVICE_ATTR(val, S_IWUSR | S_IRUSR, bxtwc_val_show, bxtwc_val_store);
+static struct attribute *bxtwc_attrs[] = {
+ &dev_attr_addr.attr,
+ &dev_attr_val.attr,
+ NULL
+};
+
+static const struct attribute_group bxtwc_group = {
+ .attrs = bxtwc_attrs,
+};
+
+static const struct regmap_config bxtwc_regmap_config = {
+ .reg_bits = 16,
+ .val_bits = 8,
+ .reg_write = regmap_ipc_byte_reg_write,
+ .reg_read = regmap_ipc_byte_reg_read,
+};
+
+static int bxtwc_probe(struct platform_device *pdev)
+{
+ int ret;
+ acpi_handle handle;
+ acpi_status status;
+ unsigned long long hrv;
+ struct intel_soc_pmic *pmic;
+
+ handle = ACPI_HANDLE(&pdev->dev);
+ status = acpi_evaluate_integer(handle, "_HRV", NULL, &hrv);
+ if (ACPI_FAILURE(status)) {
+ dev_err(&pdev->dev, "Failed to get PMIC hardware revision\n");
+ return -ENODEV;
+ }
+ if (hrv != BROXTON_PMIC_WC_HRV) {
+ dev_err(&pdev->dev, "Invalid PMIC hardware revision: %llu\n",
+ hrv);
+ return -ENODEV;
+ }
+
+ pmic = devm_kzalloc(&pdev->dev, sizeof(*pmic), GFP_KERNEL);
+ if (!pmic)
+ return -ENOMEM;
+
+ ret = platform_get_irq(pdev, 0);
+ if (ret < 0) {
+ dev_err(&pdev->dev, "Invalid IRQ\n");
+ return ret;
+ }
+ pmic->irq = ret;
+
+ dev_set_drvdata(&pdev->dev, pmic);
+ pmic->dev = &pdev->dev;
+
+ pmic->regmap = devm_regmap_init(&pdev->dev, NULL, pmic,
+ &bxtwc_regmap_config);
+ if (IS_ERR(pmic->regmap)) {
+ ret = PTR_ERR(pmic->regmap);
+ dev_err(&pdev->dev, "Failed to initialise regmap: %d\n", ret);
+ return ret;
+ }
+
+ ret = regmap_add_irq_chip(pmic->regmap, pmic->irq,
+ IRQF_ONESHOT | IRQF_SHARED,
+ 0, &bxtwc_regmap_irq_chip,
+ &pmic->irq_chip_data);
+ if (ret) {
+ dev_err(&pdev->dev, "Failed to add IRQ chip\n");
+ return ret;
+ }
+
+ ret = regmap_add_irq_chip(pmic->regmap, pmic->irq,
+ IRQF_ONESHOT | IRQF_SHARED,
+ 0, &bxtwc_regmap_irq_chip_level2,
+ &pmic->irq_chip_data_level2);
+ if (ret) {
+ dev_err(&pdev->dev, "Failed to add secondary IRQ chip\n");
+ goto err_irq_chip_level2;
+ }
+
+ ret = mfd_add_devices(&pdev->dev, PLATFORM_DEVID_NONE, bxt_wc_dev,
+ ARRAY_SIZE(bxt_wc_dev), NULL, 0,
+ NULL);
+ if (ret) {
+ dev_err(&pdev->dev, "Failed to add devices\n");
+ goto err_mfd;
+ }
+
+ ret = sysfs_create_group(&pdev->dev.kobj, &bxtwc_group);
+ if (ret) {
+ dev_err(&pdev->dev, "Failed to create sysfs group %d\n", ret);
+ goto err_sysfs;
+ }
+
+ return 0;
+
+err_sysfs:
+ mfd_remove_devices(&pdev->dev);
+err_mfd:
+ regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data_level2);
+err_irq_chip_level2:
+ regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data);
+
+ return ret;
+}
+
+static int bxtwc_remove(struct platform_device *pdev)
+{
+ struct intel_soc_pmic *pmic = dev_get_drvdata(&pdev->dev);
+
+ sysfs_remove_group(&pdev->dev.kobj, &bxtwc_group);
+ mfd_remove_devices(&pdev->dev);
+ regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data);
+ regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data_level2);
+
+ return 0;
+}
+
+static void bxtwc_shutdown(struct platform_device *pdev)
+{
+ struct intel_soc_pmic *pmic = dev_get_drvdata(&pdev->dev);
+
+ disable_irq(pmic->irq);
+}
+
+#ifdef CONFIG_PM_SLEEP
+static int bxtwc_suspend(struct device *dev)
+{
+ struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
+
+ disable_irq(pmic->irq);
+
+ return 0;
+}
+
+static int bxtwc_resume(struct device *dev)
+{
+ struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
+
+ enable_irq(pmic->irq);
+ return 0;
+}
+#endif
+static SIMPLE_DEV_PM_OPS(bxtwc_pm_ops, bxtwc_suspend, bxtwc_resume);
+
+static const struct acpi_device_id bxtwc_acpi_ids[] = {
+ { "INT34D3", },
+ { }
+};
+MODULE_DEVICE_TABLE(acpi, pmic_acpi_ids);
+
+static struct platform_driver bxtwc_driver = {
+ .probe = bxtwc_probe,
+ .remove = bxtwc_remove,
+ .shutdown = bxtwc_shutdown,
+ .driver = {
+ .name = "BXTWC PMIC",
+ .pm = &bxtwc_pm_ops,
+ .acpi_match_table = ACPI_PTR(bxtwc_acpi_ids),
+ },
+};
+
+module_platform_driver(bxtwc_driver);
+
+MODULE_LICENSE("GPL v2");
+MODULE_AUTHOR("Qipeng Zha<qipeng.zha@intel.com>");
diff --git a/include/linux/mfd/intel_bxtwc.h b/include/linux/mfd/intel_bxtwc.h
new file mode 100644
index 0000000..1a0ee9d
--- /dev/null
+++ b/include/linux/mfd/intel_bxtwc.h
@@ -0,0 +1,69 @@
+/*
+ * intel_bxtwc.h - Header file for Intel Broxton Whiskey Cove PMIC
+ *
+ * Copyright (C) 2015 Intel Corporation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify it
+ * under the terms and conditions of the GNU General Public License,
+ * version 2, as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope it will be useful, but WITHOUT
+ * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+ * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
+ * more details.
+ */
+
+#include <linux/mfd/intel_soc_pmic.h>
+
+#ifndef __INTEL_BXTWC_H__
+#define __INTEL_BXTWC_H__
+
+/* BXT WC devices */
+#define BXTWC_DEVICE1_ADDR 0x4E
+#define BXTWC_DEVICE2_ADDR 0x4F
+#define BXTWC_DEVICE3_ADDR 0x5E
+
+/* device1 Registers */
+#define BXTWC_CHIPID 0x4E00
+#define BXTWC_CHIPVER 0x4E01
+
+#define BXTWC_SCHGRIRQ0_ADDR 0x5E1A
+#define BXTWC_CHGRCTRL0_ADDR 0x5E16
+#define BXTWC_CHGRCTRL1_ADDR 0x5E17
+#define BXTWC_CHGRCTRL2_ADDR 0x5E18
+#define BXTWC_CHGRSTATUS_ADDR 0x5E19
+#define BXTWC_THRMBATZONE_ADDR 0x4F22
+
+#define BXTWC_USBPATH_ADDR 0x5E19
+#define BXTWC_USBPHYCTRL_ADDR 0x5E07
+#define BXTWC_USBIDCTRL_ADDR 0x5E05
+#define BXTWC_USBIDEN_MASK 0x01
+#define BXTWC_USBIDSTAT_ADDR 0x00FF
+#define BXTWC_USBSRCDETSTATUS_ADDR 0x5E29
+
+#define BXTWC_DBGUSBBC1_ADDR 0x5FE0
+#define BXTWC_DBGUSBBC2_ADDR 0x5FE1
+#define BXTWC_DBGUSBBCSTAT_ADDR 0x5FE2
+
+#define BXTWC_WAKESRC_ADDR 0x4E22
+#define BXTWC_WAKESRC2_ADDR 0x4EE5
+#define BXTWC_CHRTTADDR_ADDR 0x5E22
+#define BXTWC_CHRTTDATA_ADDR 0x5E23
+
+#define BXTWC_STHRMIRQ0_ADDR 0x4F19
+#define WC_MTHRMIRQ1_ADDR 0x4E12
+#define WC_STHRMIRQ1_ADDR 0x4F1A
+#define WC_STHRMIRQ2_ADDR 0x4F1B
+
+#define BXTWC_THRMZN0H_ADDR 0x4F44
+#define BXTWC_THRMZN0L_ADDR 0x4F45
+#define BXTWC_THRMZN1H_ADDR 0x4F46
+#define BXTWC_THRMZN1L_ADDR 0x4F47
+#define BXTWC_THRMZN2H_ADDR 0x4F48
+#define BXTWC_THRMZN2L_ADDR 0x4F49
+#define BXTWC_THRMZN3H_ADDR 0x4F4A
+#define BXTWC_THRMZN3L_ADDR 0x4F4B
+#define BXTWC_THRMZN4H_ADDR 0x4F4C
+#define BXTWC_THRMZN4L_ADDR 0x4F4D
+
+#endif
--
1.8.3.2
^ permalink raw reply related [flat|nested] 14+ messages in thread
* Re: [PATCH v6 1/3] regmap: add generic macro to define regmap_irq
2015-09-14 16:39 [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Qipeng Zha
2015-09-14 16:39 ` [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC Qipeng Zha
2015-09-14 16:39 ` [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver Qipeng Zha
@ 2015-09-19 18:22 ` Mark Brown
2015-09-22 22:04 ` Lee Jones
2015-09-20 4:18 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Lee Jones
2015-09-22 22:04 ` Lee Jones
4 siblings, 1 reply; 14+ messages in thread
From: Mark Brown @ 2015-09-19 18:22 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, lee.jones, samuel.ortiz
[-- Attachment #1: Type: text/plain, Size: 207 bytes --]
On Tue, Sep 15, 2015 at 12:39:17AM +0800, Qipeng Zha wrote:
> Add REGMAP_IRQ_REG macro in regmap.h to define regmap_irq
> structure easily for other driver module.
Acked-by: Mark Brown <broonie@kernel.org>
[-- Attachment #2: Digital signature --]
[-- Type: application/pgp-signature, Size: 473 bytes --]
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver
2015-09-14 16:39 ` [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver Qipeng Zha
@ 2015-09-20 4:18 ` Lee Jones
2015-09-21 1:51 ` Zha, Qipeng
2015-09-22 22:05 ` Lee Jones
1 sibling, 1 reply; 14+ messages in thread
From: Lee Jones @ 2015-09-20 4:18 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, broonie, samuel.ortiz
On Tue, 15 Sep 2015, Qipeng Zha wrote:
> Add MFD core driver for Intel Broxton Whiskey Cove PMIC,
> which is specially accessed by hardware IPC, not a generic
> I2C device
>
> Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
>
> ---
> change in v6
> Replace INIT_REGMAP_IRQ with REGMAP_IRQ_REG.
If that's all that has changed my Ack can carry:
Acked-by: Lee Jones <lee.jones@linaro.org>
Still no Ack for the regmap side though, so still can't apply.
> change in v5
> Fix issues in code style, espcially make error messages readable;
> Put regmap_irq macro in header file and separate into two patch;
> Use DEFFINE_RES_IRQ to define irq resource;
> Remove default_i2c_addr and use macro directly;
> Change platform driver name to make it more readable;
>
> change in v4
> Add compile dependency to PMC IPC driver in Makefile, or will
> use NULL stubs defined in PMC IPC header file;
>
> change in v3
> Implement ipc regmap r/w callback in pmic driver, since there dropped
> before patch of implement virtual ipc support in regmap core;
> Update some function's comment;
> ---
> drivers/mfd/Makefile | 1 +
> drivers/mfd/intel_soc_pmic_bxtwc.c | 478 +++++++++++++++++++++++++++++++++++++
> include/linux/mfd/intel_bxtwc.h | 69 ++++++
> 3 files changed, 548 insertions(+)
> create mode 100644 drivers/mfd/intel_soc_pmic_bxtwc.c
> create mode 100644 include/linux/mfd/intel_bxtwc.h
>
> diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
> index 0e5cfeb..8fc894e 100644
> --- a/drivers/mfd/Makefile
> +++ b/drivers/mfd/Makefile
> @@ -183,5 +183,6 @@ obj-$(CONFIG_MFD_RT5033) += rt5033.o
> obj-$(CONFIG_MFD_SKY81452) += sky81452.o
>
> intel-soc-pmic-objs := intel_soc_pmic_core.o intel_soc_pmic_crc.o
> +intel-soc-pmic-$(CONFIG_INTEL_PMC_IPC) += intel_soc_pmic_bxtwc.o
> obj-$(CONFIG_INTEL_SOC_PMIC) += intel-soc-pmic.o
> obj-$(CONFIG_MFD_MT6397) += mt6397-core.o
> diff --git a/drivers/mfd/intel_soc_pmic_bxtwc.c b/drivers/mfd/intel_soc_pmic_bxtwc.c
> new file mode 100644
> index 0000000..40acaff
> --- /dev/null
> +++ b/drivers/mfd/intel_soc_pmic_bxtwc.c
> @@ -0,0 +1,478 @@
> +/*
> + * MFD core driver for Intel Broxton Whiskey Cove PMIC
> + *
> + * Copyright (C) 2015 Intel Corporation. All rights reserved.
> + *
> + * This program is free software; you can redistribute it and/or modify it
> + * under the terms and conditions of the GNU General Public License,
> + * version 2, as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope it will be useful, but WITHOUT
> + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
> + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
> + * more details.
> + */
> +
> +#include <linux/module.h>
> +#include <linux/acpi.h>
> +#include <linux/err.h>
> +#include <linux/delay.h>
> +#include <linux/interrupt.h>
> +#include <linux/kernel.h>
> +#include <linux/mfd/core.h>
> +#include <linux/mfd/intel_bxtwc.h>
> +#include <asm/intel_pmc_ipc.h>
> +
> +/* PMIC device registers */
> +#define REG_ADDR_MASK 0xFF00
> +#define REG_ADDR_SHIFT 8
> +#define REG_OFFSET_MASK 0xFF
> +
> +/* Interrupt Status Registers */
> +#define BXTWC_IRQLVL1 0x4E02
> +#define BXTWC_PWRBTNIRQ 0x4E03
> +
> +#define BXTWC_THRM0IRQ 0x4E04
> +#define BXTWC_THRM1IRQ 0x4E05
> +#define BXTWC_THRM2IRQ 0x4E06
> +#define BXTWC_BCUIRQ 0x4E07
> +#define BXTWC_ADCIRQ 0x4E08
> +#define BXTWC_CHGR0IRQ 0x4E09
> +#define BXTWC_CHGR1IRQ 0x4E0A
> +#define BXTWC_GPIOIRQ0 0x4E0B
> +#define BXTWC_GPIOIRQ1 0x4E0C
> +#define BXTWC_CRITIRQ 0x4E0D
> +
> +/* Interrupt MASK Registers */
> +#define BXTWC_MIRQLVL1 0x4E0E
> +#define BXTWC_MPWRTNIRQ 0x4E0F
> +
> +#define BXTWC_MTHRM0IRQ 0x4E12
> +#define BXTWC_MTHRM1IRQ 0x4E13
> +#define BXTWC_MTHRM2IRQ 0x4E14
> +#define BXTWC_MBCUIRQ 0x4E15
> +#define BXTWC_MADCIRQ 0x4E16
> +#define BXTWC_MCHGR0IRQ 0x4E17
> +#define BXTWC_MCHGR1IRQ 0x4E18
> +#define BXTWC_MGPIO0IRQ 0x4E19
> +#define BXTWC_MGPIO1IRQ 0x4E1A
> +#define BXTWC_MCRITIRQ 0x4E1B
> +
> +/* Whiskey Cove PMIC share same ACPI ID between different platforms */
> +#define BROXTON_PMIC_WC_HRV 4
> +
> +/* Manage in two IRQ chips since mask registers are not consecutive */
> +enum bxtwc_irqs {
> + /* Level 1 */
> + BXTWC_PWRBTN_LVL1_IRQ = 0,
> + BXTWC_TMU_LVL1_IRQ,
> + BXTWC_THRM_LVL1_IRQ,
> + BXTWC_BCU_LVL1_IRQ,
> + BXTWC_ADC_LVL1_IRQ,
> + BXTWC_CHGR_LVL1_IRQ,
> + BXTWC_GPIO_LVL1_IRQ,
> + BXTWC_CRIT_LVL1_IRQ,
> +
> + /* Level 2 */
> + BXTWC_PWRBTN_IRQ,
> +};
> +
> +enum bxtwc_irqs_level2 {
> + /* Level 2 */
> + BXTWC_THRM0_IRQ = 0,
> + BXTWC_THRM1_IRQ,
> + BXTWC_THRM2_IRQ,
> + BXTWC_BCU_IRQ,
> + BXTWC_ADC_IRQ,
> + BXTWC_CHGR0_IRQ,
> + BXTWC_CHGR1_IRQ,
> + BXTWC_GPIO0_IRQ,
> + BXTWC_GPIO1_IRQ,
> + BXTWC_CRIT_IRQ,
> +};
> +
> +static const struct regmap_irq bxtwc_regmap_irqs[] = {
> + REGMAP_IRQ_REG(BXTWC_PWRBTN_LVL1_IRQ, 0, BIT(0)),
> + REGMAP_IRQ_REG(BXTWC_TMU_LVL1_IRQ, 0, BIT(1)),
> + REGMAP_IRQ_REG(BXTWC_THRM_LVL1_IRQ, 0, BIT(2)),
> + REGMAP_IRQ_REG(BXTWC_BCU_LVL1_IRQ, 0, BIT(3)),
> + REGMAP_IRQ_REG(BXTWC_ADC_LVL1_IRQ, 0, BIT(4)),
> + REGMAP_IRQ_REG(BXTWC_CHGR_LVL1_IRQ, 0, BIT(5)),
> + REGMAP_IRQ_REG(BXTWC_GPIO_LVL1_IRQ, 0, BIT(6)),
> + REGMAP_IRQ_REG(BXTWC_CRIT_LVL1_IRQ, 0, BIT(7)),
> + REGMAP_IRQ_REG(BXTWC_PWRBTN_IRQ, 1, 0x03),
> +};
> +
> +static const struct regmap_irq bxtwc_regmap_irqs_level2[] = {
> + REGMAP_IRQ_REG(BXTWC_THRM0_IRQ, 0, 0xff),
> + REGMAP_IRQ_REG(BXTWC_THRM1_IRQ, 1, 0xbf),
> + REGMAP_IRQ_REG(BXTWC_THRM2_IRQ, 2, 0xff),
> + REGMAP_IRQ_REG(BXTWC_BCU_IRQ, 3, 0x1f),
> + REGMAP_IRQ_REG(BXTWC_ADC_IRQ, 4, 0xff),
> + REGMAP_IRQ_REG(BXTWC_CHGR0_IRQ, 5, 0x1f),
> + REGMAP_IRQ_REG(BXTWC_CHGR1_IRQ, 6, 0x1f),
> + REGMAP_IRQ_REG(BXTWC_GPIO0_IRQ, 7, 0xff),
> + REGMAP_IRQ_REG(BXTWC_GPIO1_IRQ, 8, 0x3f),
> + REGMAP_IRQ_REG(BXTWC_CRIT_IRQ, 9, 0x03),
> +};
> +
> +static struct regmap_irq_chip bxtwc_regmap_irq_chip = {
> + .name = "bxtwc_irq_chip",
> + .status_base = BXTWC_IRQLVL1,
> + .mask_base = BXTWC_MIRQLVL1,
> + .irqs = bxtwc_regmap_irqs,
> + .num_irqs = ARRAY_SIZE(bxtwc_regmap_irqs),
> + .num_regs = 2,
> +};
> +
> +static struct regmap_irq_chip bxtwc_regmap_irq_chip_level2 = {
> + .name = "bxtwc_irq_chip_level2",
> + .status_base = BXTWC_THRM0IRQ,
> + .mask_base = BXTWC_MTHRM0IRQ,
> + .irqs = bxtwc_regmap_irqs_level2,
> + .num_irqs = ARRAY_SIZE(bxtwc_regmap_irqs_level2),
> + .num_regs = 10,
> +};
> +
> +static struct resource gpio_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_GPIO0_IRQ, "GPIO0"),
> + DEFINE_RES_IRQ_NAMED(BXTWC_GPIO1_IRQ, "GPIO1"),
> +};
> +
> +static struct resource adc_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_ADC_IRQ, "ADC"),
> +};
> +
> +static struct resource charger_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_CHGR0_IRQ, "CHARGER"),
> + DEFINE_RES_IRQ_NAMED(BXTWC_CHGR1_IRQ, "CHARGER1"),
> +};
> +
> +static struct resource thermal_resources[] = {
> + DEFINE_RES_IRQ(BXTWC_THRM0_IRQ),
> + DEFINE_RES_IRQ(BXTWC_THRM1_IRQ),
> + DEFINE_RES_IRQ(BXTWC_THRM2_IRQ),
> +};
> +
> +static struct resource bcu_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_BCU_IRQ, "BCU"),
> +};
> +
> +static struct mfd_cell bxt_wc_dev[] = {
> + {
> + .name = "bxt_wcove_gpadc",
> + .num_resources = ARRAY_SIZE(adc_resources),
> + .resources = adc_resources,
> + },
> + {
> + .name = "bxt_wcove_thermal",
> + .num_resources = ARRAY_SIZE(thermal_resources),
> + .resources = thermal_resources,
> + },
> + {
> + .name = "bxt_wcove_ext_charger",
> + .num_resources = ARRAY_SIZE(charger_resources),
> + .resources = charger_resources,
> + },
> + {
> + .name = "bxt_wcove_bcu",
> + .num_resources = ARRAY_SIZE(bcu_resources),
> + .resources = bcu_resources,
> + },
> + {
> + .name = "bxt_wcove_gpio",
> + .num_resources = ARRAY_SIZE(gpio_resources),
> + .resources = gpio_resources,
> + },
> + {
> + .name = "bxt_wcove_region",
> + },
> +};
> +
> +static int regmap_ipc_byte_reg_read(void *context, unsigned int reg,
> + unsigned int *val)
> +{
> + int ret;
> + int i2c_addr;
> + u8 ipc_in[2];
> + u8 ipc_out[4];
> + struct intel_soc_pmic *pmic = context;
> +
> + if (reg & REG_ADDR_MASK)
> + i2c_addr = (reg & REG_ADDR_MASK) >> REG_ADDR_SHIFT;
> + else {
> + i2c_addr = BXTWC_DEVICE1_ADDR;
> + if (!i2c_addr) {
> + dev_err(pmic->dev, "I2C address not set\n");
> + return -EINVAL;
> + }
> + }
> + reg &= REG_OFFSET_MASK;
> +
> + ipc_in[0] = reg;
> + ipc_in[1] = i2c_addr;
> + ret = intel_pmc_ipc_command(PMC_IPC_PMIC_ACCESS,
> + PMC_IPC_PMIC_ACCESS_READ,
> + ipc_in, sizeof(ipc_in), (u32 *)ipc_out, 1);
> + if (ret) {
> + dev_err(pmic->dev, "Failed to read from PMIC\n");
> + return ret;
> + }
> + *val = ipc_out[0];
> +
> + return 0;
> +}
> +
> +static int regmap_ipc_byte_reg_write(void *context, unsigned int reg,
> + unsigned int val)
> +{
> + int ret;
> + int i2c_addr;
> + u8 ipc_in[3];
> + struct intel_soc_pmic *pmic = context;
> +
> + if (reg & REG_ADDR_MASK)
> + i2c_addr = (reg & REG_ADDR_MASK) >> REG_ADDR_SHIFT;
> + else {
> + i2c_addr = BXTWC_DEVICE1_ADDR;
> + if (!i2c_addr) {
> + dev_err(pmic->dev, "I2C address not set\n");
> + return -EINVAL;
> + }
> + }
> + reg &= REG_OFFSET_MASK;
> +
> + ipc_in[0] = reg;
> + ipc_in[1] = i2c_addr;
> + ipc_in[2] = val;
> + ret = intel_pmc_ipc_command(PMC_IPC_PMIC_ACCESS,
> + PMC_IPC_PMIC_ACCESS_WRITE,
> + ipc_in, sizeof(ipc_in), NULL, 0);
> + if (ret) {
> + dev_err(pmic->dev, "Failed to write to PMIC\n");
> + return ret;
> + }
> +
> + return 0;
> +}
> +
> +/* sysfs interfaces to r/w PMIC registers, required by initial script */
> +static unsigned long bxtwc_reg_addr;
> +static ssize_t bxtwc_reg_show(struct device *dev,
> + struct device_attribute *attr, char *buf)
> +{
> + return sprintf(buf, "0x%lx\n", bxtwc_reg_addr);
> +}
> +
> +static ssize_t bxtwc_reg_store(struct device *dev,
> + struct device_attribute *attr, const char *buf, size_t count)
> +{
> + if (kstrtoul(buf, 0, &bxtwc_reg_addr)) {
> + dev_err(dev, "Invalid register address\n");
> + return -EINVAL;
> + }
> + return (ssize_t)count;
> +}
> +
> +static ssize_t bxtwc_val_show(struct device *dev,
> + struct device_attribute *attr, char *buf)
> +{
> + int ret;
> + unsigned int val;
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + ret = regmap_read(pmic->regmap, bxtwc_reg_addr, &val);
> + if (ret < 0) {
> + dev_err(dev, "Failed to read 0x%lx\n", bxtwc_reg_addr);
> + return -EIO;
> + }
> +
> + return sprintf(buf, "0x%02x\n", val);
> +}
> +
> +static ssize_t bxtwc_val_store(struct device *dev,
> + struct device_attribute *attr, const char *buf, size_t count)
> +{
> + int ret;
> + unsigned int val;
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + if (kstrtoul(buf, 0, (unsigned long *)&val)) {
> + dev_err(dev, "Invalid register value\n");
> + return -EINVAL;
> + }
> +
> + ret = regmap_write(pmic->regmap, bxtwc_reg_addr, val);
> + if (ret) {
> + dev_err(dev, "Failed to write value 0x%02x to address 0x%lx",
> + val, bxtwc_reg_addr);
> + return -EIO;
> + }
> + return count;
> +}
> +
> +static DEVICE_ATTR(addr, S_IWUSR | S_IRUSR, bxtwc_reg_show, bxtwc_reg_store);
> +static DEVICE_ATTR(val, S_IWUSR | S_IRUSR, bxtwc_val_show, bxtwc_val_store);
> +static struct attribute *bxtwc_attrs[] = {
> + &dev_attr_addr.attr,
> + &dev_attr_val.attr,
> + NULL
> +};
> +
> +static const struct attribute_group bxtwc_group = {
> + .attrs = bxtwc_attrs,
> +};
> +
> +static const struct regmap_config bxtwc_regmap_config = {
> + .reg_bits = 16,
> + .val_bits = 8,
> + .reg_write = regmap_ipc_byte_reg_write,
> + .reg_read = regmap_ipc_byte_reg_read,
> +};
> +
> +static int bxtwc_probe(struct platform_device *pdev)
> +{
> + int ret;
> + acpi_handle handle;
> + acpi_status status;
> + unsigned long long hrv;
> + struct intel_soc_pmic *pmic;
> +
> + handle = ACPI_HANDLE(&pdev->dev);
> + status = acpi_evaluate_integer(handle, "_HRV", NULL, &hrv);
> + if (ACPI_FAILURE(status)) {
> + dev_err(&pdev->dev, "Failed to get PMIC hardware revision\n");
> + return -ENODEV;
> + }
> + if (hrv != BROXTON_PMIC_WC_HRV) {
> + dev_err(&pdev->dev, "Invalid PMIC hardware revision: %llu\n",
> + hrv);
> + return -ENODEV;
> + }
> +
> + pmic = devm_kzalloc(&pdev->dev, sizeof(*pmic), GFP_KERNEL);
> + if (!pmic)
> + return -ENOMEM;
> +
> + ret = platform_get_irq(pdev, 0);
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Invalid IRQ\n");
> + return ret;
> + }
> + pmic->irq = ret;
> +
> + dev_set_drvdata(&pdev->dev, pmic);
> + pmic->dev = &pdev->dev;
> +
> + pmic->regmap = devm_regmap_init(&pdev->dev, NULL, pmic,
> + &bxtwc_regmap_config);
> + if (IS_ERR(pmic->regmap)) {
> + ret = PTR_ERR(pmic->regmap);
> + dev_err(&pdev->dev, "Failed to initialise regmap: %d\n", ret);
> + return ret;
> + }
> +
> + ret = regmap_add_irq_chip(pmic->regmap, pmic->irq,
> + IRQF_ONESHOT | IRQF_SHARED,
> + 0, &bxtwc_regmap_irq_chip,
> + &pmic->irq_chip_data);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to add IRQ chip\n");
> + return ret;
> + }
> +
> + ret = regmap_add_irq_chip(pmic->regmap, pmic->irq,
> + IRQF_ONESHOT | IRQF_SHARED,
> + 0, &bxtwc_regmap_irq_chip_level2,
> + &pmic->irq_chip_data_level2);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to add secondary IRQ chip\n");
> + goto err_irq_chip_level2;
> + }
> +
> + ret = mfd_add_devices(&pdev->dev, PLATFORM_DEVID_NONE, bxt_wc_dev,
> + ARRAY_SIZE(bxt_wc_dev), NULL, 0,
> + NULL);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to add devices\n");
> + goto err_mfd;
> + }
> +
> + ret = sysfs_create_group(&pdev->dev.kobj, &bxtwc_group);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to create sysfs group %d\n", ret);
> + goto err_sysfs;
> + }
> +
> + return 0;
> +
> +err_sysfs:
> + mfd_remove_devices(&pdev->dev);
> +err_mfd:
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data_level2);
> +err_irq_chip_level2:
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data);
> +
> + return ret;
> +}
> +
> +static int bxtwc_remove(struct platform_device *pdev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(&pdev->dev);
> +
> + sysfs_remove_group(&pdev->dev.kobj, &bxtwc_group);
> + mfd_remove_devices(&pdev->dev);
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data);
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data_level2);
> +
> + return 0;
> +}
> +
> +static void bxtwc_shutdown(struct platform_device *pdev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(&pdev->dev);
> +
> + disable_irq(pmic->irq);
> +}
> +
> +#ifdef CONFIG_PM_SLEEP
> +static int bxtwc_suspend(struct device *dev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + disable_irq(pmic->irq);
> +
> + return 0;
> +}
> +
> +static int bxtwc_resume(struct device *dev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + enable_irq(pmic->irq);
> + return 0;
> +}
> +#endif
> +static SIMPLE_DEV_PM_OPS(bxtwc_pm_ops, bxtwc_suspend, bxtwc_resume);
> +
> +static const struct acpi_device_id bxtwc_acpi_ids[] = {
> + { "INT34D3", },
> + { }
> +};
> +MODULE_DEVICE_TABLE(acpi, pmic_acpi_ids);
> +
> +static struct platform_driver bxtwc_driver = {
> + .probe = bxtwc_probe,
> + .remove = bxtwc_remove,
> + .shutdown = bxtwc_shutdown,
> + .driver = {
> + .name = "BXTWC PMIC",
> + .pm = &bxtwc_pm_ops,
> + .acpi_match_table = ACPI_PTR(bxtwc_acpi_ids),
> + },
> +};
> +
> +module_platform_driver(bxtwc_driver);
> +
> +MODULE_LICENSE("GPL v2");
> +MODULE_AUTHOR("Qipeng Zha<qipeng.zha@intel.com>");
> diff --git a/include/linux/mfd/intel_bxtwc.h b/include/linux/mfd/intel_bxtwc.h
> new file mode 100644
> index 0000000..1a0ee9d
> --- /dev/null
> +++ b/include/linux/mfd/intel_bxtwc.h
> @@ -0,0 +1,69 @@
> +/*
> + * intel_bxtwc.h - Header file for Intel Broxton Whiskey Cove PMIC
> + *
> + * Copyright (C) 2015 Intel Corporation. All rights reserved.
> + *
> + * This program is free software; you can redistribute it and/or modify it
> + * under the terms and conditions of the GNU General Public License,
> + * version 2, as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope it will be useful, but WITHOUT
> + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
> + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
> + * more details.
> + */
> +
> +#include <linux/mfd/intel_soc_pmic.h>
> +
> +#ifndef __INTEL_BXTWC_H__
> +#define __INTEL_BXTWC_H__
> +
> +/* BXT WC devices */
> +#define BXTWC_DEVICE1_ADDR 0x4E
> +#define BXTWC_DEVICE2_ADDR 0x4F
> +#define BXTWC_DEVICE3_ADDR 0x5E
> +
> +/* device1 Registers */
> +#define BXTWC_CHIPID 0x4E00
> +#define BXTWC_CHIPVER 0x4E01
> +
> +#define BXTWC_SCHGRIRQ0_ADDR 0x5E1A
> +#define BXTWC_CHGRCTRL0_ADDR 0x5E16
> +#define BXTWC_CHGRCTRL1_ADDR 0x5E17
> +#define BXTWC_CHGRCTRL2_ADDR 0x5E18
> +#define BXTWC_CHGRSTATUS_ADDR 0x5E19
> +#define BXTWC_THRMBATZONE_ADDR 0x4F22
> +
> +#define BXTWC_USBPATH_ADDR 0x5E19
> +#define BXTWC_USBPHYCTRL_ADDR 0x5E07
> +#define BXTWC_USBIDCTRL_ADDR 0x5E05
> +#define BXTWC_USBIDEN_MASK 0x01
> +#define BXTWC_USBIDSTAT_ADDR 0x00FF
> +#define BXTWC_USBSRCDETSTATUS_ADDR 0x5E29
> +
> +#define BXTWC_DBGUSBBC1_ADDR 0x5FE0
> +#define BXTWC_DBGUSBBC2_ADDR 0x5FE1
> +#define BXTWC_DBGUSBBCSTAT_ADDR 0x5FE2
> +
> +#define BXTWC_WAKESRC_ADDR 0x4E22
> +#define BXTWC_WAKESRC2_ADDR 0x4EE5
> +#define BXTWC_CHRTTADDR_ADDR 0x5E22
> +#define BXTWC_CHRTTDATA_ADDR 0x5E23
> +
> +#define BXTWC_STHRMIRQ0_ADDR 0x4F19
> +#define WC_MTHRMIRQ1_ADDR 0x4E12
> +#define WC_STHRMIRQ1_ADDR 0x4F1A
> +#define WC_STHRMIRQ2_ADDR 0x4F1B
> +
> +#define BXTWC_THRMZN0H_ADDR 0x4F44
> +#define BXTWC_THRMZN0L_ADDR 0x4F45
> +#define BXTWC_THRMZN1H_ADDR 0x4F46
> +#define BXTWC_THRMZN1L_ADDR 0x4F47
> +#define BXTWC_THRMZN2H_ADDR 0x4F48
> +#define BXTWC_THRMZN2L_ADDR 0x4F49
> +#define BXTWC_THRMZN3H_ADDR 0x4F4A
> +#define BXTWC_THRMZN3L_ADDR 0x4F4B
> +#define BXTWC_THRMZN4H_ADDR 0x4F4C
> +#define BXTWC_THRMZN4L_ADDR 0x4F4D
> +
> +#endif
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 1/3] regmap: add generic macro to define regmap_irq
2015-09-14 16:39 [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Qipeng Zha
` (2 preceding siblings ...)
2015-09-19 18:22 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Mark Brown
@ 2015-09-20 4:18 ` Lee Jones
2015-09-22 22:04 ` Lee Jones
4 siblings, 0 replies; 14+ messages in thread
From: Lee Jones @ 2015-09-20 4:18 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, broonie, samuel.ortiz
On Tue, 15 Sep 2015, Qipeng Zha wrote:
> Add REGMAP_IRQ_REG macro in regmap.h to define regmap_irq
> structure easily for other driver module.
Couple of people requested this now:
Acked-by: Lee Jones <lee.jones@linaro.org>
> Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
> ---
> include/linux/regmap.h | 3 +++
> 1 file changed, 3 insertions(+)
>
> diff --git a/include/linux/regmap.h b/include/linux/regmap.h
> index 116655d..0d1ee0a 100644
> --- a/include/linux/regmap.h
> +++ b/include/linux/regmap.h
> @@ -517,6 +517,9 @@ struct regmap_irq {
> unsigned int mask;
> };
>
> +#define REGMAP_IRQ_REG(_irq, _off, _mask) \
> + [_irq] = { .reg_offset = (_off), .mask = (_mask) }
> +
> /**
> * Description of a generic regmap irq_chip. This is not intended to
> * handle every possible interrupt controller, but it should handle a
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC
2015-09-14 16:39 ` [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC Qipeng Zha
@ 2015-09-20 4:18 ` Lee Jones
2015-09-22 22:05 ` Lee Jones
1 sibling, 0 replies; 14+ messages in thread
From: Lee Jones @ 2015-09-20 4:18 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, broonie, samuel.ortiz
On Tue, 15 Sep 2015, Qipeng Zha wrote:
> IRQ control registers of Intel Broxton Whisky Cove PMIC are
> separated in two parts, so add secondary IRQ chip.
> And the new member of device will be used in PMC IPC regmap APIs.
>
> Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
> ---
> include/linux/mfd/intel_soc_pmic.h | 2 ++
> 1 file changed, 2 insertions(+)
Acked-by: Lee Jones <lee.jones@linaro.org>
> diff --git a/include/linux/mfd/intel_soc_pmic.h b/include/linux/mfd/intel_soc_pmic.h
> index abcbfcf..cf619db 100644
> --- a/include/linux/mfd/intel_soc_pmic.h
> +++ b/include/linux/mfd/intel_soc_pmic.h
> @@ -25,6 +25,8 @@ struct intel_soc_pmic {
> int irq;
> struct regmap *regmap;
> struct regmap_irq_chip_data *irq_chip_data;
> + struct regmap_irq_chip_data *irq_chip_data_level2;
> + struct device *dev;
> };
>
> #endif /* __INTEL_SOC_PMIC_H__ */
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* RE: [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver
2015-09-20 4:18 ` Lee Jones
@ 2015-09-21 1:51 ` Zha, Qipeng
0 siblings, 0 replies; 14+ messages in thread
From: Zha, Qipeng @ 2015-09-21 1:51 UTC (permalink / raw)
To: Lee Jones; +Cc: linux-kernel@vger.kernel.org, broonie@kernel.org, Ortiz, Samuel
[-- Warning: decoded text below may be mangled, UTF-8 assumed --]
[-- Attachment #1: Type: text/plain; charset="utf-8", Size: 546 bytes --]
> > ---
> > change in v6
> > Replace INIT_REGMAP_IRQ with REGMAP_IRQ_REG.
> If that's all that has changed my Ack can carry:
> Acked-by: Lee Jones <lee.jones@linaro.org>
> Still no Ack for the regmap side though, so still can't apply.
Yes, compare to V5, that's all change for V6.
Mark acked patch set 1 for regmap core change, and need to wait for that's applied, right ?
Thanks.
ÿôèº{.nÇ+·®+%Ëÿ±éݶ\x17¥wÿº{.nÇ+·¥{±þG«éÿ{ayº\x1dÊÚë,j\a¢f£¢·hïêÿêçz_è®\x03(éÝ¢j"ú\x1a¶^[m§ÿÿ¾\a«þG«éÿ¢¸?¨èÚ&£ø§~á¶iOæ¬z·vØ^\x14\x04\x1a¶^[m§ÿÿÃ\fÿ¶ìÿ¢¸?I¥
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 1/3] regmap: add generic macro to define regmap_irq
2015-09-19 18:22 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Mark Brown
@ 2015-09-22 22:04 ` Lee Jones
2015-09-23 17:58 ` Mark Brown
0 siblings, 1 reply; 14+ messages in thread
From: Lee Jones @ 2015-09-22 22:04 UTC (permalink / raw)
To: Mark Brown; +Cc: Qipeng Zha, linux-kernel, samuel.ortiz
On Sat, 19 Sep 2015, Mark Brown wrote:
> On Tue, Sep 15, 2015 at 12:39:17AM +0800, Qipeng Zha wrote:
> > Add REGMAP_IRQ_REG macro in regmap.h to define regmap_irq
> > structure easily for other driver module.
>
> Acked-by: Mark Brown <broonie@kernel.org>
Do you want a pull request for this?
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 1/3] regmap: add generic macro to define regmap_irq
2015-09-14 16:39 [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Qipeng Zha
` (3 preceding siblings ...)
2015-09-20 4:18 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Lee Jones
@ 2015-09-22 22:04 ` Lee Jones
4 siblings, 0 replies; 14+ messages in thread
From: Lee Jones @ 2015-09-22 22:04 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, broonie, samuel.ortiz
On Tue, 15 Sep 2015, Qipeng Zha wrote:
> Add REGMAP_IRQ_REG macro in regmap.h to define regmap_irq
> structure easily for other driver module.
>
> Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
> ---
> include/linux/regmap.h | 3 +++
> 1 file changed, 3 insertions(+)
Applied, thanks.
> diff --git a/include/linux/regmap.h b/include/linux/regmap.h
> index 116655d..0d1ee0a 100644
> --- a/include/linux/regmap.h
> +++ b/include/linux/regmap.h
> @@ -517,6 +517,9 @@ struct regmap_irq {
> unsigned int mask;
> };
>
> +#define REGMAP_IRQ_REG(_irq, _off, _mask) \
> + [_irq] = { .reg_offset = (_off), .mask = (_mask) }
> +
> /**
> * Description of a generic regmap irq_chip. This is not intended to
> * handle every possible interrupt controller, but it should handle a
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC
2015-09-14 16:39 ` [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC Qipeng Zha
2015-09-20 4:18 ` Lee Jones
@ 2015-09-22 22:05 ` Lee Jones
1 sibling, 0 replies; 14+ messages in thread
From: Lee Jones @ 2015-09-22 22:05 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, broonie, samuel.ortiz
On Tue, 15 Sep 2015, Qipeng Zha wrote:
> IRQ control registers of Intel Broxton Whisky Cove PMIC are
> separated in two parts, so add secondary IRQ chip.
> And the new member of device will be used in PMC IPC regmap APIs.
>
> Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
> ---
> include/linux/mfd/intel_soc_pmic.h | 2 ++
> 1 file changed, 2 insertions(+)
Applied, thanks.
> diff --git a/include/linux/mfd/intel_soc_pmic.h b/include/linux/mfd/intel_soc_pmic.h
> index abcbfcf..cf619db 100644
> --- a/include/linux/mfd/intel_soc_pmic.h
> +++ b/include/linux/mfd/intel_soc_pmic.h
> @@ -25,6 +25,8 @@ struct intel_soc_pmic {
> int irq;
> struct regmap *regmap;
> struct regmap_irq_chip_data *irq_chip_data;
> + struct regmap_irq_chip_data *irq_chip_data_level2;
> + struct device *dev;
> };
>
> #endif /* __INTEL_SOC_PMIC_H__ */
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver
2015-09-14 16:39 ` [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver Qipeng Zha
2015-09-20 4:18 ` Lee Jones
@ 2015-09-22 22:05 ` Lee Jones
1 sibling, 0 replies; 14+ messages in thread
From: Lee Jones @ 2015-09-22 22:05 UTC (permalink / raw)
To: Qipeng Zha; +Cc: linux-kernel, broonie, samuel.ortiz
On Tue, 15 Sep 2015, Qipeng Zha wrote:
> Add MFD core driver for Intel Broxton Whiskey Cove PMIC,
> which is specially accessed by hardware IPC, not a generic
> I2C device
>
> Signed-off-by: Qipeng Zha <qipeng.zha@intel.com>
>
> ---
> change in v6
> Replace INIT_REGMAP_IRQ with REGMAP_IRQ_REG.
>
> change in v5
> Fix issues in code style, espcially make error messages readable;
> Put regmap_irq macro in header file and separate into two patch;
> Use DEFFINE_RES_IRQ to define irq resource;
> Remove default_i2c_addr and use macro directly;
> Change platform driver name to make it more readable;
>
> change in v4
> Add compile dependency to PMC IPC driver in Makefile, or will
> use NULL stubs defined in PMC IPC header file;
>
> change in v3
> Implement ipc regmap r/w callback in pmic driver, since there dropped
> before patch of implement virtual ipc support in regmap core;
> Update some function's comment;
> ---
> drivers/mfd/Makefile | 1 +
> drivers/mfd/intel_soc_pmic_bxtwc.c | 478 +++++++++++++++++++++++++++++++++++++
> include/linux/mfd/intel_bxtwc.h | 69 ++++++
> 3 files changed, 548 insertions(+)
> create mode 100644 drivers/mfd/intel_soc_pmic_bxtwc.c
> create mode 100644 include/linux/mfd/intel_bxtwc.h
Applied, thanks.
> diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
> index 0e5cfeb..8fc894e 100644
> --- a/drivers/mfd/Makefile
> +++ b/drivers/mfd/Makefile
> @@ -183,5 +183,6 @@ obj-$(CONFIG_MFD_RT5033) += rt5033.o
> obj-$(CONFIG_MFD_SKY81452) += sky81452.o
>
> intel-soc-pmic-objs := intel_soc_pmic_core.o intel_soc_pmic_crc.o
> +intel-soc-pmic-$(CONFIG_INTEL_PMC_IPC) += intel_soc_pmic_bxtwc.o
> obj-$(CONFIG_INTEL_SOC_PMIC) += intel-soc-pmic.o
> obj-$(CONFIG_MFD_MT6397) += mt6397-core.o
> diff --git a/drivers/mfd/intel_soc_pmic_bxtwc.c b/drivers/mfd/intel_soc_pmic_bxtwc.c
> new file mode 100644
> index 0000000..40acaff
> --- /dev/null
> +++ b/drivers/mfd/intel_soc_pmic_bxtwc.c
> @@ -0,0 +1,478 @@
> +/*
> + * MFD core driver for Intel Broxton Whiskey Cove PMIC
> + *
> + * Copyright (C) 2015 Intel Corporation. All rights reserved.
> + *
> + * This program is free software; you can redistribute it and/or modify it
> + * under the terms and conditions of the GNU General Public License,
> + * version 2, as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope it will be useful, but WITHOUT
> + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
> + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
> + * more details.
> + */
> +
> +#include <linux/module.h>
> +#include <linux/acpi.h>
> +#include <linux/err.h>
> +#include <linux/delay.h>
> +#include <linux/interrupt.h>
> +#include <linux/kernel.h>
> +#include <linux/mfd/core.h>
> +#include <linux/mfd/intel_bxtwc.h>
> +#include <asm/intel_pmc_ipc.h>
> +
> +/* PMIC device registers */
> +#define REG_ADDR_MASK 0xFF00
> +#define REG_ADDR_SHIFT 8
> +#define REG_OFFSET_MASK 0xFF
> +
> +/* Interrupt Status Registers */
> +#define BXTWC_IRQLVL1 0x4E02
> +#define BXTWC_PWRBTNIRQ 0x4E03
> +
> +#define BXTWC_THRM0IRQ 0x4E04
> +#define BXTWC_THRM1IRQ 0x4E05
> +#define BXTWC_THRM2IRQ 0x4E06
> +#define BXTWC_BCUIRQ 0x4E07
> +#define BXTWC_ADCIRQ 0x4E08
> +#define BXTWC_CHGR0IRQ 0x4E09
> +#define BXTWC_CHGR1IRQ 0x4E0A
> +#define BXTWC_GPIOIRQ0 0x4E0B
> +#define BXTWC_GPIOIRQ1 0x4E0C
> +#define BXTWC_CRITIRQ 0x4E0D
> +
> +/* Interrupt MASK Registers */
> +#define BXTWC_MIRQLVL1 0x4E0E
> +#define BXTWC_MPWRTNIRQ 0x4E0F
> +
> +#define BXTWC_MTHRM0IRQ 0x4E12
> +#define BXTWC_MTHRM1IRQ 0x4E13
> +#define BXTWC_MTHRM2IRQ 0x4E14
> +#define BXTWC_MBCUIRQ 0x4E15
> +#define BXTWC_MADCIRQ 0x4E16
> +#define BXTWC_MCHGR0IRQ 0x4E17
> +#define BXTWC_MCHGR1IRQ 0x4E18
> +#define BXTWC_MGPIO0IRQ 0x4E19
> +#define BXTWC_MGPIO1IRQ 0x4E1A
> +#define BXTWC_MCRITIRQ 0x4E1B
> +
> +/* Whiskey Cove PMIC share same ACPI ID between different platforms */
> +#define BROXTON_PMIC_WC_HRV 4
> +
> +/* Manage in two IRQ chips since mask registers are not consecutive */
> +enum bxtwc_irqs {
> + /* Level 1 */
> + BXTWC_PWRBTN_LVL1_IRQ = 0,
> + BXTWC_TMU_LVL1_IRQ,
> + BXTWC_THRM_LVL1_IRQ,
> + BXTWC_BCU_LVL1_IRQ,
> + BXTWC_ADC_LVL1_IRQ,
> + BXTWC_CHGR_LVL1_IRQ,
> + BXTWC_GPIO_LVL1_IRQ,
> + BXTWC_CRIT_LVL1_IRQ,
> +
> + /* Level 2 */
> + BXTWC_PWRBTN_IRQ,
> +};
> +
> +enum bxtwc_irqs_level2 {
> + /* Level 2 */
> + BXTWC_THRM0_IRQ = 0,
> + BXTWC_THRM1_IRQ,
> + BXTWC_THRM2_IRQ,
> + BXTWC_BCU_IRQ,
> + BXTWC_ADC_IRQ,
> + BXTWC_CHGR0_IRQ,
> + BXTWC_CHGR1_IRQ,
> + BXTWC_GPIO0_IRQ,
> + BXTWC_GPIO1_IRQ,
> + BXTWC_CRIT_IRQ,
> +};
> +
> +static const struct regmap_irq bxtwc_regmap_irqs[] = {
> + REGMAP_IRQ_REG(BXTWC_PWRBTN_LVL1_IRQ, 0, BIT(0)),
> + REGMAP_IRQ_REG(BXTWC_TMU_LVL1_IRQ, 0, BIT(1)),
> + REGMAP_IRQ_REG(BXTWC_THRM_LVL1_IRQ, 0, BIT(2)),
> + REGMAP_IRQ_REG(BXTWC_BCU_LVL1_IRQ, 0, BIT(3)),
> + REGMAP_IRQ_REG(BXTWC_ADC_LVL1_IRQ, 0, BIT(4)),
> + REGMAP_IRQ_REG(BXTWC_CHGR_LVL1_IRQ, 0, BIT(5)),
> + REGMAP_IRQ_REG(BXTWC_GPIO_LVL1_IRQ, 0, BIT(6)),
> + REGMAP_IRQ_REG(BXTWC_CRIT_LVL1_IRQ, 0, BIT(7)),
> + REGMAP_IRQ_REG(BXTWC_PWRBTN_IRQ, 1, 0x03),
> +};
> +
> +static const struct regmap_irq bxtwc_regmap_irqs_level2[] = {
> + REGMAP_IRQ_REG(BXTWC_THRM0_IRQ, 0, 0xff),
> + REGMAP_IRQ_REG(BXTWC_THRM1_IRQ, 1, 0xbf),
> + REGMAP_IRQ_REG(BXTWC_THRM2_IRQ, 2, 0xff),
> + REGMAP_IRQ_REG(BXTWC_BCU_IRQ, 3, 0x1f),
> + REGMAP_IRQ_REG(BXTWC_ADC_IRQ, 4, 0xff),
> + REGMAP_IRQ_REG(BXTWC_CHGR0_IRQ, 5, 0x1f),
> + REGMAP_IRQ_REG(BXTWC_CHGR1_IRQ, 6, 0x1f),
> + REGMAP_IRQ_REG(BXTWC_GPIO0_IRQ, 7, 0xff),
> + REGMAP_IRQ_REG(BXTWC_GPIO1_IRQ, 8, 0x3f),
> + REGMAP_IRQ_REG(BXTWC_CRIT_IRQ, 9, 0x03),
> +};
> +
> +static struct regmap_irq_chip bxtwc_regmap_irq_chip = {
> + .name = "bxtwc_irq_chip",
> + .status_base = BXTWC_IRQLVL1,
> + .mask_base = BXTWC_MIRQLVL1,
> + .irqs = bxtwc_regmap_irqs,
> + .num_irqs = ARRAY_SIZE(bxtwc_regmap_irqs),
> + .num_regs = 2,
> +};
> +
> +static struct regmap_irq_chip bxtwc_regmap_irq_chip_level2 = {
> + .name = "bxtwc_irq_chip_level2",
> + .status_base = BXTWC_THRM0IRQ,
> + .mask_base = BXTWC_MTHRM0IRQ,
> + .irqs = bxtwc_regmap_irqs_level2,
> + .num_irqs = ARRAY_SIZE(bxtwc_regmap_irqs_level2),
> + .num_regs = 10,
> +};
> +
> +static struct resource gpio_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_GPIO0_IRQ, "GPIO0"),
> + DEFINE_RES_IRQ_NAMED(BXTWC_GPIO1_IRQ, "GPIO1"),
> +};
> +
> +static struct resource adc_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_ADC_IRQ, "ADC"),
> +};
> +
> +static struct resource charger_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_CHGR0_IRQ, "CHARGER"),
> + DEFINE_RES_IRQ_NAMED(BXTWC_CHGR1_IRQ, "CHARGER1"),
> +};
> +
> +static struct resource thermal_resources[] = {
> + DEFINE_RES_IRQ(BXTWC_THRM0_IRQ),
> + DEFINE_RES_IRQ(BXTWC_THRM1_IRQ),
> + DEFINE_RES_IRQ(BXTWC_THRM2_IRQ),
> +};
> +
> +static struct resource bcu_resources[] = {
> + DEFINE_RES_IRQ_NAMED(BXTWC_BCU_IRQ, "BCU"),
> +};
> +
> +static struct mfd_cell bxt_wc_dev[] = {
> + {
> + .name = "bxt_wcove_gpadc",
> + .num_resources = ARRAY_SIZE(adc_resources),
> + .resources = adc_resources,
> + },
> + {
> + .name = "bxt_wcove_thermal",
> + .num_resources = ARRAY_SIZE(thermal_resources),
> + .resources = thermal_resources,
> + },
> + {
> + .name = "bxt_wcove_ext_charger",
> + .num_resources = ARRAY_SIZE(charger_resources),
> + .resources = charger_resources,
> + },
> + {
> + .name = "bxt_wcove_bcu",
> + .num_resources = ARRAY_SIZE(bcu_resources),
> + .resources = bcu_resources,
> + },
> + {
> + .name = "bxt_wcove_gpio",
> + .num_resources = ARRAY_SIZE(gpio_resources),
> + .resources = gpio_resources,
> + },
> + {
> + .name = "bxt_wcove_region",
> + },
> +};
> +
> +static int regmap_ipc_byte_reg_read(void *context, unsigned int reg,
> + unsigned int *val)
> +{
> + int ret;
> + int i2c_addr;
> + u8 ipc_in[2];
> + u8 ipc_out[4];
> + struct intel_soc_pmic *pmic = context;
> +
> + if (reg & REG_ADDR_MASK)
> + i2c_addr = (reg & REG_ADDR_MASK) >> REG_ADDR_SHIFT;
> + else {
> + i2c_addr = BXTWC_DEVICE1_ADDR;
> + if (!i2c_addr) {
> + dev_err(pmic->dev, "I2C address not set\n");
> + return -EINVAL;
> + }
> + }
> + reg &= REG_OFFSET_MASK;
> +
> + ipc_in[0] = reg;
> + ipc_in[1] = i2c_addr;
> + ret = intel_pmc_ipc_command(PMC_IPC_PMIC_ACCESS,
> + PMC_IPC_PMIC_ACCESS_READ,
> + ipc_in, sizeof(ipc_in), (u32 *)ipc_out, 1);
> + if (ret) {
> + dev_err(pmic->dev, "Failed to read from PMIC\n");
> + return ret;
> + }
> + *val = ipc_out[0];
> +
> + return 0;
> +}
> +
> +static int regmap_ipc_byte_reg_write(void *context, unsigned int reg,
> + unsigned int val)
> +{
> + int ret;
> + int i2c_addr;
> + u8 ipc_in[3];
> + struct intel_soc_pmic *pmic = context;
> +
> + if (reg & REG_ADDR_MASK)
> + i2c_addr = (reg & REG_ADDR_MASK) >> REG_ADDR_SHIFT;
> + else {
> + i2c_addr = BXTWC_DEVICE1_ADDR;
> + if (!i2c_addr) {
> + dev_err(pmic->dev, "I2C address not set\n");
> + return -EINVAL;
> + }
> + }
> + reg &= REG_OFFSET_MASK;
> +
> + ipc_in[0] = reg;
> + ipc_in[1] = i2c_addr;
> + ipc_in[2] = val;
> + ret = intel_pmc_ipc_command(PMC_IPC_PMIC_ACCESS,
> + PMC_IPC_PMIC_ACCESS_WRITE,
> + ipc_in, sizeof(ipc_in), NULL, 0);
> + if (ret) {
> + dev_err(pmic->dev, "Failed to write to PMIC\n");
> + return ret;
> + }
> +
> + return 0;
> +}
> +
> +/* sysfs interfaces to r/w PMIC registers, required by initial script */
> +static unsigned long bxtwc_reg_addr;
> +static ssize_t bxtwc_reg_show(struct device *dev,
> + struct device_attribute *attr, char *buf)
> +{
> + return sprintf(buf, "0x%lx\n", bxtwc_reg_addr);
> +}
> +
> +static ssize_t bxtwc_reg_store(struct device *dev,
> + struct device_attribute *attr, const char *buf, size_t count)
> +{
> + if (kstrtoul(buf, 0, &bxtwc_reg_addr)) {
> + dev_err(dev, "Invalid register address\n");
> + return -EINVAL;
> + }
> + return (ssize_t)count;
> +}
> +
> +static ssize_t bxtwc_val_show(struct device *dev,
> + struct device_attribute *attr, char *buf)
> +{
> + int ret;
> + unsigned int val;
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + ret = regmap_read(pmic->regmap, bxtwc_reg_addr, &val);
> + if (ret < 0) {
> + dev_err(dev, "Failed to read 0x%lx\n", bxtwc_reg_addr);
> + return -EIO;
> + }
> +
> + return sprintf(buf, "0x%02x\n", val);
> +}
> +
> +static ssize_t bxtwc_val_store(struct device *dev,
> + struct device_attribute *attr, const char *buf, size_t count)
> +{
> + int ret;
> + unsigned int val;
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + if (kstrtoul(buf, 0, (unsigned long *)&val)) {
> + dev_err(dev, "Invalid register value\n");
> + return -EINVAL;
> + }
> +
> + ret = regmap_write(pmic->regmap, bxtwc_reg_addr, val);
> + if (ret) {
> + dev_err(dev, "Failed to write value 0x%02x to address 0x%lx",
> + val, bxtwc_reg_addr);
> + return -EIO;
> + }
> + return count;
> +}
> +
> +static DEVICE_ATTR(addr, S_IWUSR | S_IRUSR, bxtwc_reg_show, bxtwc_reg_store);
> +static DEVICE_ATTR(val, S_IWUSR | S_IRUSR, bxtwc_val_show, bxtwc_val_store);
> +static struct attribute *bxtwc_attrs[] = {
> + &dev_attr_addr.attr,
> + &dev_attr_val.attr,
> + NULL
> +};
> +
> +static const struct attribute_group bxtwc_group = {
> + .attrs = bxtwc_attrs,
> +};
> +
> +static const struct regmap_config bxtwc_regmap_config = {
> + .reg_bits = 16,
> + .val_bits = 8,
> + .reg_write = regmap_ipc_byte_reg_write,
> + .reg_read = regmap_ipc_byte_reg_read,
> +};
> +
> +static int bxtwc_probe(struct platform_device *pdev)
> +{
> + int ret;
> + acpi_handle handle;
> + acpi_status status;
> + unsigned long long hrv;
> + struct intel_soc_pmic *pmic;
> +
> + handle = ACPI_HANDLE(&pdev->dev);
> + status = acpi_evaluate_integer(handle, "_HRV", NULL, &hrv);
> + if (ACPI_FAILURE(status)) {
> + dev_err(&pdev->dev, "Failed to get PMIC hardware revision\n");
> + return -ENODEV;
> + }
> + if (hrv != BROXTON_PMIC_WC_HRV) {
> + dev_err(&pdev->dev, "Invalid PMIC hardware revision: %llu\n",
> + hrv);
> + return -ENODEV;
> + }
> +
> + pmic = devm_kzalloc(&pdev->dev, sizeof(*pmic), GFP_KERNEL);
> + if (!pmic)
> + return -ENOMEM;
> +
> + ret = platform_get_irq(pdev, 0);
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Invalid IRQ\n");
> + return ret;
> + }
> + pmic->irq = ret;
> +
> + dev_set_drvdata(&pdev->dev, pmic);
> + pmic->dev = &pdev->dev;
> +
> + pmic->regmap = devm_regmap_init(&pdev->dev, NULL, pmic,
> + &bxtwc_regmap_config);
> + if (IS_ERR(pmic->regmap)) {
> + ret = PTR_ERR(pmic->regmap);
> + dev_err(&pdev->dev, "Failed to initialise regmap: %d\n", ret);
> + return ret;
> + }
> +
> + ret = regmap_add_irq_chip(pmic->regmap, pmic->irq,
> + IRQF_ONESHOT | IRQF_SHARED,
> + 0, &bxtwc_regmap_irq_chip,
> + &pmic->irq_chip_data);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to add IRQ chip\n");
> + return ret;
> + }
> +
> + ret = regmap_add_irq_chip(pmic->regmap, pmic->irq,
> + IRQF_ONESHOT | IRQF_SHARED,
> + 0, &bxtwc_regmap_irq_chip_level2,
> + &pmic->irq_chip_data_level2);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to add secondary IRQ chip\n");
> + goto err_irq_chip_level2;
> + }
> +
> + ret = mfd_add_devices(&pdev->dev, PLATFORM_DEVID_NONE, bxt_wc_dev,
> + ARRAY_SIZE(bxt_wc_dev), NULL, 0,
> + NULL);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to add devices\n");
> + goto err_mfd;
> + }
> +
> + ret = sysfs_create_group(&pdev->dev.kobj, &bxtwc_group);
> + if (ret) {
> + dev_err(&pdev->dev, "Failed to create sysfs group %d\n", ret);
> + goto err_sysfs;
> + }
> +
> + return 0;
> +
> +err_sysfs:
> + mfd_remove_devices(&pdev->dev);
> +err_mfd:
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data_level2);
> +err_irq_chip_level2:
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data);
> +
> + return ret;
> +}
> +
> +static int bxtwc_remove(struct platform_device *pdev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(&pdev->dev);
> +
> + sysfs_remove_group(&pdev->dev.kobj, &bxtwc_group);
> + mfd_remove_devices(&pdev->dev);
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data);
> + regmap_del_irq_chip(pmic->irq, pmic->irq_chip_data_level2);
> +
> + return 0;
> +}
> +
> +static void bxtwc_shutdown(struct platform_device *pdev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(&pdev->dev);
> +
> + disable_irq(pmic->irq);
> +}
> +
> +#ifdef CONFIG_PM_SLEEP
> +static int bxtwc_suspend(struct device *dev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + disable_irq(pmic->irq);
> +
> + return 0;
> +}
> +
> +static int bxtwc_resume(struct device *dev)
> +{
> + struct intel_soc_pmic *pmic = dev_get_drvdata(dev);
> +
> + enable_irq(pmic->irq);
> + return 0;
> +}
> +#endif
> +static SIMPLE_DEV_PM_OPS(bxtwc_pm_ops, bxtwc_suspend, bxtwc_resume);
> +
> +static const struct acpi_device_id bxtwc_acpi_ids[] = {
> + { "INT34D3", },
> + { }
> +};
> +MODULE_DEVICE_TABLE(acpi, pmic_acpi_ids);
> +
> +static struct platform_driver bxtwc_driver = {
> + .probe = bxtwc_probe,
> + .remove = bxtwc_remove,
> + .shutdown = bxtwc_shutdown,
> + .driver = {
> + .name = "BXTWC PMIC",
> + .pm = &bxtwc_pm_ops,
> + .acpi_match_table = ACPI_PTR(bxtwc_acpi_ids),
> + },
> +};
> +
> +module_platform_driver(bxtwc_driver);
> +
> +MODULE_LICENSE("GPL v2");
> +MODULE_AUTHOR("Qipeng Zha<qipeng.zha@intel.com>");
> diff --git a/include/linux/mfd/intel_bxtwc.h b/include/linux/mfd/intel_bxtwc.h
> new file mode 100644
> index 0000000..1a0ee9d
> --- /dev/null
> +++ b/include/linux/mfd/intel_bxtwc.h
> @@ -0,0 +1,69 @@
> +/*
> + * intel_bxtwc.h - Header file for Intel Broxton Whiskey Cove PMIC
> + *
> + * Copyright (C) 2015 Intel Corporation. All rights reserved.
> + *
> + * This program is free software; you can redistribute it and/or modify it
> + * under the terms and conditions of the GNU General Public License,
> + * version 2, as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope it will be useful, but WITHOUT
> + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
> + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
> + * more details.
> + */
> +
> +#include <linux/mfd/intel_soc_pmic.h>
> +
> +#ifndef __INTEL_BXTWC_H__
> +#define __INTEL_BXTWC_H__
> +
> +/* BXT WC devices */
> +#define BXTWC_DEVICE1_ADDR 0x4E
> +#define BXTWC_DEVICE2_ADDR 0x4F
> +#define BXTWC_DEVICE3_ADDR 0x5E
> +
> +/* device1 Registers */
> +#define BXTWC_CHIPID 0x4E00
> +#define BXTWC_CHIPVER 0x4E01
> +
> +#define BXTWC_SCHGRIRQ0_ADDR 0x5E1A
> +#define BXTWC_CHGRCTRL0_ADDR 0x5E16
> +#define BXTWC_CHGRCTRL1_ADDR 0x5E17
> +#define BXTWC_CHGRCTRL2_ADDR 0x5E18
> +#define BXTWC_CHGRSTATUS_ADDR 0x5E19
> +#define BXTWC_THRMBATZONE_ADDR 0x4F22
> +
> +#define BXTWC_USBPATH_ADDR 0x5E19
> +#define BXTWC_USBPHYCTRL_ADDR 0x5E07
> +#define BXTWC_USBIDCTRL_ADDR 0x5E05
> +#define BXTWC_USBIDEN_MASK 0x01
> +#define BXTWC_USBIDSTAT_ADDR 0x00FF
> +#define BXTWC_USBSRCDETSTATUS_ADDR 0x5E29
> +
> +#define BXTWC_DBGUSBBC1_ADDR 0x5FE0
> +#define BXTWC_DBGUSBBC2_ADDR 0x5FE1
> +#define BXTWC_DBGUSBBCSTAT_ADDR 0x5FE2
> +
> +#define BXTWC_WAKESRC_ADDR 0x4E22
> +#define BXTWC_WAKESRC2_ADDR 0x4EE5
> +#define BXTWC_CHRTTADDR_ADDR 0x5E22
> +#define BXTWC_CHRTTDATA_ADDR 0x5E23
> +
> +#define BXTWC_STHRMIRQ0_ADDR 0x4F19
> +#define WC_MTHRMIRQ1_ADDR 0x4E12
> +#define WC_STHRMIRQ1_ADDR 0x4F1A
> +#define WC_STHRMIRQ2_ADDR 0x4F1B
> +
> +#define BXTWC_THRMZN0H_ADDR 0x4F44
> +#define BXTWC_THRMZN0L_ADDR 0x4F45
> +#define BXTWC_THRMZN1H_ADDR 0x4F46
> +#define BXTWC_THRMZN1L_ADDR 0x4F47
> +#define BXTWC_THRMZN2H_ADDR 0x4F48
> +#define BXTWC_THRMZN2L_ADDR 0x4F49
> +#define BXTWC_THRMZN3H_ADDR 0x4F4A
> +#define BXTWC_THRMZN3L_ADDR 0x4F4B
> +#define BXTWC_THRMZN4H_ADDR 0x4F4C
> +#define BXTWC_THRMZN4L_ADDR 0x4F4D
> +
> +#endif
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
* Re: [PATCH v6 1/3] regmap: add generic macro to define regmap_irq
2015-09-22 22:04 ` Lee Jones
@ 2015-09-23 17:58 ` Mark Brown
2015-09-24 17:20 ` [GIT PULL] mfd: Immutable branch between MFD and Regmap due for v4.3 Lee Jones
0 siblings, 1 reply; 14+ messages in thread
From: Mark Brown @ 2015-09-23 17:58 UTC (permalink / raw)
To: Lee Jones; +Cc: Qipeng Zha, linux-kernel, samuel.ortiz
[-- Attachment #1: Type: text/plain, Size: 389 bytes --]
On Tue, Sep 22, 2015 at 11:04:01PM +0100, Lee Jones wrote:
> On Sat, 19 Sep 2015, Mark Brown wrote:
> > On Tue, Sep 15, 2015 at 12:39:17AM +0800, Qipeng Zha wrote:
> > > Add REGMAP_IRQ_REG macro in regmap.h to define regmap_irq
> > > structure easily for other driver module.
> >
> > Acked-by: Mark Brown <broonie@kernel.org>
>
> Do you want a pull request for this?
Please.
[-- Attachment #2: Digital signature --]
[-- Type: application/pgp-signature, Size: 473 bytes --]
^ permalink raw reply [flat|nested] 14+ messages in thread
* [GIT PULL] mfd: Immutable branch between MFD and Regmap due for v4.3
2015-09-23 17:58 ` Mark Brown
@ 2015-09-24 17:20 ` Lee Jones
0 siblings, 0 replies; 14+ messages in thread
From: Lee Jones @ 2015-09-24 17:20 UTC (permalink / raw)
To: Mark Brown; +Cc: Qipeng Zha, linux-kernel, samuel.ortiz
Mark,
Enjoy!
The following changes since commit 1f93e4a96c9109378204c147b3eec0d0e8100fde:
Linux 4.3-rc2 (2015-09-20 14:32:34 -0700)
are available in the git repository at:
git://git.kernel.org/pub/scm/linux/kernel/git/lee/mfd.git tags/ib-mfd-regmap-v4.3
for you to fetch changes up to b4fe8ba7a310da6a2b99e3abe67c7815198cde49:
regmap: Add generic macro to define regmap_irq (2015-09-24 18:03:38 +0100)
----------------------------------------------------------------
Immutable branch between MFD and Regmap due for v4.3
----------------------------------------------------------------
Qipeng Zha (1):
regmap: Add generic macro to define regmap_irq
include/linux/regmap.h | 3 +++
1 file changed, 3 insertions(+)
--
Lee Jones
Linaro STMicroelectronics Landing Team Lead
Linaro.org │ Open source software for ARM SoCs
Follow Linaro: Facebook | Twitter | Blog
^ permalink raw reply [flat|nested] 14+ messages in thread
end of thread, other threads:[~2015-09-24 17:20 UTC | newest]
Thread overview: 14+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2015-09-14 16:39 [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Qipeng Zha
2015-09-14 16:39 ` [PATCH v6 2/3] mfd: update intel_soc_pmic structure to support Broxton WC PMIC Qipeng Zha
2015-09-20 4:18 ` Lee Jones
2015-09-22 22:05 ` Lee Jones
2015-09-14 16:39 ` [PATCH v6 3/3] mfd: add Intel Broxton Whiskey Cove PMIC driver Qipeng Zha
2015-09-20 4:18 ` Lee Jones
2015-09-21 1:51 ` Zha, Qipeng
2015-09-22 22:05 ` Lee Jones
2015-09-19 18:22 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Mark Brown
2015-09-22 22:04 ` Lee Jones
2015-09-23 17:58 ` Mark Brown
2015-09-24 17:20 ` [GIT PULL] mfd: Immutable branch between MFD and Regmap due for v4.3 Lee Jones
2015-09-20 4:18 ` [PATCH v6 1/3] regmap: add generic macro to define regmap_irq Lee Jones
2015-09-22 22:04 ` Lee Jones
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).